diff --git a/crazyflie-firmware-src/src/config/FreeRTOSConfig.h b/crazyflie-firmware-src/src/config/FreeRTOSConfig.h
new file mode 100644
index 0000000000000000000000000000000000000000..2b2910a981ceabcf35aaf2478d2971e53526f3ab
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/FreeRTOSConfig.h
@@ -0,0 +1,156 @@
+/*
+    FreeRTOS V6.0.0 - Copyright (C) 2009 Real Time Engineers Ltd.
+
+    ***************************************************************************
+    *                                                                         *
+    * If you are:                                                             *
+    *                                                                         *
+    *    + New to FreeRTOS,                                                   *
+    *    + Wanting to learn FreeRTOS or multitasking in general quickly       *
+    *    + Looking for basic training,                                        *
+    *    + Wanting to improve your FreeRTOS skills and productivity           *
+    *                                                                         *
+    * then take a look at the FreeRTOS eBook                                  *
+    *                                                                         *
+    *        "Using the FreeRTOS Real Time Kernel - a Practical Guide"        *
+    *                  http://www.FreeRTOS.org/Documentation                  *
+    *                                                                         *
+    * A pdf reference manual is also available.  Both are usually delivered   *
+    * to your inbox within 20 minutes to two hours when purchased between 8am *
+    * and 8pm GMT (although please allow up to 24 hours in case of            *
+    * exceptional circumstances).  Thank you for your support!                *
+    *                                                                         *
+    ***************************************************************************
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
+    ***NOTE*** The exception to the GPL is included to allow you to distribute
+    a combined work that includes FreeRTOS without being obliged to provide the
+    source code for proprietary components outside of the FreeRTOS kernel.
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT
+    ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+    FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+    more details. You should have received a copy of the GNU General Public
+    License and the FreeRTOS license exception along with FreeRTOS; if not it
+    can be viewed here: http://www.freertos.org/a00114.html and also obtained
+    by writing to Richard Barry, contact details for whom are available on the
+    FreeRTOS WEB site.
+
+    1 tab == 4 spaces!
+
+    http://www.FreeRTOS.org - Documentation, latest information, license and
+    contact details.
+
+    http://www.SafeRTOS.com - A version that is certified for use in safety
+    critical systems.
+
+    http://www.OpenRTOS.com - Commercial support, development, porting,
+    licensing and training services.
+*/
+
+#ifndef FREERTOS_CONFIG_H
+#define FREERTOS_CONFIG_H
+
+#include <stdint.h>
+
+#include "config.h"
+#include "cfassert.h"
+/*-----------------------------------------------------------
+ * Application specific definitions.
+ *
+ * These definitions should be adjusted for your particular hardware and
+ * application requirements.
+ *
+ * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
+ * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
+ *
+ * See http://www.freertos.org/a00110.html.
+ *----------------------------------------------------------*/
+
+#define configUSE_PREEMPTION		1
+#define configUSE_IDLE_HOOK			1
+#define configUSE_TICK_HOOK			0
+#define configCPU_CLOCK_HZ			( ( unsigned long ) FREERTOS_MCU_CLOCK_HZ )
+#define configTICK_RATE_HZ			( ( portTickType ) 1000 )
+#define configMINIMAL_STACK_SIZE	( ( unsigned short ) FREERTOS_MIN_STACK_SIZE )
+#define configTOTAL_HEAP_SIZE		( ( size_t ) ( FREERTOS_HEAP_SIZE ) )
+#define configMAX_TASK_NAME_LEN		( 10 )
+#define configUSE_16_BIT_TICKS		0
+#define configIDLE_SHOULD_YIELD		0
+#define configUSE_CO_ROUTINES 		0
+#ifdef DEBUG
+  #define configCHECK_FOR_STACK_OVERFLOW      1
+#else
+  #define configCHECK_FOR_STACK_OVERFLOW      0
+#endif
+#define configUSE_TIMERS          1
+#define configTIMER_TASK_PRIORITY 1
+#define configTIMER_QUEUE_LENGTH  20
+#define configUSE_MALLOC_FAILED_HOOK 1
+#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
+
+#define configMAX_PRIORITIES		( 6 )
+#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
+
+/* Set the following definitions to 1 to include the API function, or zero
+to exclude the API function. */
+
+#define INCLUDE_vTaskPrioritySet		1
+#define INCLUDE_uxTaskPriorityGet		1
+#define INCLUDE_vTaskDelete				1
+#define INCLUDE_vTaskCleanUpResources	1
+#define INCLUDE_vTaskSuspend			1
+#define INCLUDE_vTaskDelayUntil			1
+#define INCLUDE_vTaskDelay				1
+#define INCLUDE_uxTaskGetStackHighWaterMark 1
+
+#define configUSE_MUTEXES 1
+
+#define configKERNEL_INTERRUPT_PRIORITY     255
+//#define configMAX_SYSCALL_INTERRUPT_PRIORITY 1
+#define configMAX_SYSCALL_INTERRUPT_PRIORITY 0x5F /* equivalent to 0x05, or priority 5. */
+
+//Map the port handler to the crt0 interruptions handlers
+#define xPortPendSVHandler PendSV_Handler
+#define xPortSysTickHandler tickFreeRTOS
+#define vPortSVCHandler SVC_Handler
+
+//Milliseconds to OS Ticks
+#define M2T(X) ((unsigned int)((X)*(configTICK_RATE_HZ/1000.0)))
+#define F2T(X) ((unsigned int)((configTICK_RATE_HZ/(X))))
+
+// DEBUG SECTION
+#define configUSE_APPLICATION_TASK_TAG  1
+#define configQUEUE_REGISTRY_SIZE       10
+
+#define TASK_LED_ID_NBR         1
+#define TASK_RADIO_ID_NBR       2
+#define TASK_STABILIZER_ID_NBR  3
+#define TASK_ADC_ID_NBR         4
+#define TASK_PM_ID_NBR          5
+#define TASK_PROXIMITY_ID_NBR   6
+
+#define configASSERT( x )  if( ( x ) == 0 ) assertFail(#x, __FILE__, __LINE__ )
+
+/*
+#define traceTASK_SWITCHED_IN() \
+  { \
+    extern void debugSendTraceInfo(unsigned int taskNbr); \
+    debugSendTraceInfo((int)pxCurrentTCB->pxTaskTag); \
+  }
+*/
+
+// Queue monitoring
+#ifdef DEBUG_QUEUE_MONITOR
+    #undef traceQUEUE_SEND
+    #undef traceQUEUE_SEND_FAILED
+    #define traceQUEUE_SEND(xQueue) qm_traceQUEUE_SEND(xQueue)
+    void qm_traceQUEUE_SEND(void* xQueue);
+    #define traceQUEUE_SEND_FAILED(xQueue) qm_traceQUEUE_SEND_FAILED(xQueue)
+    void qm_traceQUEUE_SEND_FAILED(void* xQueue);
+#endif // DEBUG_QUEUE_MONITOR
+
+#endif /* FREERTOS_CONFIG_H */
diff --git a/crazyflie-firmware-src/src/config/config.h b/crazyflie-firmware-src/src/config/config.h
new file mode 100644
index 0000000000000000000000000000000000000000..5b2dab5096b0aeee4c7c08acb828f9092ffa99fb
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/config.h
@@ -0,0 +1,199 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * config.h - Main configuration file
+ *
+ * This file define the default configuration of the copter
+ * It contains two types of parameters:
+ * - The global parameters are globally defined and independent of any
+ *   compilation profile. An example of such define could be some pinout.
+ * - The profiled defines, they are parameter that can be specific to each
+ *   dev build. The vanilla build is intended to be a "customer" build without
+ *   fancy spinning debugging stuff. The developers build are anything the
+ *   developer could need to debug and run his code/crazy stuff.
+ *
+ * The golden rule for the profile is NEVER BREAK ANOTHER PROFILE. When adding a
+ * new parameter, one shall take care to modified everything necessary to
+ * preserve the behavior of the other profiles.
+ *
+ * For the flag. T_ means task. H_ means HAL module. U_ would means utils.
+ */
+
+#ifndef CONFIG_H_
+#define CONFIG_H_
+#include "nrf24l01.h"
+
+#include "trace.h"
+
+#define PROTOCOL_VERSION 2
+
+#ifdef STM32F4XX
+  #define P_NAME "Crazyflie 2.0"
+  #define QUAD_FORMATION_X
+
+  #define CONFIG_BLOCK_ADDRESS    (2048 * (64-1))
+  #define MCU_ID_ADDRESS          0x1FFF7A10
+  #define MCU_FLASH_SIZE_ADDRESS  0x1FFF7A22
+  #define FREERTOS_HEAP_SIZE      30000
+  #define FREERTOS_MIN_STACK_SIZE 150       // M4-FPU register setup is bigger so stack needs to be bigger
+  #define FREERTOS_MCU_CLOCK_HZ   168000000
+
+#else
+  #define P_NAME "Crazyflie 1.0"
+  #define CONFIG_BLOCK_ADDRESS    (1024 * (128-1))
+  #define MCU_ID_ADDRESS          0x1FFFF7E8
+  #define MCU_FLASH_SIZE_ADDRESS  0x1FFFF7E0
+  #define FREERTOS_HEAP_SIZE      14000
+  #define FREERTOS_MIN_STACK_SIZE 100
+  #define FREERTOS_MCU_CLOCK_HZ   72000000
+#endif
+
+
+// Task priorities. Higher number higher priority
+#define STABILIZER_TASK_PRI     4
+#define SENSORS_TASK_PRI        4
+#define ADC_TASK_PRI            3
+#define SYSTEM_TASK_PRI         2
+#define CRTP_TX_TASK_PRI        2
+#define CRTP_RX_TASK_PRI        2
+#define EXTRX_TASK_PRI          2
+#define LOG_TASK_PRI            1
+#define MEM_TASK_PRI            1
+#define PARAM_TASK_PRI          1
+#define PROXIMITY_TASK_PRI      0
+#define PM_TASK_PRI             0
+
+#ifdef PLATFORM_CF2
+  #define SYSLINK_TASK_PRI        5
+  #define USBLINK_TASK_PRI        3
+#endif
+
+#ifdef PLATFORM_CF1
+  #define NRF24LINK_TASK_PRI      2
+  #define ESKYLINK_TASK_PRI       1
+  #define UART_RX_TASK_PRI        2
+#endif
+
+// Not compiled
+#if 0
+  #define INFO_TASK_PRI           2
+  #define PID_CTRL_TASK_PRI       2
+#endif
+
+
+// Task names
+#define SYSTEM_TASK_NAME        "SYSTEM"
+#define ADC_TASK_NAME           "ADC"
+#define PM_TASK_NAME            "PWRMGNT"
+#define CRTP_TX_TASK_NAME       "CRTP-TX"
+#define CRTP_RX_TASK_NAME       "CRTP-RX"
+#define CRTP_RXTX_TASK_NAME     "CRTP-RXTX"
+#define LOG_TASK_NAME           "LOG"
+#define MEM_TASK_NAME           "MEM"
+#define PARAM_TASK_NAME         "PARAM"
+#define SENSORS_TASK_NAME       "SENSORS"
+#define STABILIZER_TASK_NAME    "STABILIZER"
+#define NRF24LINK_TASK_NAME     "NRF24LINK"
+#define ESKYLINK_TASK_NAME      "ESKYLINK"
+#define SYSLINK_TASK_NAME       "SYSLINK"
+#define USBLINK_TASK_NAME       "USBLINK"
+#define PROXIMITY_TASK_NAME     "PROXIMITY"
+#define EXTRX_TASK_NAME         "EXTRX"
+#define UART_RX_TASK_NAME       "UART"
+
+//Task stack sizes
+#define SYSTEM_TASK_STACKSIZE         (2* configMINIMAL_STACK_SIZE)
+#define ADC_TASK_STACKSIZE            configMINIMAL_STACK_SIZE
+#define PM_TASK_STACKSIZE             configMINIMAL_STACK_SIZE
+#define CRTP_TX_TASK_STACKSIZE        configMINIMAL_STACK_SIZE
+#define CRTP_RX_TASK_STACKSIZE        configMINIMAL_STACK_SIZE
+#define CRTP_RXTX_TASK_STACKSIZE      configMINIMAL_STACK_SIZE
+#define LOG_TASK_STACKSIZE            configMINIMAL_STACK_SIZE
+#define MEM_TASK_STACKSIZE            configMINIMAL_STACK_SIZE
+#define PARAM_TASK_STACKSIZE          configMINIMAL_STACK_SIZE
+#define SENSORS_TASK_STACKSIZE        configMINIMAL_STACK_SIZE
+#define STABILIZER_TASK_STACKSIZE     (3 * configMINIMAL_STACK_SIZE)
+#define NRF24LINK_TASK_STACKSIZE      configMINIMAL_STACK_SIZE
+#define ESKYLINK_TASK_STACKSIZE       configMINIMAL_STACK_SIZE
+#define SYSLINK_TASK_STACKSIZE        configMINIMAL_STACK_SIZE
+#define USBLINK_TASK_STACKSIZE        configMINIMAL_STACK_SIZE
+#define PROXIMITY_TASK_STACKSIZE      configMINIMAL_STACK_SIZE
+#define EXTRX_TASK_STACKSIZE          configMINIMAL_STACK_SIZE
+#define UART_RX_TASK_STACKSIZE        configMINIMAL_STACK_SIZE
+
+//The radio channel. From 0 to 125
+#define RADIO_CHANNEL 80
+#define RADIO_DATARATE RADIO_RATE_250K
+#define RADIO_ADDRESS 0xE7E7E7E7E7ULL
+
+/**
+ * \def ACTIVATE_AUTO_SHUTDOWN
+ * Will automatically shot of system if no radio activity
+ */
+//#define ACTIVATE_AUTO_SHUTDOWN
+
+/**
+ * \def ACTIVATE_STARTUP_SOUND
+ * Playes a startup melody using the motors and PWM modulation
+ */
+#define ACTIVATE_STARTUP_SOUND
+
+// Define to force initialization of expansion board drivers. For test-rig and programming.
+//#define FORCE_EXP_DETECT
+
+/**
+ * \def PRINT_OS_DEBUG_INFO
+ * Print with an interval information about freertos mem/stack usage to console.
+ */
+//#define PRINT_OS_DEBUG_INFO
+
+
+//Debug defines
+//#define BRUSHLESS_MOTORCONTROLLER
+//#define ADC_OUTPUT_RAW_DATA
+//#define UART_OUTPUT_TRACE_DATA
+//#define UART_OUTPUT_RAW_DATA_ONLY
+//#define IMU_OUTPUT_RAW_DATA_ON_UART
+//#define T_LAUCH_MOTORS
+//#define T_LAUCH_MOTOR_TEST
+//#define MOTOR_RAMPUP_TEST
+/**
+ * \def ADC_OUTPUT_RAW_DATA
+ * When defined the gyro data will be written to the UART channel.
+ * The UART must be configured to run really fast, e.g. in 2Mb/s.
+ */
+//#define ADC_OUTPUT_RAW_DATA
+
+#if defined(UART_OUTPUT_TRACE_DATA) && defined(ADC_OUTPUT_RAW_DATA)
+#  error "Can't define UART_OUTPUT_TRACE_DATA and ADC_OUTPUT_RAW_DATA at the same time"
+#endif
+
+#if defined(UART_OUTPUT_TRACE_DATA) || defined(ADC_OUTPUT_RAW_DATA) || defined(IMU_OUTPUT_RAW_DATA_ON_UART)
+#define UART_OUTPUT_RAW_DATA_ONLY
+#endif
+
+#if defined(UART_OUTPUT_TRACE_DATA) && defined(T_LAUNCH_ACC)
+#  error "UART_OUTPUT_TRACE_DATA and T_LAUNCH_ACC doesn't work at the same time yet due to dma sharing..."
+#endif
+
+#endif /* CONFIG_H_ */
diff --git a/crazyflie-firmware-src/src/config/ffconf.h b/crazyflie-firmware-src/src/config/ffconf.h
new file mode 100644
index 0000000000000000000000000000000000000000..7d239742d8c5342dde204545f1d05ab516f819b1
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/ffconf.h
@@ -0,0 +1,267 @@
+/*---------------------------------------------------------------------------/
+/  FatFs - FAT file system module configuration file
+/---------------------------------------------------------------------------*/
+
+#define _FFCONF 68020	/* Revision ID */
+
+/*---------------------------------------------------------------------------/
+/ Function Configurations
+/---------------------------------------------------------------------------*/
+
+#define _FS_READONLY	0
+/* This option switches read-only configuration. (0:Read/Write or 1:Read-only)
+/  Read-only configuration removes writing API functions, f_write(), f_sync(),
+/  f_unlink(), f_mkdir(), f_chmod(), f_rename(), f_truncate(), f_getfree()
+/  and optional writing functions as well. */
+
+
+#define _FS_MINIMIZE	0
+/* This option defines minimization level to remove some basic API functions.
+/
+/   0: All basic functions are enabled.
+/   1: f_stat(), f_getfree(), f_unlink(), f_mkdir(), f_truncate() and f_rename()
+/      are removed.
+/   2: f_opendir(), f_readdir() and f_closedir() are removed in addition to 1.
+/   3: f_lseek() function is removed in addition to 2. */
+
+
+#define	_USE_STRFUNC	2
+/* This option switches string functions, f_gets(), f_putc(), f_puts() and
+/  f_printf().
+/
+/  0: Disable string functions.
+/  1: Enable without LF-CRLF conversion.
+/  2: Enable with LF-CRLF conversion. */
+
+
+#define _USE_FIND		1
+/* This option switches filtered directory read feature and related functions,
+/  f_findfirst() and f_findnext(). (0:Disable or 1:Enable) */
+
+
+#define	_USE_MKFS		1
+/* This option switches f_mkfs() function. (0:Disable or 1:Enable) */
+
+
+#define	_USE_FASTSEEK	0
+/* This option switches fast seek function. (0:Disable or 1:Enable) */
+
+
+#define	_USE_EXPAND		0
+/* This option switches f_expand function. (0:Disable or 1:Enable) */
+
+
+#define _USE_CHMOD		0
+/* This option switches attribute manipulation functions, f_chmod() and f_utime().
+/  (0:Disable or 1:Enable) Also _FS_READONLY needs to be 0 to enable this option. */
+
+
+#define _USE_LABEL		1
+/* This option switches volume label functions, f_getlabel() and f_setlabel().
+/  (0:Disable or 1:Enable) */
+
+
+#define	_USE_FORWARD	1
+/* This option switches f_forward() function. (0:Disable or 1:Enable) */
+
+
+/*---------------------------------------------------------------------------/
+/ Locale and Namespace Configurations
+/---------------------------------------------------------------------------*/
+
+#define _CODE_PAGE	850
+/* This option specifies the OEM code page to be used on the target system.
+/  Incorrect setting of the code page can cause a file open failure.
+/
+/   1   - ASCII (No extended character. Non-LFN cfg. only)
+/   437 - U.S.
+/   720 - Arabic
+/   737 - Greek
+/   771 - KBL
+/   775 - Baltic
+/   850 - Latin 1
+/   852 - Latin 2
+/   855 - Cyrillic
+/   857 - Turkish
+/   860 - Portuguese
+/   861 - Icelandic
+/   862 - Hebrew
+/   863 - Canadian French
+/   864 - Arabic
+/   865 - Nordic
+/   866 - Russian
+/   869 - Greek 2
+/   932 - Japanese (DBCS)
+/   936 - Simplified Chinese (DBCS)
+/   949 - Korean (DBCS)
+/   950 - Traditional Chinese (DBCS)
+*/
+
+
+#define	_USE_LFN	3
+#define	_MAX_LFN	255
+/* The _USE_LFN switches the support of long file name (LFN).
+/
+/   0: Disable support of LFN. _MAX_LFN has no effect.
+/   1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe.
+/   2: Enable LFN with dynamic working buffer on the STACK.
+/   3: Enable LFN with dynamic working buffer on the HEAP.
+/
+/  To enable the LFN, Unicode handling functions (option/unicode.c) must be added
+/  to the project. The working buffer occupies (_MAX_LFN + 1) * 2 bytes and
+/  additional 608 bytes at exFAT enabled. _MAX_LFN can be in range from 12 to 255.
+/  It should be set 255 to support full featured LFN operations.
+/  When use stack for the working buffer, take care on stack overflow. When use heap
+/  memory for the working buffer, memory management functions, ff_memalloc() and
+/  ff_memfree(), must be added to the project. */
+
+
+#define	_LFN_UNICODE	0
+/* This option switches character encoding on the API. (0:ANSI/OEM or 1:UTF-16)
+/  To use Unicode string for the path name, enable LFN and set _LFN_UNICODE = 1.
+/  This option also affects behavior of string I/O functions. */
+
+
+#define _STRF_ENCODE	3
+/* When _LFN_UNICODE == 1, this option selects the character encoding ON THE FILE to
+/  be read/written via string I/O functions, f_gets(), f_putc(), f_puts and f_printf().
+/
+/  0: ANSI/OEM
+/  1: UTF-16LE
+/  2: UTF-16BE
+/  3: UTF-8
+/
+/  This option has no effect when _LFN_UNICODE == 0. */
+
+
+#define _FS_RPATH	2
+/* This option configures support of relative path.
+/
+/   0: Disable relative path and remove related functions.
+/   1: Enable relative path. f_chdir() and f_chdrive() are available.
+/   2: f_getcwd() function is available in addition to 1.
+*/
+
+
+/*---------------------------------------------------------------------------/
+/ Drive/Volume Configurations
+/---------------------------------------------------------------------------*/
+
+#define _VOLUMES	1
+/* Number of volumes (logical drives) to be used. */
+
+
+#define _STR_VOLUME_ID	1
+#define _VOLUME_STRS	"SD"
+/* _STR_VOLUME_ID switches string support of volume ID.
+/  When _STR_VOLUME_ID is set to 1, also pre-defined strings can be used as drive
+/  number in the path name. _VOLUME_STRS defines the drive ID strings for each
+/  logical drives. Number of items must be equal to _VOLUMES. Valid characters for
+/  the drive ID strings are: A-Z and 0-9. */
+
+
+#define	_MULTI_PARTITION	0
+/* This option switches support of multi-partition on a physical drive.
+/  By default (0), each logical drive number is bound to the same physical drive
+/  number and only an FAT volume found on the physical drive will be mounted.
+/  When multi-partition is enabled (1), each logical drive number can be bound to
+/  arbitrary physical drive and partition listed in the VolToPart[]. Also f_fdisk()
+/  funciton will be available. */
+
+
+#define	_MIN_SS		512
+#define	_MAX_SS		512
+/* These options configure the range of sector size to be supported. (512, 1024,
+/  2048 or 4096) Always set both 512 for most systems, all type of memory cards and
+/  harddisk. But a larger value may be required for on-board flash memory and some
+/  type of optical media. When _MAX_SS is larger than _MIN_SS, FatFs is configured
+/  to variable sector size and GET_SECTOR_SIZE command must be implemented to the
+/  disk_ioctl() function. */
+
+
+#define	_USE_TRIM	0
+/* This option switches support of ATA-TRIM. (0:Disable or 1:Enable)
+/  To enable Trim function, also CTRL_TRIM command should be implemented to the
+/  disk_ioctl() function. */
+
+
+#define _FS_NOFSINFO	0
+/* If you need to know correct free space on the FAT32 volume, set bit 0 of this
+/  option, and f_getfree() function at first time after volume mount will force
+/  a full FAT scan. Bit 1 controls the use of last allocated cluster number.
+/
+/  bit0=0: Use free cluster count in the FSINFO if available.
+/  bit0=1: Do not trust free cluster count in the FSINFO.
+/  bit1=0: Use last allocated cluster number in the FSINFO if available.
+/  bit1=1: Do not trust last allocated cluster number in the FSINFO.
+*/
+
+
+
+/*---------------------------------------------------------------------------/
+/ System Configurations
+/---------------------------------------------------------------------------*/
+
+#define	_FS_TINY	0
+/* This option switches tiny buffer configuration. (0:Normal or 1:Tiny)
+/  At the tiny configuration, size of file object (FIL) is reduced _MAX_SS bytes.
+/  Instead of private sector buffer eliminated from the file object, common sector
+/  buffer in the file system object (FATFS) is used for the file data transfer. */
+
+
+#define _FS_EXFAT	0
+/* This option switches support of exFAT file system. (0:Disable or 1:Enable)
+/  When enable exFAT, also LFN needs to be enabled. (_USE_LFN >= 1)
+/  Note that enabling exFAT discards C89 compatibility. */
+
+
+#define _FS_NORTC	0
+#define _NORTC_MON	2
+#define _NORTC_MDAY	1
+#define _NORTC_YEAR	2016
+/* The option _FS_NORTC switches timestamp functiton. If the system does not have
+/  any RTC function or valid timestamp is not needed, set _FS_NORTC = 1 to disable
+/  the timestamp function. All objects modified by FatFs will have a fixed timestamp
+/  defined by _NORTC_MON, _NORTC_MDAY and _NORTC_YEAR in local time.
+/  To enable timestamp function (_FS_NORTC = 0), get_fattime() function need to be
+/  added to the project to get current time form real-time clock. _NORTC_MON,
+/  _NORTC_MDAY and _NORTC_YEAR have no effect. 
+/  These options have no effect at read-only configuration (_FS_READONLY = 1). */
+
+
+#define	_FS_LOCK	0
+/* The option _FS_LOCK switches file lock function to control duplicated file open
+/  and illegal operation to open objects. This option must be 0 when _FS_READONLY
+/  is 1.
+/
+/  0:  Disable file lock function. To avoid volume corruption, application program
+/      should avoid illegal open, remove and rename to the open objects.
+/  >0: Enable file lock function. The value defines how many files/sub-directories
+/      can be opened simultaneously under file lock control. Note that the file
+/      lock control is independent of re-entrancy. */
+
+
+#define _FS_REENTRANT	0
+#define _FS_TIMEOUT		1000
+#define	_SYNC_t			HANDLE
+/* The option _FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs
+/  module itself. Note that regardless of this option, file access to different
+/  volume is always re-entrant and volume control functions, f_mount(), f_mkfs()
+/  and f_fdisk() function, are always not re-entrant. Only file/directory access
+/  to the same volume is under control of this function.
+/
+/   0: Disable re-entrancy. _FS_TIMEOUT and _SYNC_t have no effect.
+/   1: Enable re-entrancy. Also user provided synchronization handlers,
+/      ff_req_grant(), ff_rel_grant(), ff_del_syncobj() and ff_cre_syncobj()
+/      function, must be added to the project. Samples are available in
+/      option/syscall.c.
+/
+/  The _FS_TIMEOUT defines timeout period in unit of time tick.
+/  The _SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*,
+/  SemaphoreHandle_t and etc.. A header file for O/S definitions needs to be
+/  included somewhere in the scope of ff.h. */
+
+/* #include <windows.h>	// O/S definitions  */
+
+
+/*--- End of configuration options ---*/
diff --git a/crazyflie-firmware-src/src/config/nvicconf.h b/crazyflie-firmware-src/src/config/nvicconf.h
new file mode 100644
index 0000000000000000000000000000000000000000..c7d50edc751a3009772116c100c61efefde6fa49
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/nvicconf.h
@@ -0,0 +1,98 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nvicconf.c - Interrupt priority configuration
+ *
+ * The STM32 has 16 priorities to choose from where 0 is the
+ * highest priority. They are now configured using no groups.
+ *
+ * Interrupt functions that call FreeRTOS FromISR functions
+ * must have a interrupt number 10 and above which is currently
+ * set by configMAX_SYSCALL_INTERRUPT_PRIORITY.
+ */
+#ifndef NVIC_CONF_H_
+#define NVIC_CONF_H_
+
+/*
+ Interrupt priority organisation in Crazyflie:
+
+ In Cortex-M low priority number is higher priority. Hence priority 0 is the
+ highest priority interrupt and priority 15 the lowest (STM32 implements
+ 4 priority bits)
+
+ Interrupts bellow MAX_SYSCALL_INTERRUPT_PRIORITY cannot call any RTOS
+ functions! They should be handled like some kind of softdevice, running above
+ the OS.
+
+ 3 Interrupt level are defined
+  - NVIC_LOW_PRI
+  - NVIC_MID_PRI
+  - NVIC_HIGH_PRI
+ The aim is to simplify interrupt handling and to document why any special case
+ is required.
+
+ 15 -
+ 14 -
+ 13 - NVIC_LOW_PRI
+ 12 - NVIC_ADC_PRI
+ 11 - NVIC_RADIO_PRI
+ 10 - NVIC_MID_PRI
+  9 -
+  8 -
+  7 - NVIC_HIGH_PRI
+  6 -
+  5 -                                     <-- MAX_SYSCALL_INTERRUPT_PRIORITY
+  4 ! NVIC_I2C_PRI_LOW NVIC_TRACE_TIM_PRI --- Does not call any RTOS function
+  3 ! NVIC_I2C_PRI_HIGH
+  2 !
+  1 !
+  0 !
+*/
+
+// Standard interrupt levels
+#define NVIC_LOW_PRI  13
+#define NVIC_MID_PRI  10
+#define NVIC_HIGH_PRI 7
+
+// Priorities used for Crazyflie
+#define NVIC_I2C_HIGH_PRI    3
+#define NVIC_I2C_LOW_PRI      4
+#define NVIC_TRACE_TIM_PRI    4
+#define NVIC_UART_PRI         6
+
+// Priorities for Crazyflie 2.0
+#define NVIC_RADIO_PRI        11
+#define NVIC_ADC_PRI          12
+#define NVIC_CPPM_PRI         14
+#define NVIC_SYSLINK_PRI      5
+
+// Priorities for external interrupts
+#define EXTI0_PRI NVIC_LOW_PRI
+#define EXTI1_PRI NVIC_LOW_PRI
+#define EXTI2_PRI NVIC_LOW_PRI
+#define EXTI3_PRI NVIC_LOW_PRI
+#define EXTI4_PRI NVIC_SYSLINK_PRI // this serves the syslink UART
+#define EXTI9_5_PRI NVIC_LOW_PRI
+#define EXTI15_10_PRI NVIC_MID_PRI // this serves the decks and sensors
+
+#endif /* NVIC_CONF_H_ */
diff --git a/crazyflie-firmware-src/src/config/stm32f10x_conf.h b/crazyflie-firmware-src/src/config/stm32f10x_conf.h
new file mode 100644
index 0000000000000000000000000000000000000000..6c1e8befcc0f8800530ef22405d044dba02bc669
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/stm32f10x_conf.h
@@ -0,0 +1,76 @@
+/**
+  ******************************************************************************
+  * @file    Project/Template/stm32f10x_conf.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   Library configuration file.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CONF_H
+#define __STM32F10x_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Uncomment the line below to enable peripheral header file inclusion */
+#include "stm32f10x_adc.h"
+/* #include "stm32f10x_bkp.h" */
+/* #include "stm32f10x_can.h" */
+/* #include "stm32f10x_crc.h" */
+/* #include "stm32f10x_dac.h" */
+#include "stm32f10x_dbgmcu.h"
+#include "stm32f10x_dma.h"
+#include "stm32f10x_exti.h"
+#include "stm32f10x_flash.h"
+/* #include "stm32f10x_fsmc.h" */
+#include "stm32f10x_gpio.h"
+#include "stm32f10x_i2c.h"
+#include "stm32f10x_iwdg.h"
+/* #include "stm32f10x_pwr.h" */
+#include "stm32f10x_rcc.h"
+/* #include "stm32f10x_rtc.h" */
+/* #include "stm32f10x_sdio.h" */
+#include "stm32f10x_spi.h"
+#include "stm32f10x_tim.h"
+#include "stm32f10x_usart.h"
+/* #include "stm32f10x_wwdg.h" */
+#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Uncomment the line below to expanse the "assert_param" macro in the
+   Standard Peripheral Library drivers code */
+/* #define USE_FULL_ASSERT    1 */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef  USE_FULL_ASSERT
+
+/**
+  * @brief  The assert_param macro is used for function's parameters check.
+  * @param  expr: If expr is false, it calls assert_failed function
+  *   which reports the name of the source file and the source
+  *   line number of the call that failed.
+  *   If expr is true, it returns no value.
+  * @retval None
+  */
+  #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+  void assert_failed(uint8_t* file, uint32_t line);
+#else
+  #define assert_param(expr) ((void)0)
+#endif /* USE_FULL_ASSERT */
+
+#endif /* __STM32F10x_CONF_H */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/config/stm32f4xx_conf.h b/crazyflie-firmware-src/src/config/stm32f4xx_conf.h
new file mode 100644
index 0000000000000000000000000000000000000000..3d1524d03af3a770ee5a64183b5f23a05897db17
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/stm32f4xx_conf.h
@@ -0,0 +1,122 @@
+/**
+  ******************************************************************************
+  * @file    Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_conf.h  
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    13-November-2013
+  * @brief   Library configuration file.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_CONF_H
+#define __STM32F4xx_CONF_H
+
+/* Includes ------------------------------------------------------------------*/
+/* Uncomment the line below to enable peripheral header file inclusion */
+#include "stm32f4xx_adc.h"
+#include "stm32f4xx_crc.h"
+#include "stm32f4xx_dbgmcu.h"
+#include "stm32f4xx_dma.h"
+#include "stm32f4xx_exti.h"
+#include "stm32f4xx_flash.h"
+#include "stm32f4xx_gpio.h"
+#include "stm32f4xx_i2c.h"
+#include "stm32f4xx_iwdg.h"
+#include "stm32f4xx_pwr.h"
+#include "stm32f4xx_rcc.h"
+#include "stm32f4xx_rtc.h"
+#include "stm32f4xx_sdio.h"
+#include "stm32f4xx_spi.h"
+#include "stm32f4xx_syscfg.h"
+#include "stm32f4xx_tim.h"
+#include "stm32f4xx_usart.h"
+#include "stm32f4xx_wwdg.h"
+#include "stm32f4xx_misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
+
+#if defined (STM32F429_439xx)
+#include "stm32f4xx_cryp.h"
+#include "stm32f4xx_hash.h"
+#include "stm32f4xx_rng.h"
+#include "stm32f4xx_can.h"
+#include "stm32f4xx_dac.h"
+#include "stm32f4xx_dcmi.h"
+#include "stm32f4xx_dma2d.h"
+#include "stm32f4xx_fmc.h"
+#include "stm32f4xx_ltdc.h"
+#include "stm32f4xx_sai.h"
+#endif /* STM32F429_439xx */
+
+#if defined (STM32F427_437xx)
+#include "stm32f4xx_cryp.h"
+#include "stm32f4xx_hash.h"
+#include "stm32f4xx_rng.h"
+#include "stm32f4xx_can.h"
+#include "stm32f4xx_dac.h"
+#include "stm32f4xx_dcmi.h"
+#include "stm32f4xx_dma2d.h"
+#include "stm32f4xx_fmc.h"
+#include "stm32f4xx_sai.h"
+#endif /* STM32F427_437xx */
+
+#if defined (STM32F40_41xxx)
+#include "stm32f4xx_cryp.h"
+#include "stm32f4xx_hash.h"
+#include "stm32f4xx_rng.h"
+#include "stm32f4xx_can.h"
+#include "stm32f4xx_dac.h"
+#include "stm32f4xx_dcmi.h"
+#include "stm32f4xx_fsmc.h"
+#endif /* STM32F40_41xxx */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* If an external clock source is used, then the value of the following define 
+   should be set to the value of the external clock source, else, if no external 
+   clock is used, keep this define commented */
+/*#define I2S_EXTERNAL_CLOCK_VAL   12288000 */ /* Value of the external clock in Hz */
+
+
+/* Uncomment the line below to expanse the "assert_param" macro in the 
+   Standard Peripheral Library drivers code */
+/* #define USE_FULL_ASSERT    1 */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef  USE_FULL_ASSERT
+
+/**
+  * @brief  The assert_param macro is used for function's parameters check.
+  * @param  expr: If expr is false, it calls assert_failed function
+  *   which reports the name of the source file and the source
+  *   line number of the call that failed. 
+  *   If expr is true, it returns no value.
+  * @retval None
+  */
+  #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+  void assert_failed(uint8_t* file, uint32_t line);
+#else
+  #define assert_param(expr) ((void)0)
+#endif /* USE_FULL_ASSERT */
+
+#endif /* __STM32F4xx_CONF_H */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/config/stm32fxxx.h b/crazyflie-firmware-src/src/config/stm32fxxx.h
new file mode 100644
index 0000000000000000000000000000000000000000..8aa3e8ad6813a8c6a5df7530c0245d4e0ade574b
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/stm32fxxx.h
@@ -0,0 +1,38 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * stm32fxxx.h - Includes correct stm32 include file.
+ */
+
+#ifndef STM32FXXX_H_
+#define STM32FXXX_H_
+
+#if defined (STM32F40_41xxx)
+  #include "stm32f4xx.h"
+#elif defined (STM32F10X_MD)
+  #include "stm32f10x.h"
+#else
+  #warning "Don't know which stm32fxxx header file to include"
+#endif
+
+#endif /* STM32FXXX_H_ */
diff --git a/crazyflie-firmware-src/src/config/trace.h b/crazyflie-firmware-src/src/config/trace.h
new file mode 100644
index 0000000000000000000000000000000000000000..65fa9ffb246992ad3d21b8c1e69269794b2aa39a
--- /dev/null
+++ b/crazyflie-firmware-src/src/config/trace.h
@@ -0,0 +1,57 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * trace.h - ITM trace implementation/definition
+ */
+
+#ifndef __TRACE_H__
+#define __TRACE_H__
+
+#define configUSE_TRACE_FACILITY	1
+
+// ITM useful macros
+#ifndef ITM_NO_OVERFLOW
+#define ITM_SEND(CH, DATA) ((uint32_t*)0xE0000000)[CH] = DATA
+#else
+#define ITM_SEND(CH, DATA) while(((uint32_t*)0xE0000000)[CH] == 0);\
+                           ((uint32_t*)0xE0000000)[CH] = DATA
+#endif
+
+// Send 4 first chatacters of task name to ITM port 1
+#define traceTASK_SWITCHED_IN() ITM_SEND(1, *((uint32_t*)pxCurrentTCB->pcTaskName))
+
+// Systick value on port 2
+#define traceTASK_INCREMENT_TICK(xTickCount) ITM_SEND(2, xTickCount)
+
+// Queue trace on port 3
+#define ITM_QUEUE_SEND 0x0100
+#define ITM_QUEUE_FAILED 0x0200
+#define ITM_BLOCKING_ON_QUEUE_RECEIVE 0x0300
+#define ITM_BLOCKING_ON_QUEUE_SEND 0x0400
+
+#define traceQUEUE_SEND(xQueue) ITM_SEND(3, ITM_QUEUE_SEND | ((xQUEUE *) xQueue)->uxQueueNumber)
+#define traceQUEUE_SEND_FAILED(xQueue) ITM_SEND(3, ITM_QUEUE_FAILED | ((xQUEUE *) xQueue)->uxQueueNumber)
+#define traceBLOCKING_ON_QUEUE_RECEIVE(xQueue) ITM_SEND(3, ITM_BLOCKING_ON_QUEUE_RECEIVE | ((xQUEUE *) xQueue)->uxQueueNumber)
+#define traceBLOCKING_ON_QUEUE_SEND(xQueue) ITM_SEND(3, ITM_BLOCKING_ON_QUEUE_SEND | ((xQUEUE *) xQueue)->uxQueueNumber)
+
+#endif
diff --git a/crazyflie-firmware-src/src/deck/api/deck_analog.c b/crazyflie-firmware-src/src/deck/api/deck_analog.c
new file mode 100644
index 0000000000000000000000000000000000000000..776bcd342d52639855892cb60ab77d1d25ac57bf
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/api/deck_analog.c
@@ -0,0 +1,154 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_analog.c - Arduino-compatible analog input implementation
+ */
+
+#include "deck.h"
+
+#include "stm32fxxx.h"
+
+static  uint32_t  stregResolution;
+static  uint32_t  adcRange;
+
+void adcInit(void)
+{
+  /*
+   * Note: This function initializes only ADC2, and only for single channel, single conversion mode. No DMA, no interrupts, no bells or whistles.
+   */
+
+  /* Note that this de-initializes registers for all ADCs (ADCx) */
+  ADC_DeInit();
+
+  /* Define ADC init structures */
+  ADC_InitTypeDef       ADC_InitStructure;
+  ADC_CommonInitTypeDef ADC_CommonInitStructure;
+
+  /* Populates structures with reset values */
+  ADC_StructInit(&ADC_InitStructure);
+  ADC_CommonStructInit(&ADC_CommonInitStructure);
+
+  /* enable ADC clock */
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC2, ENABLE);
+
+  /* init ADCs in independent mode, div clock by two */
+  ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
+  ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div2; /* HCLK = 168MHz, PCLK2 = 84MHz, ADCCLK = 42MHz (when using ADC_Prescaler_Div2) */
+  ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
+  ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
+  ADC_CommonInit(&ADC_CommonInitStructure);
+
+  /* Init ADC2: 12bit, single-conversion. For Arduino compatibility set 10bit */
+  analogReadResolution(12);
+
+  /* Enable ADC2 */
+  ADC_Cmd(ADC2, ENABLE);
+}
+
+static uint16_t analogReadChannel(uint8_t channel)
+{
+  /* According to datasheet, minimum sampling time for 12-bit conversion is 15 cycles. */
+  ADC_RegularChannelConfig(ADC2, channel, 1, ADC_SampleTime_15Cycles);
+
+  /* Start the conversion */
+  ADC_SoftwareStartConv(ADC2);
+
+  /* Wait until conversion completion */
+  while(ADC_GetFlagStatus(ADC2, ADC_FLAG_EOC) == RESET);
+
+  /* Get the conversion value */
+  return ADC_GetConversionValue(ADC2);
+}
+
+uint16_t analogRead(uint32_t pin)
+{
+  assert_param((pin >= 1) && (pin <= 13));
+  assert_param(deckGPIOMapping[pin-1].adcCh > -1);
+
+  /* Now set the GPIO pin to analog mode. */
+
+  /* Enable clock for the peripheral of the pin.*/
+  RCC_AHB1PeriphClockCmd(deckGPIOMapping[pin-1].periph, ENABLE);
+
+  /* Populate structure with RESET values. */
+  GPIO_InitTypeDef GPIO_InitStructure;
+  GPIO_StructInit(&GPIO_InitStructure);
+
+  /* Initialise the GPIO pin to analog mode. */
+  GPIO_InitStructure.GPIO_Pin   = deckGPIOMapping[pin-1].pin;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AN;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
+  GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_NOPULL;
+
+  /* TODO: Any settling time before we can do ADC after init on the GPIO pin? */
+  GPIO_Init(deckGPIOMapping[pin-1].port, &GPIO_InitStructure);
+
+  /* Read the appropriate ADC channel. */
+  return analogReadChannel((uint8_t)deckGPIOMapping[pin-1].adcCh);
+}
+
+void analogReference(uint8_t type)
+{
+  /*
+   * TODO: We should probably support the Arduino EXTERNAL type here.
+   * TODO: Figure out which voltage reference to compensate with.
+   */
+  assert_param(type == 0 /* DEFAULT */);
+}
+
+void analogReadResolution(uint8_t bits)
+{
+  ADC_InitTypeDef       ADC_InitStructure;
+
+  assert_param((bits >= 6) && (bits <= 12));
+
+  adcRange = 1 << bits;
+  switch (bits)
+  {
+    case 12: stregResolution = ADC_Resolution_12b; break;
+    case 10: stregResolution = ADC_Resolution_10b; break;
+    case 8:  stregResolution = ADC_Resolution_8b; break;
+    case 6:  stregResolution = ADC_Resolution_6b; break;
+    default: stregResolution = ADC_Resolution_12b; break;
+  }
+
+  /* Init ADC2 witch new resolution */
+  ADC_InitStructure.ADC_Resolution = stregResolution;
+  ADC_InitStructure.ADC_ScanConvMode = DISABLE;
+  ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
+  ADC_InitStructure.ADC_ExternalTrigConvEdge = 0;
+  ADC_InitStructure.ADC_ExternalTrigConv = 0;
+  ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+  ADC_InitStructure.ADC_NbrOfConversion = 1;
+  ADC_Init(ADC2, &ADC_InitStructure);
+}
+
+float analogReadVoltage(uint32_t pin)
+{
+  float voltage;
+
+  voltage = analogRead(pin) * VREF / adcRange;
+
+  return voltage;
+
+}
diff --git a/crazyflie-firmware-src/src/deck/api/deck_constants.c b/crazyflie-firmware-src/src/deck/api/deck_constants.c
new file mode 100644
index 0000000000000000000000000000000000000000..f822be65e66c3161991b206805931aded918c9d0
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/api/deck_constants.c
@@ -0,0 +1,44 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_constants.c - Constants for the Deck API
+ */
+
+#include "deck.h"
+
+/* Mapping between Deck Pin number, real GPIO and ADC channel */
+deckGPIOMapping_t deckGPIOMapping[13] = {
+  {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_11, .adcCh=-1},            /* RX1 */
+  {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_10, .adcCh=-1},            /* TX1 */
+  {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_7,  .adcCh=-1},            /* SDA */
+  {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_6,  .adcCh=-1},            /* SCL */
+  {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_8,  .adcCh=-1},            /* IO1 */
+  {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_5,  .adcCh=-1},            /* IO2 */
+  {.periph= RCC_AHB1Periph_GPIOB, .port= GPIOB, .pin=GPIO_Pin_4,  .adcCh=-1},            /* IO3 */
+  {.periph= RCC_AHB1Periph_GPIOC, .port= GPIOC, .pin=GPIO_Pin_12, .adcCh=-1},            /* IO4 */
+  {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_2,  .adcCh=ADC_Channel_2}, /* TX2 */
+  {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_3,  .adcCh=ADC_Channel_3}, /* RX2 */
+  {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_5,  .adcCh=ADC_Channel_5}, /* SCK */
+  {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_6,  .adcCh=ADC_Channel_6}, /* MISO */
+  {.periph= RCC_AHB1Periph_GPIOA, .port= GPIOA, .pin=GPIO_Pin_7,  .adcCh=ADC_Channel_7}, /* MOSI */
+};
diff --git a/crazyflie-firmware-src/src/deck/api/deck_digital.c b/crazyflie-firmware-src/src/deck/api/deck_digital.c
new file mode 100644
index 0000000000000000000000000000000000000000..67a20bf753e53d1e0a60ef998b0b1dc39bcc4ba7
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/api/deck_digital.c
@@ -0,0 +1,69 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * digital.c - Deck-API digital IO implementation
+ */
+
+#include "deck.h"
+
+#include "stm32fxxx.h"
+
+void pinMode(uint32_t pin, uint32_t mode)
+{
+  if (pin > 13) {
+    return;
+  }
+
+  RCC_AHB1PeriphClockCmd(deckGPIOMapping[pin-1].periph, ENABLE);
+
+  GPIO_InitTypeDef GPIO_InitStructure = {0};
+
+  GPIO_InitStructure.GPIO_Pin = deckGPIOMapping[pin-1].pin;
+  GPIO_InitStructure.GPIO_Mode = (mode == OUTPUT) ? GPIO_Mode_OUT:GPIO_Mode_IN;
+  if (mode == OUTPUT) GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  if (mode == INPUT_PULLUP) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
+  if (mode == INPUT_PULLDOWN) GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
+  GPIO_Init(deckGPIOMapping[pin-1].port, &GPIO_InitStructure);
+}
+
+void digitalWrite(uint32_t pin, uint32_t val)
+{
+  if (pin > 13) {
+    return;
+  }
+
+  if (val) val = Bit_SET;
+
+  GPIO_WriteBit(deckGPIOMapping[pin-1].port, deckGPIOMapping[pin-1].pin, val);
+}
+
+int digitalRead(uint32_t pin)
+{
+  if (pin > 13) {
+    return LOW;
+  }
+
+  int val = GPIO_ReadInputDataBit(deckGPIOMapping[pin-1].port, deckGPIOMapping[pin-1].pin);
+  return (val==Bit_SET)?HIGH:LOW;
+}
diff --git a/crazyflie-firmware-src/src/deck/api/deck_spi.c b/crazyflie-firmware-src/src/deck/api/deck_spi.c
new file mode 100644
index 0000000000000000000000000000000000000000..1acfb7f6e00277c60538d726b08e9c8bf1823dbb
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/api/deck_spi.c
@@ -0,0 +1,316 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_spi.c - Deck-API SPI communication implementation
+ */
+
+#include "deck.h"
+
+/*ST includes */
+#include "stm32fxxx.h"
+#include "config.h"
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+
+#include "cfassert.h"
+#include "config.h"
+#include "nvicconf.h"
+
+#define SPI                           SPI1
+#define SPI_CLK                       RCC_APB2Periph_SPI1
+#define SPI_CLK_INIT                  RCC_APB2PeriphClockCmd
+#define SPI_IRQ_HANDLER               SPI1_IRQHandler
+#define SPI_IRQn                      SPI1_IRQn
+
+#define SPI_DMA_IRQ_PRIO        (NVIC_HIGH_PRI)
+#define SPI_DMA                 DMA2
+#define SPI_DMA_CLK             RCC_AHB1Periph_DMA2
+#define SPI_DMA_CLK_INIT        RCC_AHB1PeriphClockCmd
+
+#define SPI_TX_DMA_STREAM       DMA2_Stream5
+#define SPI_TX_DMA_IRQ          DMA2_Stream5_IRQn
+#define SPI_TX_DMA_IRQHandler   DMA2_Stream5_IRQHandler
+#define SPI_TX_DMA_CHANNEL      DMA_Channel_3
+#define SPI_TX_DMA_FLAG_TCIF    DMA_FLAG_TCIF5
+
+#define SPI_RX_DMA_STREAM       DMA2_Stream0
+#define SPI_RX_DMA_IRQ          DMA2_Stream0_IRQn
+#define SPI_RX_DMA_IRQHandler   DMA2_Stream0_IRQHandler
+#define SPI_RX_DMA_CHANNEL      DMA_Channel_3
+#define SPI_RX_DMA_FLAG_TCIF    DMA_FLAG_TCIF0
+
+#define SPI_SCK_PIN                   GPIO_Pin_5
+#define SPI_SCK_GPIO_PORT             GPIOA
+#define SPI_SCK_GPIO_CLK              RCC_AHB1Periph_GPIOA
+#define SPI_SCK_SOURCE                GPIO_PinSource5
+#define SPI_SCK_AF                    GPIO_AF_SPI1
+
+#define SPI_MISO_PIN                  GPIO_Pin_6
+#define SPI_MISO_GPIO_PORT            GPIOA
+#define SPI_MISO_GPIO_CLK             RCC_AHB1Periph_GPIOA
+#define SPI_MISO_SOURCE               GPIO_PinSource6
+#define SPI_MISO_AF                   GPIO_AF_SPI1
+
+#define SPI_MOSI_PIN                  GPIO_Pin_7
+#define SPI_MOSI_GPIO_PORT            GPIOA
+#define SPI_MOSI_GPIO_CLK             RCC_AHB1Periph_GPIOA
+#define SPI_MOSI_SOURCE               GPIO_PinSource7
+#define SPI_MOSI_AF                   GPIO_AF_SPI1
+
+#define DUMMY_BYTE         0xA5
+
+static bool isInit = false;
+
+static SemaphoreHandle_t txComplete;
+static SemaphoreHandle_t rxComplete;
+
+static void spiDMAInit();
+
+void spiBegin(void)
+{
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  // binary semaphores created using xSemaphoreCreateBinary() are created in a state
+  // such that the the semaphore must first be 'given' before it can be 'taken'
+  txComplete = xSemaphoreCreateBinary();
+  rxComplete = xSemaphoreCreateBinary();
+
+  /*!< Enable the SPI clock */
+  SPI_CLK_INIT(SPI_CLK, ENABLE);
+
+  /*!< Enable GPIO clocks */
+  RCC_AHB1PeriphClockCmd(SPI_SCK_GPIO_CLK | SPI_MISO_GPIO_CLK |
+                         SPI_MOSI_GPIO_CLK, ENABLE);
+
+  /*!< Enable DMA Clocks */
+  SPI_DMA_CLK_INIT(SPI_DMA_CLK, ENABLE);
+
+  /*!< SPI pins configuration *************************************************/
+
+  /*!< Connect SPI pins to AF5 */
+  GPIO_PinAFConfig(SPI_SCK_GPIO_PORT, SPI_SCK_SOURCE, SPI_SCK_AF);
+  GPIO_PinAFConfig(SPI_MISO_GPIO_PORT, SPI_MISO_SOURCE, SPI_MISO_AF);
+  GPIO_PinAFConfig(SPI_MOSI_GPIO_PORT, SPI_MOSI_SOURCE, SPI_MOSI_AF);
+
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_DOWN;
+
+  /*!< SPI SCK pin configuration */
+  GPIO_InitStructure.GPIO_Pin = SPI_SCK_PIN;
+  GPIO_Init(SPI_SCK_GPIO_PORT, &GPIO_InitStructure);
+
+  /*!< SPI MOSI pin configuration */
+  GPIO_InitStructure.GPIO_Pin =  SPI_MOSI_PIN;
+  GPIO_Init(SPI_MOSI_GPIO_PORT, &GPIO_InitStructure);
+
+  /*!< SPI MISO pin configuration */
+  GPIO_InitStructure.GPIO_Pin =  SPI_MISO_PIN;
+  GPIO_Init(SPI_MISO_GPIO_PORT, &GPIO_InitStructure);
+
+  /*!< SPI DMA Initialization */
+  spiDMAInit();
+
+  /*!< SPI configuration */
+  spiConfigureSlow();
+
+  isInit = true;
+}
+
+void spiDMAInit()
+{
+  DMA_InitTypeDef  DMA_InitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  /* Configure DMA Initialization Structure */
+  DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
+  DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
+  DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
+  DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+  DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+  DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+  DMA_InitStructure.DMA_PeripheralBaseAddr =(uint32_t) (&(SPI->DR)) ;
+  DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+  DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+  DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+  DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+  DMA_InitStructure.DMA_BufferSize = 0; // set later
+  DMA_InitStructure.DMA_Memory0BaseAddr = 0; // set later
+
+  // Configure TX DMA
+  DMA_InitStructure.DMA_Channel = SPI_TX_DMA_CHANNEL;
+  DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
+  DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE);
+  DMA_Init(SPI_TX_DMA_STREAM, &DMA_InitStructure);
+
+  // Configure RX DMA
+  DMA_InitStructure.DMA_Channel = SPI_RX_DMA_CHANNEL;
+  DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
+  DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE);
+  DMA_Init(SPI_RX_DMA_STREAM, &DMA_InitStructure);
+
+  // Configure interrupts
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+
+  NVIC_InitStructure.NVIC_IRQChannel = SPI_TX_DMA_IRQ;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannel = SPI_RX_DMA_IRQ;
+  NVIC_Init(&NVIC_InitStructure);
+}
+
+void spiConfigureSlow()
+{
+  SPI_InitTypeDef  SPI_InitStructure;
+
+  SPI_I2S_DeInit(SPI);
+
+  SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+  SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+  SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+  SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+  SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
+  SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+  SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+  SPI_InitStructure.SPI_CRCPolynomial = 0; // Not used
+
+  SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32; //~2.7 MHz
+  SPI_Init(SPI, &SPI_InitStructure);
+}
+
+void spiConfigureFast()
+{
+  SPI_InitTypeDef  SPI_InitStructure;
+
+  SPI_I2S_DeInit(SPI);
+
+  SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+  SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+  SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+  SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+  SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
+  SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+  SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+  SPI_InitStructure.SPI_CRCPolynomial = 0; // Not used
+
+  SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4; //~21 MHz
+  SPI_Init(SPI, &SPI_InitStructure);
+}
+
+bool spiTest(void)
+{
+  return isInit;
+}
+
+bool spiExchange(size_t length, const uint8_t * data_tx, uint8_t * data_rx)
+{
+  // DMA already configured, just need to set memory addresses
+  SPI_TX_DMA_STREAM->M0AR = (uint32_t)data_tx;
+  SPI_TX_DMA_STREAM->NDTR = length;
+
+  SPI_RX_DMA_STREAM->M0AR = (uint32_t)data_rx;
+  SPI_RX_DMA_STREAM->NDTR = length;
+
+  // Enable SPI DMA Interrupts
+  DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, ENABLE);
+  DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, ENABLE);
+
+  // Clear DMA Flags
+  DMA_ClearFlag(SPI_TX_DMA_STREAM, DMA_FLAG_FEIF5|DMA_FLAG_DMEIF5|DMA_FLAG_TEIF5|DMA_FLAG_HTIF5|DMA_FLAG_TCIF5);
+  DMA_ClearFlag(SPI_RX_DMA_STREAM, DMA_FLAG_FEIF0|DMA_FLAG_DMEIF0|DMA_FLAG_TEIF0|DMA_FLAG_HTIF0|DMA_FLAG_TCIF0);
+
+  // Enable DMA Streams
+  DMA_Cmd(SPI_TX_DMA_STREAM,ENABLE);
+  DMA_Cmd(SPI_RX_DMA_STREAM,ENABLE);
+
+  // Enable SPI DMA requests
+  SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, ENABLE);
+  SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, ENABLE);
+
+  // Enable peripheral
+  SPI_Cmd(SPI, ENABLE);
+
+  // Wait for completion
+  bool result = (xSemaphoreTake(txComplete, portMAX_DELAY) == pdTRUE)
+             && (xSemaphoreTake(rxComplete, portMAX_DELAY) == pdTRUE);
+
+  // Disable peripheral
+  SPI_Cmd(SPI, DISABLE);
+  return result;
+}
+
+void __attribute__((used)) SPI_TX_DMA_IRQHandler(void)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+
+  // Stop and cleanup DMA stream
+  DMA_ITConfig(SPI_TX_DMA_STREAM, DMA_IT_TC, DISABLE);
+  DMA_ClearITPendingBit(SPI_TX_DMA_STREAM, SPI_TX_DMA_FLAG_TCIF);
+
+  // Clear stream flags
+  DMA_ClearFlag(SPI_TX_DMA_STREAM,SPI_TX_DMA_FLAG_TCIF);
+
+  // Disable SPI DMA requests
+  SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Tx, DISABLE);
+
+  // Disable streams
+  DMA_Cmd(SPI_TX_DMA_STREAM,DISABLE);
+
+  // Give the semaphore, allowing the SPI transaction to complete
+  xSemaphoreGiveFromISR(txComplete, &xHigherPriorityTaskWoken);
+
+  if (xHigherPriorityTaskWoken)
+  {
+    portYIELD();
+  }
+}
+
+void __attribute__((used)) SPI_RX_DMA_IRQHandler(void)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+
+  // Stop and cleanup DMA stream
+  DMA_ITConfig(SPI_RX_DMA_STREAM, DMA_IT_TC, DISABLE);
+  DMA_ClearITPendingBit(SPI_RX_DMA_STREAM, SPI_RX_DMA_FLAG_TCIF);
+
+  // Clear stream flags
+  DMA_ClearFlag(SPI_RX_DMA_STREAM,SPI_RX_DMA_FLAG_TCIF);
+
+  // Disable SPI DMA requests
+  SPI_I2S_DMACmd(SPI, SPI_I2S_DMAReq_Rx, DISABLE);
+
+  // Disable streams
+  DMA_Cmd(SPI_RX_DMA_STREAM,DISABLE);
+
+  // Give the semaphore, allowing the SPI transaction to complete
+  xSemaphoreGiveFromISR(rxComplete, &xHigherPriorityTaskWoken);
+
+  if (xHigherPriorityTaskWoken)
+  {
+    portYIELD();
+  }
+}
diff --git a/crazyflie-firmware-src/src/deck/core/deck.c b/crazyflie-firmware-src/src/deck/core/deck.c
new file mode 100644
index 0000000000000000000000000000000000000000..0db996823f170eeca9b235db616db5c097f41310
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/core/deck.c
@@ -0,0 +1,128 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck.c - Deck subsystem main entry points
+ */
+
+#define DEBUG_MODULE "DECK_CORE"
+
+#include <string.h>
+
+#include "deck.h"
+#include "debug.h"
+
+#ifdef DEBUG
+  #define DECK_CORE_DBG_PRINT(fmt, ...)  DEBUG_PRINT(fmt, ## __VA_ARGS__)
+#else
+  #define DECK_CORE_DBG_PRINT(...)
+#endif
+
+#ifndef DECK_FORCE
+#define DECK_FORCE
+#endif
+
+#define xstr(s) str(s)
+#define str(s) #s
+
+static char* deck_force = xstr(DECK_FORCE);
+
+extern void deckInfoInit();
+
+void deckInit()
+{
+  deckDriverCount();
+  deckInfoInit();
+
+#ifndef IGNORE_OW_DECKS
+  int nDecks;
+  int i;
+
+  nDecks = deckCount();
+
+  DEBUG_PRINT("%d deck enumerated\n", nDecks);
+
+  for (i=0; i<nDecks; i++) {
+    DeckInfo *deck = deckInfo(i);
+
+    if (deck->driver->init) {
+      if (deck->driver->name) {
+        DECK_CORE_DBG_PRINT("Calling INIT from driver %s for deck %i\n", deck->driver->name, i);
+      } else {
+        DECK_CORE_DBG_PRINT("Calling INIT for deck %i\n", i);
+      }
+
+      deck->driver->init(deck);
+    }
+  }
+#endif
+
+  // Init build-forced driver
+  if (strlen(deck_force)>0) {
+    const DeckDriver *driver = deckFindDriverByName(deck_force);
+    if (!driver) {
+      DEBUG_PRINT("WARNING: compile-time forced driver %s not found\n", deck_force);
+    } else if (driver->init) {
+      DEBUG_PRINT("Initializing compile-time forced driver %s\n", deck_force);
+      driver->init(NULL);  // Passing NULL as deck info
+    }
+  }
+}
+
+bool deckTest()
+{
+  bool pass = true;
+#ifndef IGNORE_OW_DECKS
+  int nDecks;
+  int i;
+
+  nDecks = deckCount();
+
+  for (i=0; i<nDecks; i++) {
+    DeckInfo *deck = deckInfo(i);
+
+    if (deck->driver->test) {
+      if (deck->driver->test()) {
+        DEBUG_PRINT("Deck %i test [OK].\n", i);
+      } else {
+        DEBUG_PRINT("Deck %i test [FAIL].\n", i);
+        pass = false;
+      }
+    }
+  }
+#endif
+
+  // Test build-forced driver
+  if (strlen(deck_force)>0) {
+    const DeckDriver *driver = deckFindDriverByName(deck_force);
+    if (driver && driver->test) {
+      if (driver->test()) {
+        DEBUG_PRINT("Compile-time forced driver %s test [OK]\n", deck_force);
+      } else {
+        DEBUG_PRINT("Compile-time forced driver %s test [FAIL]\n", deck_force);
+        pass = false;
+      }
+    }
+  }
+
+  return pass;
+}
diff --git a/crazyflie-firmware-src/src/deck/core/deck_drivers.c b/crazyflie-firmware-src/src/deck/core/deck_drivers.c
new file mode 100644
index 0000000000000000000000000000000000000000..8ec756baa9ee42c2d2cf64ca9d25c026d6da6e27
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/core/deck_drivers.c
@@ -0,0 +1,110 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_drivers.c - Deck drivers loading and handling
+ */
+
+#define DEBUG_MODULE "DECK_DRIVERS"
+
+#include <stdlib.h>
+#include <string.h>
+
+#include "deck.h"
+#include "debug.h"
+
+#ifdef DEBUG
+  #define DECK_DRV_DBG_PRINT(fmt, ...)  DEBUG_PRINT(fmt, ## __VA_ARGS__)
+#else
+  #define DECK_DRV_DBG_PRINT(...)
+#endif
+
+/* Symbols set by the linker script */
+extern const struct deck_driver * _deckDriver_start;
+extern const struct deck_driver * _deckDriver_stop;
+
+static const struct deck_driver ** drivers;
+static int driversLen;
+
+// Init the toc access variables. Lazy initialisation: it is going to be done
+// the first time any api function is called.
+static void deckdriversInit() {
+  static bool init = false;
+  if (!init) {
+    int i;
+
+    drivers = &_deckDriver_start;
+    driversLen = &_deckDriver_stop - &_deckDriver_start;
+    init = true;
+
+    DEBUG_PRINT("Found %d drivers\n", driversLen);
+    for (i=0; i<driversLen; i++) {
+      if (drivers[i]->name) {
+        DECK_DRV_DBG_PRINT("VID:PID %02x:%02x (%s)\n", drivers[i]->vid, drivers[i]->pid, drivers[i]->name);
+      } else {
+        DECK_DRV_DBG_PRINT("VID:PID %02x:%02x\n", drivers[i]->vid, drivers[i]->pid);
+      }
+
+    }
+  }
+}
+
+int deckDriverCount() {
+  deckdriversInit();
+
+  return driversLen;
+}
+
+const struct deck_driver* deckGetDriver(int i) {
+  deckdriversInit();
+
+  if (i<driversLen) {
+    return drivers[i];
+  }
+  return NULL;
+}
+
+const DeckDriver* deckFindDriverByVidPid(uint8_t vid, uint8_t pid) {
+  int i;
+
+  deckdriversInit();
+
+  for (i=0; i<driversLen; i++) {
+    if ((vid == drivers[i]->vid) && (pid == drivers[i]->pid)) {
+      return drivers[i];
+    }
+  }
+  return NULL;
+}
+
+const DeckDriver* deckFindDriverByName(char* name) {
+  int i;
+
+  deckdriversInit();
+
+  for (i=0; i<driversLen; i++) {
+    if (!strcmp(name, drivers[i]->name)) {
+      return drivers[i];
+    }
+  }
+  return NULL;
+}
diff --git a/crazyflie-firmware-src/src/deck/core/deck_info.c b/crazyflie-firmware-src/src/deck/core/deck_info.c
new file mode 100644
index 0000000000000000000000000000000000000000..dce54e5f1aeb68b0e557e68aa1e94eab992ab804
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/core/deck_info.c
@@ -0,0 +1,282 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_ow.c - Functions to decode the decks oneWire memory content
+ */
+
+#include <stdlib.h>
+#include <stdbool.h>
+#include <string.h>
+
+#define DEBUG_MODULE "DECK_INFO"
+
+#include "deck.h"
+
+#include "ow.h"
+#include "crc.h"
+#include "debug.h"
+
+#ifdef DEBUG
+  #define DECK_INFO_DBG_PRINT(fmt, ...)  DEBUG_PRINT(fmt, ## __VA_ARGS__)
+#else
+  #define DECK_INFO_DBG_PRINT(...)
+#endif
+
+static int count = 0;
+static DeckInfo deckInfos[DECK_MAX_COUNT];
+
+static void enumerateDecks(void);
+
+void deckInfoInit()
+{
+  static bool isInit = false;
+
+  if (isInit) return;
+
+  enumerateDecks();
+
+  isInit = true;
+}
+
+int deckCount(void)
+{
+  return count;
+}
+
+DeckInfo * deckInfo(int i)
+{
+  if (i<count) {
+    return &deckInfos[i];
+  }
+
+  return NULL;
+}
+
+// Dummy driver for decks that do not have a driver implemented
+static const DeckDriver dummyDriver;
+
+static const DeckDriver * findDriver(DeckInfo *deck)
+{
+  char name[30];
+  const DeckDriver *driver = &dummyDriver;
+
+  deckTlvGetString(&deck->tlv, DECK_INFO_NAME, name, 30);
+
+  if (deck->vid) {
+    driver = deckFindDriverByVidPid(deck->vid, deck->pid);
+  } else if (strlen(name)>0) {
+    driver = deckFindDriverByName(name);
+  }
+
+  if (driver == NULL)
+    driver = &dummyDriver;
+
+  return driver;
+}
+
+void printDeckInfo(DeckInfo *info)
+{
+  char name[30] = "NoName";
+  char rev[10] = "NoRev";
+
+  if (deckTlvHasElement(&info->tlv, DECK_INFO_NAME)) {
+    deckTlvGetString(&info->tlv, DECK_INFO_NAME, name, 30);
+  }
+
+  if (deckTlvHasElement(&info->tlv, DECK_INFO_REVISION)) {
+    deckTlvGetString(&info->tlv, DECK_INFO_REVISION, rev, 10);
+  }
+
+  DECK_INFO_DBG_PRINT("Deck %02x:%02x %s (Rev. %s)\n", info->vid, info->pid, name, rev);
+  DECK_INFO_DBG_PRINT("Used pin: %08x\n", (unsigned int)info->usedPins);
+
+  if (info->driver == &dummyDriver) {
+    DEBUG_PRINT("Warning! No driver found for deck.\n");
+  } else {
+    DECK_INFO_DBG_PRINT("Driver implements: [ %s%s]\n",
+                        info->driver->init?"init ":"", info->driver->test?"test ":"");
+  }
+}
+
+static bool infoDecode(DeckInfo * info)
+{
+  uint8_t crcHeader;
+  uint8_t crcTlv;
+
+  if (info->header != DECK_INFO_HEADER_ID) {
+    DEBUG_PRINT("Memory error: wrong header ID\n");
+    return false;
+  }
+
+  crcHeader = crcSlow(info->raw, DECK_INFO_HEADER_SIZE);
+  if(info->crc != crcHeader) {
+    DEBUG_PRINT("Memory error: incorrect header CRC\n");
+    return false;
+  }
+
+  if(info->raw[DECK_INFO_TLV_VERSION_POS] != DECK_INFO_TLV_VERSION) {
+    DEBUG_PRINT("Memory error: incorrect TLV version\n");
+    return false;
+  }
+
+  crcTlv = crcSlow(&info->raw[DECK_INFO_TLV_VERSION_POS], info->raw[DECK_INFO_TLV_LENGTH_POS]+2);
+  if(crcTlv != info->raw[DECK_INFO_TLV_DATA_POS + info->raw[DECK_INFO_TLV_LENGTH_POS]]) {
+    DEBUG_PRINT("Memory error: incorrect TLV CRC %x!=%x\n", (unsigned int)crcTlv,
+                info->raw[DECK_INFO_TLV_DATA_POS + info->raw[DECK_INFO_TLV_LENGTH_POS]]);
+    return false;
+  }
+
+  info->tlv.data = &info->raw[DECK_INFO_TLV_DATA_POS];
+  info->tlv.length = info->raw[DECK_INFO_TLV_LENGTH_POS];
+
+  return true;
+}
+
+static void enumerateDecks(void)
+{
+  uint8_t nDecks = 0;
+  int i;
+  bool noError = true;
+  uint32_t usedPeriph = 0;
+  uint32_t usedGpio = 0;
+
+  owInit();
+
+  if (owScan(&nDecks))
+  {
+    DEBUG_PRINT("Found %d deck memor%s.\n", nDecks, nDecks>1?"ies":"y");
+  } else {
+    DEBUG_PRINT("Error scanning for deck memories, "
+                "no deck drivers will be initialised\n");
+    nDecks = 0;
+  }
+
+  for (i = 0; i < nDecks; i++)
+  {
+    DECK_INFO_DBG_PRINT("Enumerating deck %i\n", i);
+    if (owRead(i, 0, sizeof(deckInfos[0].raw), (uint8_t *)&deckInfos[i]))
+    {
+      if (infoDecode(&deckInfos[i]))
+      {
+        deckInfos[i].driver = findDriver(&deckInfos[i]);
+
+        printDeckInfo(&deckInfos[i]);
+
+        // Check for Periph and Gpio conflict
+        if (usedPeriph & deckInfos[i].driver->usedPeriph) {
+          DEBUG_PRINT("ERROR: Driver Periph usage conflicts with a "
+                      "previously enumerated deck driver. No decks will be "
+                      "initialized!\n");
+          noError = false;
+        }
+
+        if (usedGpio & deckInfos[i].driver->usedGpio) {
+          DEBUG_PRINT("ERROR: Driver Gpio usage conflicts with a "
+                      "previously enumerated deck driver. No decks will be "
+                      "initialized!\n");
+          noError = false;
+        }
+
+        usedPeriph |= deckInfos[i].driver->usedPeriph;
+        usedGpio |= deckInfos[i].driver->usedGpio;
+      } else {
+#ifdef DEBUG
+        DEBUG_PRINT("Deck %i has corrupted OW memory. "
+                    "Ignoring the deck in DEBUG mode.\n", i);
+        deckInfos[i].driver = &dummyDriver;
+#else
+        DEBUG_PRINT("Deck %i has corrupted OW memory. "
+                    "No driver will be initialized!\n", i);
+        noError = false;
+#endif
+      }
+    }
+    else
+    {
+      DEBUG_PRINT("Reading deck nr:%d [FAILED]. "
+                  "No driver will be initialized!\n", i);
+      noError = false;
+    }
+  }
+
+  if (noError) {
+    count = nDecks;
+  }
+
+  return;
+}
+
+/****** Key/value area handling ********/
+static int findType(TlvArea *tlv, int type) {
+  int pos = 0;
+
+  while (pos < tlv->length) {
+    if (tlv->data[pos] == type) {
+      return pos;
+    } else {
+      pos += tlv->data[pos+1]+2;
+    }
+  }
+  return -1;
+}
+
+bool deckTlvHasElement(TlvArea *tlv, int type) {
+  return findType(tlv, type) >= 0;
+}
+
+int deckTlvGetString(TlvArea *tlv, int type, char *string, int length) {
+  int pos = findType(tlv, type);
+  int strlength = 0;
+
+  if (pos >= 0) {
+    strlength = tlv->data[pos+1];
+
+    if (strlength > (length-1)) {
+      strlength = length-1;
+    }
+
+    memcpy(string, &tlv->data[pos+2], strlength);
+    string[strlength] = '\0';
+
+    return strlength;
+  } else {
+    string[0] = '\0';
+
+    return -1;
+  }
+}
+
+char* deckTlvGetBuffer(TlvArea *tlv, int type, int *length) {
+  int pos = findType(tlv, type);
+  if (pos >= 0) {
+    *length = tlv->data[pos+1];
+    return (char*) &tlv->data[pos+2];
+  }
+
+  return NULL;
+}
+
+void deckTlvGetTlv(TlvArea *tlv, int type, TlvArea *output) {
+  output->length = 0;
+  output->data = (uint8_t *)deckTlvGetBuffer(tlv, type, &output->length);
+}
diff --git a/crazyflie-firmware-src/src/deck/core/deck_test.c b/crazyflie-firmware-src/src/deck/core/deck_test.c
new file mode 100644
index 0000000000000000000000000000000000000000..98eeeaf640c0ab2e3661c75cc773eeb2ca027032
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/core/deck_test.c
@@ -0,0 +1,72 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_test.c - Test utility functions for testing decks.
+ */
+#include <string.h>
+
+#include "stm32fxxx.h"
+
+#include "deck.h"
+#include "deck_test.h"
+#include "debug.h"
+
+
+#ifndef DECK_TEST_PRINT_ALL_FAILED
+  #define STATUS_EVAL (*status)
+#else
+  #define STATUS_EVAL 1
+#endif
+
+
+void decktestEval(bool result, char *failString, bool *status)
+{
+  if (STATUS_EVAL)
+  {
+    if (!result)
+    {
+      consolePrintf("%s [FAIL]\n", failString);
+      *status = false;
+    }
+    else
+    {
+      *status = true;
+    }
+  }
+}
+
+void decktestSaveGPIOStatesABC(GpioRegBuf *gpioRegBuf)
+{
+  // Save GPIO registers
+  memcpy(&gpioRegBuf->gpioBuffA, GPIOA, sizeof(GPIO_TypeDef));
+  memcpy(&gpioRegBuf->gpioBuffB, GPIOB, sizeof(GPIO_TypeDef));
+  memcpy(&gpioRegBuf->gpioBuffC, GPIOC, sizeof(GPIO_TypeDef));
+}
+
+void decktestRestoreGPIOStatesABC(GpioRegBuf *gpioRegBuf)
+{
+  // Restore GPIO registers
+  memcpy(GPIOA, &gpioRegBuf->gpioBuffA, sizeof(GPIO_TypeDef));
+  memcpy(GPIOB, &gpioRegBuf->gpioBuffB, sizeof(GPIO_TypeDef));
+  memcpy(GPIOC, &gpioRegBuf->gpioBuffC, sizeof(GPIO_TypeDef));
+}
diff --git a/crazyflie-firmware-src/src/deck/drivers/interface/ledring12.h b/crazyflie-firmware-src/src/deck/drivers/interface/ledring12.h
new file mode 100644
index 0000000000000000000000000000000000000000..c4bbfc2fe9582e27e3f28dc58bead8f639e0f34b
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/interface/ledring12.h
@@ -0,0 +1,11 @@
+#ifndef __LEDRING12_H__
+#define __LEDRING12_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#define NBR_LEDS  12
+
+extern uint8_t ledringmem[NBR_LEDS * 2];
+
+#endif //__LEDRING12_H__
diff --git a/crazyflie-firmware-src/src/deck/drivers/interface/locodeck.h b/crazyflie-firmware-src/src/deck/drivers/interface/locodeck.h
new file mode 100644
index 0000000000000000000000000000000000000000..344c4b1957fbbb4f5fa27403bedcf9039f56e36f
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/interface/locodeck.h
@@ -0,0 +1,82 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2016 Bitcraze AB
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.  IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * locodeck.h: Dwm1000 deck driver.
+ */
+
+#ifndef __LOCODECK_H__
+#define __LOCODECK_H__
+
+#include "libdw1000.h"
+#include "stabilizer_types.h"
+
+#define SPEED_OF_LIGHT 299792458.0
+// Timestamp counter frequency
+#define LOCODECK_TS_FREQ (499.2e6 * 128)
+
+
+typedef enum uwbEvent_e {
+  eventTimeout,
+  eventPacketReceived,
+  eventPacketSent,
+  eventReceiveTimeout,
+  eventReceiveFailed,
+} uwbEvent_t;
+
+#define LOCODECK_NR_OF_ANCHORS 6
+
+typedef uint64_t locoAddress_t;
+
+typedef struct {
+  const uint64_t antennaDelay;
+  const int rangingFailedThreshold;
+
+  const locoAddress_t tagAddress;
+  const locoAddress_t anchorAddress[LOCODECK_NR_OF_ANCHORS];
+
+  point_t anchorPosition[LOCODECK_NR_OF_ANCHORS];
+  bool anchorPositionOk;
+
+  float distance[LOCODECK_NR_OF_ANCHORS];
+  float pressures[LOCODECK_NR_OF_ANCHORS];
+  int failedRanging[LOCODECK_NR_OF_ANCHORS];
+  volatile uint16_t rangingState;
+} lpsAlgoOptions_t;
+
+// Callback for one uwb algorithm
+typedef struct uwbAlgorithm_s {
+  void (*init)(dwDevice_t *dev, lpsAlgoOptions_t* options);
+  uint32_t (*onEvent)(dwDevice_t *dev, uwbEvent_t event);
+} uwbAlgorithm_t;
+
+#include <FreeRTOS.h>
+
+#define MAX_TIMEOUT portMAX_DELAY
+
+#endif // __LOCODECK_H__
diff --git a/crazyflie-firmware-src/src/deck/drivers/interface/lpsTdoaTag.h b/crazyflie-firmware-src/src/deck/drivers/interface/lpsTdoaTag.h
new file mode 100644
index 0000000000000000000000000000000000000000..193b3b0cee94dc06a92d945d63693690c16e3346
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/interface/lpsTdoaTag.h
@@ -0,0 +1,17 @@
+#ifndef __LPS_TDOA_TAG_H__
+#define __LPS_TDOA_TAG_H__
+
+#include "locodeck.h"
+#include "libdw1000.h"
+
+#include "mac.h"
+
+extern uwbAlgorithm_t uwbTdoaTagAlgorithm;
+
+typedef struct rangePacket_s {
+  uint8_t type;
+  uint8_t txMaster[5];
+  uint8_t timestamps[LOCODECK_NR_OF_ANCHORS][5];
+} __attribute__((packed)) rangePacket_t;
+
+#endif // __LPS_TDOA_TAG_H__
diff --git a/crazyflie-firmware-src/src/deck/drivers/interface/lpsTwrTag.h b/crazyflie-firmware-src/src/deck/drivers/interface/lpsTwrTag.h
new file mode 100644
index 0000000000000000000000000000000000000000..6bf32dc5b384643ec18d774c8d2231c2be40c9d3
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/interface/lpsTwrTag.h
@@ -0,0 +1,31 @@
+#ifndef __LPS_TWR_TAG_H__
+#define __LPS_TWR_TAG_H__
+
+#include "locodeck.h"
+#include "libdw1000.h"
+
+#include "mac.h"
+
+#define LPS_TWR_POLL 0x01   // Poll is initiated by the tag
+#define LPS_TWR_ANSWER 0x02
+#define LPS_TWR_FINAL 0x03
+#define LPS_TWR_REPORT 0x04 // Report contains all measurement from the anchor
+
+#define LPS_TWR_TYPE 0
+#define LPS_TWR_SEQ 1
+
+extern uwbAlgorithm_t uwbTwrTagAlgorithm;
+
+typedef struct {
+  uint8_t pollRx[5];
+  uint8_t answerTx[5];
+  uint8_t finalRx[5];
+
+  float pressure;
+  float temperature;
+  float asl;
+  uint8_t pressure_ok;
+} __attribute__((packed)) lpsTwrTagReportPayload_t;
+
+
+#endif // __LPS_TWR_TAG_H__
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/deck/drivers/interface/mac.h b/crazyflie-firmware-src/src/deck/drivers/interface/mac.h
new file mode 100644
index 0000000000000000000000000000000000000000..9784acb4ad6ddd468098cc12d6fd9f093549429a
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/interface/mac.h
@@ -0,0 +1,51 @@
+#ifndef __MAC_H__
+#define __MAC_H__
+
+#include <stdint.h>
+
+#include "locodeck.h"
+
+// Packet format with compressed PAN and 64Bit addresses
+// Maximum 64 bytes payload
+typedef struct packet_s {
+    union {
+      uint16_t fcf;
+      struct {
+        uint16_t type:3;
+        uint16_t security:1;
+        uint16_t framePending:1;
+        uint16_t ack:1;
+        uint16_t ipan:1;
+        uint16_t reserved:3;
+        uint16_t destAddrMode:2;
+        uint16_t version:2;
+        uint16_t srcAddrMode:2;
+      } fcf_s;
+    };
+
+    uint8_t seq;
+    uint16_t pan;
+    locoAddress_t destAddress;
+    locoAddress_t sourceAddress;
+
+    uint8_t payload[64];
+} __attribute__((packed)) packet_t;
+
+#define MAC80215_PACKET_INIT(packet, TYPE) packet.fcf_s.type = (TYPE); \
+  packet.fcf_s.security = 0; \
+  packet.fcf_s.framePending = 0; \
+  packet.fcf_s.ack = 0; \
+  packet.fcf_s.ipan = 1; \
+  packet.fcf_s.destAddrMode = 3; \
+  packet.fcf_s.version = 1; \
+  packet.fcf_s.srcAddrMode = 3;
+
+
+#define MAC802154_TYPE_BEACON 0
+#define MAC802154_TYPE_DATA 1
+#define MAC802154_TYPE_ACK 2
+#define MAC802154_TYPE_CMD 3
+
+#define MAC802154_HEADER_LENGTH 21
+
+#endif
diff --git a/crazyflie-firmware-src/src/deck/drivers/interface/usddeck.h b/crazyflie-firmware-src/src/deck/drivers/interface/usddeck.h
new file mode 100644
index 0000000000000000000000000000000000000000..392a705e8260fb8bbab8d74d0646a0c7065d2f0f
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/interface/usddeck.h
@@ -0,0 +1,7 @@
+#ifndef __USBDECK_H__
+#define __USBDECK_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#endif //__USBDECK_H__
diff --git a/crazyflie-firmware-src/src/deck/drivers/interface/vl53l0x.h b/crazyflie-firmware-src/src/deck/drivers/interface/vl53l0x.h
new file mode 100644
index 0000000000000000000000000000000000000000..242d6757c27911ffc98000cfb2e48a7fbd7a30eb
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/interface/vl53l0x.h
@@ -0,0 +1,238 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * vl53l0x.h: Time-of-flight distance sensor driver
+ */
+
+#ifndef _VL53L0X_H_
+#define _VL53L0X_H_
+
+#define VL53L0X_DEFAULT_ADDRESS 0b0101001
+
+#define VL53L0X_RA_SYSRANGE_START                              0x00
+
+#define VL53L0X_RA_SYSTEM_THRESH_HIGH                          0x0C
+#define VL53L0X_RA_SYSTEM_THRESH_LOW                           0x0E
+
+#define VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG                      0x01
+#define VL53L0X_RA_SYSTEM_RANGE_CONFIG                         0x09
+#define VL53L0X_RA_SYSTEM_INTERMEASUREMENT_PERIOD              0x04
+
+#define VL53L0X_RA_SYSTEM_INTERRUPT_CONFIG_GPIO                0x0A
+
+#define VL53L0X_RA_GPIO_HV_MUX_ACTIVE_HIGH                     0x84
+
+#define VL53L0X_RA_SYSTEM_INTERRUPT_CLEAR                      0x0B
+
+#define VL53L0X_RA_RESULT_INTERRUPT_STATUS                     0x13
+#define VL53L0X_RA_RESULT_RANGE_STATUS                         0x14
+
+#define VL53L0X_RA_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN       0xBC
+#define VL53L0X_RA_RESULT_CORE_RANGING_TOTAL_EVENTS_RTN        0xC0
+#define VL53L0X_RA_RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF       0xD0
+#define VL53L0X_RA_RESULT_CORE_RANGING_TOTAL_EVENTS_REF        0xD4
+#define VL53L0X_RA_RESULT_PEAK_SIGNAL_RATE_REF                 0xB6
+
+#define VL53L0X_RA_ALGO_PART_TO_PART_RANGE_OFFSET_MM           0x28
+
+#define VL53L0X_RA_I2C_SLAVE_DEVICE_ADDRESS                    0x8A
+
+#define VL53L0X_RA_MSRC_CONFIG_CONTROL                         0x60
+
+#define VL53L0X_RA_PRE_RANGE_CONFIG_MIN_SNR                    0x27
+#define VL53L0X_RA_PRE_RANGE_CONFIG_VALID_PHASE_LOW            0x56
+#define VL53L0X_RA_PRE_RANGE_CONFIG_VALID_PHASE_HIGH           0x57
+#define VL53L0X_RA_PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT          0x64
+
+#define VL53L0X_RA_FINAL_RANGE_CONFIG_MIN_SNR                  0x67
+#define VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_LOW          0x47
+#define VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH         0x48
+#define VL53L0X_RA_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT 0x44
+
+#define VL53L0X_RA_PRE_RANGE_CONFIG_SIGMA_THRESH_HI            0x61
+#define VL53L0X_RA_PRE_RANGE_CONFIG_SIGMA_THRESH_LO            0x62
+
+#define VL53L0X_RA_PRE_RANGE_CONFIG_VCSEL_PERIOD               0x50
+#define VL53L0X_RA_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI          0x51
+#define VL53L0X_RA_PRE_RANGE_CONFIG_TIMEOUT_MACROP_LO          0x52
+
+#define VL53L0X_RA_SYSTEM_HISTOGRAM_BIN                        0x81
+#define VL53L0X_RA_HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT       0x33
+#define VL53L0X_RA_HISTOGRAM_CONFIG_READOUT_CTRL               0x55
+
+#define VL53L0X_RA_FINAL_RANGE_CONFIG_VCSEL_PERIOD             0x70
+#define VL53L0X_RA_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI        0x71
+#define VL53L0X_RA_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_LO        0x72
+#define VL53L0X_RA_CROSSTALK_COMPENSATION_PEAK_RATE_MCPS       0x20
+
+#define VL53L0X_RA_MSRC_CONFIG_TIMEOUT_MACROP                  0x46
+
+#define VL53L0X_RA_SOFT_RESET_GO2_SOFT_RESET_N                 0xBF
+#define VL53L0X_RA_IDENTIFICATION_MODEL_ID                     0xC0
+#define VL53L0X_RA_IDENTIFICATION_REVISION_ID                  0xC2
+
+#define VL53L0X_IDENTIFICATION_MODEL_ID                        0xEEAA
+#define VL53L0X_IDENTIFICATION_REVISION_ID                     0x10
+
+#define VL53L0X_RA_OSC_CALIBRATE_VAL                           0xF8
+
+#define VL53L0X_RA_GLOBAL_CONFIG_VCSEL_WIDTH                   0x32
+#define VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_0            0xB0
+#define VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_1            0xB1
+#define VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_2            0xB2
+#define VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_3            0xB3
+#define VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_4            0xB4
+#define VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_5            0xB5
+
+#define VL53L0X_RA_GLOBAL_CONFIG_REF_EN_START_SELECT           0xB6
+#define VL53L0X_RA_DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD         0x4E
+#define VL53L0X_RA_DYNAMIC_SPAD_REF_EN_START_OFFSET            0x4F
+#define VL53L0X_RA_POWER_MANAGEMENT_GO1_POWER_FORCE            0x80
+
+#define VL53L0X_RA_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV           0x89
+
+#define VL53L0X_RA_ALGO_PHASECAL_LIM                           0x30
+#define VL53L0X_RA_ALGO_PHASECAL_CONFIG_TIMEOUT                0x30
+
+// TCC: Target CentreCheck
+// MSRC: Minimum Signal Rate Check
+// DSS: Dynamic Spad Selection
+typedef struct {
+  bool tcc;
+  bool msrc;
+  bool dss;
+  bool pre_range;
+  bool final_range;
+} SequenceStepEnables;
+
+typedef struct
+{
+  uint16_t pre_range_vcsel_period_pclks, final_range_vcsel_period_pclks;
+  uint16_t msrc_dss_tcc_mclks, pre_range_mclks, final_range_mclks;
+  uint32_t msrc_dss_tcc_us,    pre_range_us,    final_range_us;
+} SequenceStepTimeouts;
+
+typedef enum vcselPeriodType_t { VcselPeriodPreRange, VcselPeriodFinalRange } vcselPeriodType;
+
+/** Default constructor, uses external I2C address.
+ * @see VL53L0X_DEFAULT_ADDRESS
+ */
+void vl53l0xInit(DeckInfo* info);
+
+bool vl53l0xTest(void);
+void vl53l0xTask(void* arg);
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool vl53l0xTestConnection();
+
+/** Get Model ID.
+ * This register is used to verify the model number of the device,
+ * but only before it has been configured to run
+ * @return Model ID
+ * @see VL53L0X_RA_IDENTIFICATION_MODEL_ID
+ * @see VL53L0X_IDENTIFICATION_MODEL_ID
+ */
+uint16_t vl53l0xGetModelID();
+
+/** Get Revision ID.
+ * This register is used to verify the revision number of the device,
+ * but only before it has been configured to run
+ * @return Revision ID
+ * @see VL53L0X_RA_IDENTIFICATION_REVISION_ID
+ * @see VL53L0X_IDENTIFICATION_REVISION_ID
+ */
+uint8_t vl53l0xGetRevisionID();
+
+// Initialize sensor using sequence based on VL53L0X_DataInit(),
+// VL53L0X_StaticInit(), and VL53L0X_PerformRefCalibration().
+// This function does not perform reference SPAD calibration
+// (VL53L0X_PerformRefSpadManagement()), since the API user manual says that it
+// is performed by ST on the bare modules; it seems like that should work well
+// enough unless a cover glass is added.
+// If io_2v8 (optional) is true or not given, the sensor is configured for 2V8
+// mode.
+bool vl53l0xInitSensor(bool io_2v8);
+
+// Set the return signal rate limit check value in units of MCPS (mega counts
+// per second). "This represents the amplitude of the signal reflected from the
+// target and detected by the device"; setting this limit presumably determines
+// the minimum measurement necessary for the sensor to report a valid reading.
+// Setting a lower limit increases the potential range of the sensor but also
+// seems to increase the likelihood of getting an inaccurate reading because of
+// unwanted reflections from objects other than the intended target.
+// Defaults to 0.25 MCPS as initialized by the ST API and this library.
+bool vl53l0xSetSignalRateLimit(float limit_Mcps);
+
+// Set the measurement timing budget in microseconds, which is the time allowed
+// for one measurement; the ST API and this library take care of splitting the
+// timing budget among the sub-steps in the ranging sequence. A longer timing
+// budget allows for more accurate measurements. Increasing the budget by a
+// factor of N decreases the range measurement standard deviation by a factor of
+// sqrt(N). Defaults to about 33 milliseconds; the minimum is 20 ms.
+// based on VL53L0X_set_measurement_timing_budget_micro_seconds()
+bool vl53l0xSetMeasurementTimingBudget(uint32_t budget_us);
+
+// Get the measurement timing budget in microseconds
+// based on VL53L0X_get_measurement_timing_budget_micro_seconds()
+// in us
+uint32_t vl53l0xGetMeasurementTimingBudget(void);
+
+// Set the VCSEL (vertical cavity surface emitting laser) pulse period for the
+// given period type (pre-range or final range) to the given value in PCLKs.
+// Longer periods seem to increase the potential range of the sensor.
+// Valid values are (even numbers only):
+//  pre:  12 to 18 (initialized default: 14)
+//  final: 8 to 14 (initialized default: 10)
+// based on VL53L0X_set_vcsel_pulse_period()
+bool vl53l0xSetVcselPulsePeriod(vcselPeriodType type, uint8_t period_pclks);
+
+// Get the VCSEL pulse period in PCLKs for the given period type.
+// based on VL53L0X_get_vcsel_pulse_period()
+uint8_t vl53l0xGetVcselPulsePeriod(vcselPeriodType type);
+
+// Start continuous ranging measurements. If period_ms (optional) is 0 or not
+// given, continuous back-to-back mode is used (the sensor takes measurements as
+// often as possible); otherwise, continuous timed mode is used, with the given
+// inter-measurement period in milliseconds determining how often the sensor
+// takes a measurement.
+// based on VL53L0X_StartMeasurement()
+void vl53l0xStartContinuous(uint32_t period_ms);
+
+// Stop continuous measurements
+// based on VL53L0X_StopMeasurement()
+void vl53l0xStopContinuous(void);
+
+// Returns a range reading in millimeters when continuous mode is active
+// (readRangeSingleMillimeters() also calls this function after starting a
+// single-shot range measurement)
+uint16_t vl53l0xReadRangeContinuousMillimeters(void);
+
+// Performs a single-shot range measurement and returns the reading in
+// millimeters
+// based on VL53L0X_PerformSingleRangingMeasurement()
+uint16_t vl53l0xReadRangeSingleMillimeters(void);
+
+#endif /* _VL53L0X_H_ */
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/bigquad.c b/crazyflie-firmware-src/src/deck/drivers/src/bigquad.c
new file mode 100644
index 0000000000000000000000000000000000000000..d2dc191d08795029ea580ba6907c5b710cc140ad
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/bigquad.c
@@ -0,0 +1,88 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * exptest.c - Testing of expansion port.
+ */
+#define DEBUG_MODULE "BIGQUAD"
+
+#include <stdint.h>
+#include <string.h>
+
+#include "stm32fxxx.h"
+#include "config.h"
+#include "motors.h"
+#include "debug.h"
+#include "deck.h"
+#include "extrx.h"
+#include "pm.h"
+
+#define BIGQUAD_BAT_VOLT_PIN       DECK_GPIO_MISO
+#define BIGQUAD_BAT_VOLT_MULT      7.8f
+#define BIGQUAD_BAT_CURR_PIN       DECK_GPIO_SCK
+#define BIGQUAD_BAT_AMP_PER_VOLT   1.0f
+
+//Hardware configuration
+static bool isInit;
+
+static void bigquadInit(DeckInfo *info)
+{
+  if(isInit)
+    return;
+
+  DEBUG_PRINT("Switching to brushless.\n");
+  motorsInit(motorMapBigQuadDeck);
+  extRxInit();
+#ifdef BQ_DECK_ENABLE_PM
+  pmEnableExtBatteryVoltMeasuring(BIGQUAD_BAT_VOLT_PIN, BIGQUAD_BAT_VOLT_MULT);
+  pmEnableExtBatteryCurrMeasuring(BIGQUAD_BAT_CURR_PIN, BIGQUAD_BAT_AMP_PER_VOLT);
+#endif
+
+  isInit = true;
+}
+
+static bool bigquadTest()
+{
+  bool status = true;
+
+  if(!isInit)
+    return false;
+
+  status = motorsTest();
+
+  return status;
+}
+
+static const DeckDriver bigquad_deck = {
+  .vid = 0xBC,
+  .pid = 0x05,
+  .name = "bcBigQuad",
+
+  .usedPeriph = DECK_USING_TIMER3 | DECK_USING_TIMER14,
+  .usedGpio = DECK_USING_PA2 | DECK_USING_PA3 | DECK_USING_PB4 | DECK_USING_PB5 | DECK_USING_PA7,
+  .init = bigquadInit,
+  .test = bigquadTest,
+};
+
+#ifdef ENABLE_BQ_DECK
+DECK_DRIVER(bigquad_deck);
+#endif
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/buzzdeck.c b/crazyflie-firmware-src/src/deck/drivers/src/buzzdeck.c
new file mode 100644
index 0000000000000000000000000000000000000000..034f67e73959cb26cd83c05be3701029cec9c101
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/buzzdeck.c
@@ -0,0 +1,69 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * buzzdeck.c - Deck driver for the Crazyflie 2.0 buzzer deck
+ */
+
+#include <stdint.h>
+#include <stdlib.h>
+#include "stm32fxxx.h"
+
+#include "deck.h"
+
+#include "buzzer.h"
+#include "piezo.h"
+
+static void buzzDeckOn(uint32_t freq)
+{
+  piezoSetRatio(128);
+  piezoSetFreq(freq);
+}
+
+static void buzzDeckOff()
+{
+  piezoSetRatio(0);
+}
+
+static struct buzzerControl buzzDeckCtrl = {
+  .on         = buzzDeckOn,
+  .off        = buzzDeckOff
+};
+
+static void buzzDeckInit(DeckInfo *info)
+{
+  piezoInit();
+  buzzerSetControl(&buzzDeckCtrl);
+}
+
+static const DeckDriver buzzer_deck = {
+  .vid = 0xBC,
+  .pid = 0x04,
+  .name = "bcBuzzer",
+
+  .usedPeriph = DECK_USING_TIMER5,
+  .usedGpio = DECK_USING_TX2 | DECK_USING_RX2,
+
+  .init = buzzDeckInit,
+};
+
+DECK_DRIVER(buzzer_deck);
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/cppmdeck.c b/crazyflie-firmware-src/src/deck/drivers/src/cppmdeck.c
new file mode 100644
index 0000000000000000000000000000000000000000..35b0f35d899a057813c345dba9dd3b10f087ad91
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/cppmdeck.c
@@ -0,0 +1,71 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * exptest.c - Testing of expansion port.
+ */
+#define DEBUG_MODULE "CPPM"
+
+#include <stdint.h>
+#include <string.h>
+
+#include "stm32fxxx.h"
+#include "config.h"
+#include "debug.h"
+#include "deck.h"
+#include "extrx.h"
+
+//Hardware configuration
+static bool isInit;
+
+static void cppmdeckInit(DeckInfo *info)
+{
+  if(isInit)
+    return;
+
+  extRxInit();
+
+  isInit = true;
+}
+
+static bool cppmdeckTest()
+{
+  bool status = true;
+
+  if(!isInit)
+    return false;
+
+  return status;
+}
+
+static const DeckDriver cppm_deck = {
+  .vid = 0,
+  .pid = 0,
+  .name = "bcCPPM",
+
+  .usedPeriph = DECK_USING_TIMER14,
+  .usedGpio = DECK_USING_PA7,
+  .init = cppmdeckInit,
+  .test = cppmdeckTest,
+};
+
+DECK_DRIVER(cppm_deck);
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/gtgps.c b/crazyflie-firmware-src/src/deck/drivers/src/gtgps.c
new file mode 100644
index 0000000000000000000000000000000000000000..8cdb7fbc57a4f42d6929acb5e39da6bec4b55436
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/gtgps.c
@@ -0,0 +1,321 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * exptest.c - Testing of expansion port.
+ */
+#define DEBUG_MODULE "GTGPS"
+
+#include <stdint.h>
+#include <string.h>
+#include <stdio.h>
+
+#include "stm32fxxx.h"
+#include "config.h"
+#include "console.h"
+#include "uart1.h"
+#include "debug.h"
+#include "deck.h"
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include "log.h"
+
+static bool isInit;
+
+#define LEN_TOKEN 5
+#define MAX_LEN_SENTANCE 100
+char buff[MAX_LEN_SENTANCE];
+uint8_t bi;
+
+typedef bool (*SentanceParser)(char * buff);
+
+typedef struct {
+  const char * token;
+  SentanceParser parser;
+} ParserConfig;
+
+typedef enum {
+  FixNone = 1,
+  Fix2D = 2,
+  Fix3D = 3
+} FixQuality;
+
+typedef enum {
+  NoFix = 1,
+  GPSFix = 2
+} FixType;
+
+typedef enum {FIELD_COORD, FIELD_FLOAT, FIELD_INT} FieldType;
+
+typedef struct {
+  FixQuality fix;
+  uint32_t locks[12];
+  float pdop;
+  float hdop;
+  float vdop;
+} Basic;
+
+typedef struct {
+  uint32_t fixtime;
+  int32_t latitude;
+  int32_t longitude;
+  FixType fixtype;
+  uint32_t nsat;
+  float hdop;
+  float alt;
+  float height;
+} MeasData;
+
+static Basic b;
+static MeasData m;
+
+// Only use on 0-terminated strings!
+static int skip_to_next(char ** sp, const char ch) {
+  int steps;
+  while (ch != 0 && (**sp) != ch) {
+    (*sp)++;
+    steps++;
+  }
+  if (ch != 0)
+    (*sp)++;
+  return (ch != 0 ? steps : -1);
+}
+
+static int32_t parse_coordinate(char ** sp) {
+  int32_t dm;
+  int32_t degree;
+  int32_t minute;
+  int32_t second;
+  int32_t ret;
+  char * i;
+  char * j;
+
+  // Format as DDDMM.SSSS converted by long or lat = DDD + MM / 100 + SSSS/3600
+  // To avoid inaccuracy caused by float representation save this value as
+  // a large number * 10 M
+
+  // 32 18.0489 N = 32 degrees + 18.0489 / 60 = 32.300815 N
+  dm = strtol(*sp, &i, 10);
+  degree = (dm / 100) * 10000000;
+  minute = ((dm % 100) * 10000000) / 60;
+  second = (strtol(i+1, &j, 10) * 1000) / 60;
+  ret = degree + minute + second;
+  skip_to_next(sp, ',');
+  if (**sp == 'S' || **sp == 'W')
+    ret *= -1;
+  return ret;
+}
+
+static float parse_float(char * sp) {
+  float ret = 0;
+  int major = 0;
+  int minor = 0;
+  int deci_nbr = 0;
+  char * i;
+  char * j;
+
+  major = strtol(sp, &i, 10);
+  // Do decimals
+  if (strncmp(i, ".", 1) == 0) {
+    minor = strtol(i+1, &j, 10);
+    deci_nbr = j - i - 1;
+  }
+  ret = (major * pow(10, deci_nbr) + minor) / pow(10, deci_nbr);
+  //printf("%i.%i == %f (%i) (%c)\n", major, minor, ret, deci_nbr, (int) *i);
+  return ret;
+}
+
+static void parse_next(char ** sp, FieldType t, void * value) {
+  skip_to_next(sp, ',');
+  //DEBUG_PRINT("[%s]\n", (*sp));
+  switch (t) {
+    case FIELD_INT:
+      *((uint32_t*) value) = strtol(*sp, 0, 10);
+      break;
+    case FIELD_FLOAT:
+      *((float*) value) = parse_float(*sp);
+      break;
+    case FIELD_COORD:
+      *((int32_t*) value) = parse_coordinate(sp);
+  }
+}
+
+static bool gpgsaParser(char * buff) {
+  int i = 0;
+  char * sp = buff;
+
+  // Skip leading A/M
+  skip_to_next(&sp, ',');
+
+  parse_next(&sp, FIELD_INT, &b.fix);
+  for (i = 0; i < 12; i++) {
+    parse_next(&sp, FIELD_INT, &b.locks[i]);
+  }
+  parse_next(&sp, FIELD_FLOAT, &b.pdop);
+  parse_next(&sp, FIELD_FLOAT, &b.hdop);
+  parse_next(&sp, FIELD_FLOAT, &b.vdop);
+
+  //dbg_print_basic(&b);
+  return false;
+}
+
+static bool gpggaParser(char * buff) {
+  char * sp = buff;
+
+  parse_next(&sp, FIELD_INT, &m.fixtime);
+  parse_next(&sp, FIELD_COORD, &m.latitude);
+  parse_next(&sp, FIELD_COORD, &m.longitude);
+  parse_next(&sp, FIELD_INT, &m.fixtype);
+  parse_next(&sp, FIELD_INT, &m.nsat);
+  parse_next(&sp, FIELD_FLOAT, &m.hdop);
+  parse_next(&sp, FIELD_FLOAT, &m.alt);
+  skip_to_next(&sp, ',');
+  // Unit for altitude (not used yet)
+  parse_next(&sp, FIELD_FLOAT, &m.height);
+  skip_to_next(&sp, ',');
+  // Unit for height (not used yet)
+  skip_to_next(&sp, ',');
+  //consolePutchar('.');
+  //consoleFlush();
+  return false;
+}
+
+static ParserConfig parsers[] = {
+  {.token = "GPGSA", .parser = gpgsaParser},
+  {.token = "GPGGA", .parser = gpggaParser}
+};
+
+static bool verifyChecksum(const char * buff) {
+  uint8_t test_chksum = 0;
+  uint32_t ref_chksum = 0;
+  uint8_t i = 0;
+  while (buff[i] != '*' && i < MAX_LEN_SENTANCE-3) {
+    test_chksum ^= buff[i++];
+  }
+  ref_chksum = strtol(&buff[i+1], 0, 16);
+
+  return (test_chksum == ref_chksum);
+}
+
+static uint8_t baudcmd[] = "$PMTK251,115200*1F\r\n";
+
+// 5 Hz
+static uint8_t updaterate[] = "$PMTK220,200*2C\r\n";
+static uint8_t updaterate2[] = "$PMTK300,200,0,0,0,0*2F\r\n";
+
+// 10 Hz
+//static uint8_t updaterate3[] = "$PMTK220,100*2F\r\n";
+//static uint8_t updaterate4[] = "$PMTK300,100,0,0,0,0*2C\r\n";
+
+
+void gtgpsTask(void *param)
+{
+  char ch;
+  int j;
+
+  uart1SendData(sizeof(baudcmd), baudcmd);
+
+  vTaskDelay(500);
+  uart1Init(115200);
+  vTaskDelay(500);
+
+  uart1SendData(sizeof(updaterate), updaterate);
+  uart1SendData(sizeof(updaterate2), updaterate2);
+
+//  uart1SendData(sizeof(updaterate3), updaterate3);
+//  uart1SendData(sizeof(updaterate4), updaterate4);
+
+
+  while(1)
+  {
+    uart1Getchar(&ch);
+    consolePutchar(ch);
+
+    if (ch == '$') {
+      bi = 0;
+    } else if (ch == '\n') {
+      buff[bi] = 0; // Terminate with null
+      if (verifyChecksum(buff)) {
+        //DEBUG_PRINT("O");
+        for (j = 0; j < sizeof(parsers)/sizeof(parsers[0]); j++) {
+          if (strncmp(parsers[j].token, buff, LEN_TOKEN) == 0) {
+            parsers[j].parser(&buff[LEN_TOKEN]);
+          }
+        }
+      }
+    } else if (bi < MAX_LEN_SENTANCE) {
+      buff[bi++] = ch;
+    }
+  }
+}
+
+
+static void gtgpsInit(DeckInfo *info)
+{
+  if(isInit)
+    return;
+
+  DEBUG_PRINT("Enabling reading from GlobalTop GPS\n");
+  uart1Init(9600);
+
+  xTaskCreate(gtgpsTask, "GTGPS",
+              configMINIMAL_STACK_SIZE, NULL, /*priority*/1, NULL);
+
+  isInit = true;
+}
+
+static bool gtgpsTest()
+{
+  bool status = true;
+
+  if(!isInit)
+    return false;
+
+  return status;
+}
+
+static const DeckDriver gtgps_deck = {
+  .vid = 0xBC,
+  .pid = 0x07,
+  .name = "bcGTGPS",
+
+  .usedPeriph = 0,
+  .usedGpio = 0,               // FIXME: Edit the used GPIOs
+
+  .init = gtgpsInit,
+  .test = gtgpsTest,
+};
+
+DECK_DRIVER(gtgps_deck);
+
+LOG_GROUP_START(gps)
+LOG_ADD(LOG_INT32, lat, &m.latitude)
+LOG_ADD(LOG_INT32, lon, &m.longitude)
+LOG_ADD(LOG_FLOAT, hMSL, &m.height)
+LOG_ADD(LOG_FLOAT, hAcc, &b.pdop)
+LOG_ADD(LOG_INT32, nsat, &m.nsat)
+LOG_ADD(LOG_INT32, fix, &b.fix)
+LOG_GROUP_STOP(gps)
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/ledring12.c b/crazyflie-firmware-src/src/deck/drivers/src/ledring12.c
new file mode 100644
index 0000000000000000000000000000000000000000..68a208aeed1737089e1d71af6668215231212e70
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/ledring12.c
@@ -0,0 +1,662 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * ledring12.c: RGB Ring 12 Leds effects/driver
+ */
+
+#include "ledring12.h"
+
+#include <stdint.h>
+#include <math.h>
+#include <string.h>
+
+#include "stm32fxxx.h"
+
+#include "deck.h"
+
+#include "FreeRTOS.h"
+#include "timers.h"
+
+#include "ledring12.h"
+#include "ws2812.h"
+#include "worker.h"
+#include "param.h"
+#include "pm.h"
+#include "log.h"
+
+
+/*
+ * To add a new effect just add it as a static function with the prototype
+ * void effect(uint8_t buffer[][3], bool reset)
+ *
+ * Then add it to the effectsFct[] list bellow. It will automatically be
+ * activated using the ring.effect parameter.
+ *
+ * The ring color needs to be written in the buffer argument. The buffer is not
+ * modified in memory as long as reset is not 'true', see the spin effects for
+ * and example.
+ *
+ * The log subsystem can be used to get the value of any log variable of the
+ * system. See tiltEffect for an example.
+ */
+
+typedef void (*Ledring12Effect)(uint8_t buffer[][3], bool reset);
+
+/**************** Some useful macros ***************/
+
+#define RED {0x10, 0x00, 0x00}
+#define GREEN {0x00, 0x10, 0x00}
+#define BLUE {0x00, 0x00, 0x10}
+#define WHITE {0xff, 0xff, 0xff}
+#define BLACK {0x00, 0x00, 0x00}
+
+#define MAX(a,b) ((a>b)?a:b)
+#define MIN(a,b) ((a<b)?a:b)
+#define COPY_COLOR(dest, orig) dest[0]=orig[0]; dest[1]=orig[1]; dest[2]=orig[2]
+#define ADD_COLOR(dest, o1, o2) dest[0]=(o1[0]>>1)+(o2[0]>>1);dest[1]=(o1[1]>>1)+(o2[1]>>1);dest[2]=(o1[2]>>1)+(o2[2]>>1);
+#define LIMIT(a) ((a>255)?255:(a<0)?0:a)
+#define SIGN(a) ((a>=0)?1:-1)
+#define DEADBAND(a, b) ((a<b) ? 0:a)
+#define LINSCALE(domain_low, domain_high, codomain_low, codomain_high, value) ((codomain_high - codomain_low) / (domain_high - domain_low)) * (value - domain_low) + codomain_low
+#define SET_WHITE(dest, intensity) dest[0] = intensity; dest[1] = intensity; dest[2] = intensity;
+
+static uint32_t effect = 6;
+static uint32_t neffect;
+static uint8_t headlightEnable = 0;
+static uint8_t black[][3] = {BLACK, BLACK, BLACK,
+                             BLACK, BLACK, BLACK,
+                             BLACK, BLACK, BLACK,
+                             BLACK, BLACK, BLACK,
+                            };
+
+static const uint8_t green[] = {0x00, 0xFF, 0x00};
+static const uint8_t red[] = {0xFF, 0x00, 0x00};
+static const uint8_t blue[] = {0x00, 0x00, 0xFF};
+static const uint8_t white[] = WHITE;
+static const uint8_t part_black[] = BLACK;
+
+uint8_t ledringmem[NBR_LEDS * 2];
+
+/**************** Black (LEDs OFF) ***************/
+
+static void blackEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+
+  if (reset)
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      buffer[i][0] = 0;
+      buffer[i][1] = 0;
+      buffer[i][2] = 0;
+    }
+  }
+}
+
+/**************** White spin ***************/
+static const uint8_t whiteRing[][3] = {{32, 32, 32}, {8,8,8}, {2,2,2},
+                                       BLACK, BLACK, BLACK,
+                                       BLACK, BLACK, BLACK,
+                                       BLACK, BLACK, BLACK,
+                                      };
+
+static const uint8_t blueRing[][3] = {{64, 64, 255}, {32,32,64}, {8,8,16},
+                                       BLACK, BLACK, BLACK,
+                                       BLACK, BLACK, BLACK,
+                                       BLACK, BLACK, BLACK,
+                                      };
+
+static const uint8_t greenRing[][3] = {{64, 255, 64}, {32,64,32}, {8,16,8},
+                                       BLACK, BLACK, BLACK,
+                                       BLACK, BLACK, BLACK,
+                                       BLACK, BLACK, BLACK,
+                                      };
+
+static const uint8_t redRing[][3] = {{64, 0, 0}, {16,0,0}, {8,0,0},
+                                       {4,0,0}, {2,0,0}, {1,0,0},
+                                       BLACK, BLACK, BLACK,
+                                       BLACK, BLACK, BLACK,
+                                      };
+
+static void whiteSpinEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+  uint8_t temp[3];
+
+  if (reset)
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      COPY_COLOR(buffer[i], whiteRing[i]);
+    }
+  }
+
+  COPY_COLOR(temp, buffer[0]);
+  for (i=0; i<(NBR_LEDS-1); i++) {
+    COPY_COLOR(buffer[i], buffer[i+1]);
+  }
+  COPY_COLOR(buffer[(NBR_LEDS-1)], temp);
+}
+
+static uint8_t solidRed=20, solidGreen=20, solidBlue=20;
+static float glowstep = 0.05;
+static void solidColorEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+  static float brightness=0;
+
+  if (reset) brightness = 0;
+
+  if (brightness<1) brightness += 0.05f;
+  else brightness = 1;
+
+  for (i=0; i<NBR_LEDS; i++)
+  {
+    buffer[i][0] = solidRed*brightness;
+    buffer[i][1] = solidGreen*brightness;
+    buffer[i][2] = solidBlue*brightness;
+  }
+}
+
+static void virtualMemEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+
+  if (reset)
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      COPY_COLOR(buffer[i], part_black);
+    }
+  }
+
+  for (i = 0; i < NBR_LEDS; i++)
+  {
+    uint8_t R5, G6, B5;
+    uint8_t (*led)[2] = (uint8_t (*)[2])ledringmem;
+    // Convert from RGB565 to RGB888
+    R5 = led[i][0] >> 3;
+    G6 = ((led[i][0] & 0x07) << 3) | (led[i][1] >> 5);
+    B5 = led[i][1] & 0x1F;
+    buffer[i][0] = ((uint16_t)R5 * 527 + 23 ) >> 6;
+    buffer[i][1] = ((uint16_t)G6 * 259 + 33 ) >> 6;
+    buffer[i][2] = ((uint16_t)B5 * 527 + 23 ) >> 6;
+  }
+}
+
+static void boatEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+
+  uint8_t reds[] = {1,2,3,4,5};
+  uint8_t greens[] = {7,8,9,10,11};
+  uint8_t whites[] = {0};
+  uint8_t blacks[] = {6};
+
+
+  for (i=0; i<sizeof(reds); i++)
+  {
+    COPY_COLOR(buffer[reds[i]], red);
+  }
+
+  for (i=0; i<sizeof(greens); i++)
+  {
+    COPY_COLOR(buffer[greens[i]], green);
+  }
+
+  for (i=0; i<sizeof(whites); i++)
+  {
+    COPY_COLOR(buffer[whites[i]], white);
+  }
+
+  for (i=0; i<sizeof(blacks); i++)
+  {
+    COPY_COLOR(buffer[blacks[i]], part_black);
+  }
+
+
+}
+
+/**************** Color spin ***************/
+
+static const uint8_t colorRing[][3] = {{0,0,32}, {0,0,16}, {0,0,8},
+                                       {0,0,4}, {16,16,16}, {8,8,8},
+                                       {4,4,4},{32,0,0},{16,0,0},
+                                       {8,0,0}, {4,0,0}, {2,0,0},
+                                      };
+
+static void colorSpinEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+  uint8_t temp[3];
+
+  if (reset)
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      COPY_COLOR(buffer[i], colorRing[i]);
+    }
+  }
+
+  COPY_COLOR(temp, buffer[0]);
+  for (i=0; i<(NBR_LEDS-1); i++) {
+    COPY_COLOR(buffer[i], buffer[i+1]);
+  }
+  COPY_COLOR(buffer[(NBR_LEDS-1)], temp);
+}
+
+static void spinEffect2(uint8_t buffer[][3], bool reset)
+{
+  int i;
+  uint8_t temp[3];
+
+  if (reset)
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      COPY_COLOR(buffer[(NBR_LEDS-i)%NBR_LEDS], blueRing[i]);
+    }
+  }
+
+  COPY_COLOR(temp, buffer[(NBR_LEDS-1)]);
+  for (i=(NBR_LEDS-1); i>=0; i--) {
+    COPY_COLOR(buffer[i], buffer[i-1]);
+  }
+  COPY_COLOR(buffer[0], temp);
+}
+
+static void doubleSpinEffect(uint8_t buffer[][3], bool reset) {
+  static uint8_t sub1[NBR_LEDS][3];
+  static uint8_t sub2[NBR_LEDS][3];
+  int i;
+  static int step;
+
+  if (reset) step = 0;
+
+  whiteSpinEffect(sub1, reset);
+  spinEffect2(sub2, reset);
+  //if ((step%3)) spinEffect2(sub2, false);
+  //if (reset) spinEffect2(sub2, true);
+
+  for (i=0; i<NBR_LEDS; i++)
+  {
+    ADD_COLOR(buffer[i], sub1[i], sub2[i]);
+  }
+
+  step ++;
+}
+
+/**************** Dynamic tilt effect ***************/
+
+static void tiltEffect(uint8_t buffer[][3], bool reset)
+{
+  static int pitchid, rollid, thrust=-1;
+
+  // 2014-12-28 chad: Reset LEDs to off to avoid color artifacts
+  // when switching from other effects.
+  if (reset)
+    {
+        int i;
+        for (i=0; i<NBR_LEDS; i++) {
+            buffer[i][0] = 0;
+            buffer[i][1] = 0;
+            buffer[i][2] = 0;
+        }
+    }
+
+
+  if (thrust<0) {
+    //Init
+    pitchid = logGetVarId("stabilizer", "pitch");
+    rollid = logGetVarId("stabilizer", "roll");
+    thrust = logGetVarId("stabilizer", "thrust");
+  } else {
+    const int led_middle = 10;
+    float pitch = -1*logGetFloat(pitchid);
+    float roll  = -1*logGetFloat(rollid);
+
+    pitch = (pitch>20)?20:(pitch<-20)?-20:pitch;
+    roll = (roll>20)?20:(roll<-20)?-20:roll;
+
+    pitch=SIGN(pitch)*pitch*pitch;
+    roll*=SIGN(roll)*roll;
+
+    buffer[11][0] = LIMIT(led_middle + pitch);
+    buffer[0][0] = LIMIT(led_middle + pitch);
+    buffer[1][0] = LIMIT(led_middle + pitch);
+
+    buffer[2][2] = LIMIT(led_middle - roll);
+    buffer[3][2] = LIMIT(led_middle - roll);
+    buffer[4][2] = LIMIT(led_middle - roll);
+
+    buffer[5][0] = LIMIT(led_middle - pitch);
+    buffer[6][0] = LIMIT(led_middle - pitch);
+    buffer[7][0] = LIMIT(led_middle - pitch);
+
+    buffer[8][2] = LIMIT(led_middle + roll);
+    buffer[9][2] = LIMIT(led_middle + roll);
+    buffer[10][2] = LIMIT(led_middle + roll);
+  }
+}
+
+
+/*************** Gravity light effect *******************/
+
+static float gravityLightCalculateAngle(float pitch, float roll);
+static void gravityLightRender(uint8_t buffer[][3], float led_index, int intensity);
+
+static void gravityLight(uint8_t buffer[][3], bool reset)
+{
+  static int pitchid, rollid;
+  static bool isInitialized = false;
+
+  if (!isInitialized) {
+    pitchid = logGetVarId("stabilizer", "pitch");
+    rollid = logGetVarId("stabilizer", "roll");
+    isInitialized = true;
+  }
+
+  float pitch = logGetFloat(pitchid); // -180 to 180
+  float roll = logGetFloat(rollid); // -180 to 180
+
+  float angle = gravityLightCalculateAngle(pitch, roll);
+  float led_index = NBR_LEDS * angle / (2 * (float) M_PI);
+  int intensity = LIMIT(sqrtf(pitch * pitch + roll * roll));
+  gravityLightRender(buffer, led_index, intensity);
+}
+
+static float gravityLightCalculateAngle(float pitch, float roll) {
+  float angle = 0.0;
+
+  if (roll != 0) {
+    angle = atanf(pitch / roll) + (float) M_PI_2;
+
+    if (roll < 0.0) {
+      angle += (float) M_PI;
+    }
+  }
+
+  return angle;
+}
+
+static void gravityLightRender(uint8_t buffer[][3], float led_index, int intensity) {
+  float width = 5;
+  float height = intensity;
+
+  int i;
+  for (i = 0; i < NBR_LEDS; i++) {
+	float distance = fabsf(led_index - i);
+	if (distance > NBR_LEDS / 2) {
+		distance = NBR_LEDS - distance;
+	}
+
+	int col = height - distance * (height / (width / 2));
+	SET_WHITE(buffer[i], LIMIT(col));
+  }
+}
+
+
+/*************** Brightness effect ********************/
+
+#define MAX_RATE 512
+
+static void brightnessEffect(uint8_t buffer[][3], bool reset)
+{
+
+  static int gyroYid, gyroZid, gyroXid =- 1;
+  static uint8_t brightness = 0;
+
+  if (gyroXid < 0)
+  {
+    //Init
+    gyroXid = logGetVarId("gyro", "x");
+    gyroYid = logGetVarId("gyro", "y");
+    gyroZid = logGetVarId("gyro", "z");
+  }
+  else
+  {
+    int i;
+    int gyroX = (int)logGetFloat(gyroXid);
+    int gyroY = (int)logGetFloat(gyroYid);
+    int gyroZ = (int)logGetFloat(gyroZid);
+
+    // Adjust to interval
+    gyroX = (gyroX>MAX_RATE) ? MAX_RATE:(gyroX<-MAX_RATE) ? -MAX_RATE:gyroX;
+    gyroY = (gyroY>MAX_RATE) ? MAX_RATE:(gyroY<-MAX_RATE) ? -MAX_RATE:gyroY;
+    gyroZ = (gyroZ>MAX_RATE) ? MAX_RATE:(gyroZ<-MAX_RATE) ? -MAX_RATE:gyroZ;
+
+    gyroX = SIGN(gyroX) * gyroX / 2;
+    gyroY = SIGN(gyroY) * gyroY / 2;
+    gyroZ = SIGN(gyroZ) * gyroZ / 2;
+
+    gyroX = DEADBAND(gyroX, 5);
+    gyroY = DEADBAND(gyroY, 5);
+    gyroZ = DEADBAND(gyroZ, 5);
+
+    for (i=0; i < NBR_LEDS; i++)
+    {
+      buffer[i][0] = (uint8_t)(LIMIT(gyroZ));
+      buffer[i][1] = (uint8_t)(LIMIT(gyroY));
+      buffer[i][2] = (uint8_t)(LIMIT(gyroX));
+    }
+
+    brightness++;
+  }
+}
+
+
+static void setHeadlightsOn(bool on)
+{
+  if (on)
+    GPIO_SetBits(GPIOB, GPIO_Pin_4);
+  else
+    GPIO_ResetBits(GPIOB, GPIO_Pin_4);
+}
+
+
+/* LED-ring test effect */
+#define TEST_INTENTS 20
+static uint8_t test_pat[3][3] = {{TEST_INTENTS, 0, 0}, {0, TEST_INTENTS, 0}, {0, 0, TEST_INTENTS}};
+static uint8_t test_eff_nbr = 0;
+#define TEST_DELAY 4
+static uint8_t test_delay_counter = 0;
+static uint8_t headlight_test_counter =0;
+static uint8_t test_front = false;
+static void ledTestEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+  static float brightness=0;
+
+  if (reset) brightness = 0;
+
+  if (brightness<1) brightness += 0.05f;
+  else brightness = 1;
+
+  for (i=0; i<NBR_LEDS; i++)
+  {
+    buffer[i][0] = test_pat[test_eff_nbr][0];
+    buffer[i][1] = test_pat[test_eff_nbr][1];
+    buffer[i][2] = test_pat[test_eff_nbr][2];
+  }
+
+  test_delay_counter++;
+  headlight_test_counter++;
+
+  if (test_delay_counter > TEST_DELAY) {
+    test_delay_counter = 0;
+    test_eff_nbr = (test_eff_nbr + 1) % 3;
+  }
+
+  if (headlight_test_counter > (TEST_DELAY*3)) {
+    headlight_test_counter = 0;
+    test_front = !test_front;
+    headlightEnable = test_front;
+  }
+}
+
+/**
+ * An effect that shows the battery charge on the LED ring.
+ *
+ * Red means empty, blue means full.
+ */
+static float emptyCharge = 3.1, fullCharge = 4.2;
+static void batteryChargeEffect(uint8_t buffer[][3], bool reset)
+{
+  int i;
+  static int vbatid;
+  float vbat;
+
+  vbatid = logGetVarId("pm", "vbat");
+  vbat = logGetFloat(vbatid);
+
+  for (i = 0; i < NBR_LEDS; i++) {
+    buffer[i][0] = LIMIT(LINSCALE(emptyCharge, fullCharge, 255, 0, vbat)); // Red (emtpy)
+    buffer[i][1] = 0; // Green
+    buffer[i][2] = LIMIT(LINSCALE(emptyCharge, fullCharge, 0, 255, vbat)); // Blue (charged)
+  }
+}
+
+/**
+ * An effect mimicking a blue light siren
+ */
+static void siren(uint8_t buffer[][3], bool reset)
+{
+  int i;
+  static int tic = 0;
+
+  if (reset)
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      COPY_COLOR(buffer[i], part_black);
+    }
+  }
+
+  if ((tic < 10) && (tic & 1))
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      COPY_COLOR(buffer[i], blue);
+    }
+  }
+  else
+  {
+    for (i=0; i<NBR_LEDS; i++) {
+      COPY_COLOR(buffer[i], part_black);
+    }
+  }
+  if (++tic >= 20) tic = 0;
+}
+
+/**************** Effect list ***************/
+
+
+Ledring12Effect effectsFct[] =
+{
+  blackEffect,
+  whiteSpinEffect,
+  colorSpinEffect,
+  tiltEffect,
+  brightnessEffect,
+  spinEffect2,
+  doubleSpinEffect,
+  solidColorEffect,
+  ledTestEffect,
+  batteryChargeEffect,
+  boatEffect,
+  siren,
+  gravityLight,
+  virtualMemEffect,
+}; //TODO Add more
+
+/********** Ring init and switching **********/
+static xTimerHandle timer;
+
+
+
+void ledring12Worker(void * data)
+{
+  static int current_effect = 0;
+  static uint8_t buffer[NBR_LEDS][3];
+  bool reset = true;
+
+  if (/*!pmIsDischarging() ||*/ (effect > neffect)) {
+    ws2812Send(black, NBR_LEDS);
+    return;
+  }
+
+  if (current_effect != effect) {
+    reset = true;
+  } else {
+    reset = false;
+  }
+  current_effect = effect;
+
+  effectsFct[current_effect](buffer, reset);
+  ws2812Send(buffer, NBR_LEDS);
+}
+
+static void ledring12Timer(xTimerHandle timer)
+{
+  workerSchedule(ledring12Worker, NULL);
+
+  setHeadlightsOn(headlightEnable);
+}
+
+static void ledring12Init(DeckInfo *info)
+{
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  ws2812Init();
+
+  neffect = sizeof(effectsFct)/sizeof(effectsFct[0])-1;
+
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_NOPULL;
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  timer = xTimerCreate( "ringTimer", M2T(50),
+                                     pdTRUE, NULL, ledring12Timer );
+  xTimerStart(timer, 100);
+}
+
+PARAM_GROUP_START(ring)
+PARAM_ADD(PARAM_UINT8, effect, &effect)
+PARAM_ADD(PARAM_UINT32 | PARAM_RONLY, neffect, &neffect)
+PARAM_ADD(PARAM_UINT8, solidRed, &solidRed)
+PARAM_ADD(PARAM_UINT8, solidGreen, &solidGreen)
+PARAM_ADD(PARAM_UINT8, solidBlue, &solidBlue)
+PARAM_ADD(PARAM_UINT8, headlightEnable, &headlightEnable)
+PARAM_ADD(PARAM_FLOAT, glowstep, &glowstep)
+PARAM_ADD(PARAM_FLOAT, emptyCharge, &emptyCharge)
+PARAM_ADD(PARAM_FLOAT, fullCharge, &fullCharge)
+PARAM_GROUP_STOP(ring)
+
+static const DeckDriver ledring12_deck = {
+  .vid = 0xBC,
+  .pid = 0x01,
+  .name = "bcLedRing",
+
+  .usedPeriph = DECK_USING_TIMER3,
+  .usedGpio = DECK_USING_IO_2 | DECK_USING_IO_3,
+
+  .init = ledring12Init,
+};
+
+DECK_DRIVER(ledring12_deck);
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/locodeck.c b/crazyflie-firmware-src/src/deck/drivers/src/locodeck.c
new file mode 100644
index 0000000000000000000000000000000000000000..7eef44b0c161030c8d22777d0dfdef6ae94ddeaf
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/locodeck.c
@@ -0,0 +1,375 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2016 Bitcraze AB
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.  IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * locodeck.c: Dwm1000 deck driver.
+ */
+
+#define DEBUG_MODULE "DWM"
+
+#include <stdint.h>
+#include <string.h>
+#include "stm32fxxx.h"
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+#include "task.h"
+
+#include "deck.h"
+#include "system.h"
+#include "debug.h"
+#include "log.h"
+#include "param.h"
+#include "nvicconf.h"
+
+#include "locodeck.h"
+
+#if LPS_TDOA_ENABLE
+  #include "lpsTdoaTag.h"
+#else
+  #include "lpsTwrTag.h"
+#endif
+
+
+#define CS_PIN DECK_GPIO_IO1
+
+#if LPS_TDOA_ENABLE
+  #define RX_TIMEOUT 10000
+#else
+  #define RX_TIMEOUT 1000
+#endif
+
+
+#define ANTENNA_OFFSET 154.6   // In meter
+
+// The anchor position can be set using parameters
+// As an option you can set a static position in this file and set
+// anchorPositionOk to enable sending the anchor rangings to the Kalman filter
+
+static lpsAlgoOptions_t algoOptions = {
+  .tagAddress = 0xbccf000000000008,
+  .anchorAddress = {
+    0xbccf000000000001,
+    0xbccf000000000002,
+    0xbccf000000000003,
+    0xbccf000000000004,
+    0xbccf000000000005,
+    0xbccf000000000006
+  },
+  .antennaDelay = (ANTENNA_OFFSET*499.2e6*128)/299792458.0, // In radio tick
+  .rangingFailedThreshold = 6,
+ 
+  .anchorPositionOk = false,
+
+  // To set a static anchor position from startup, uncomment and modify the
+  // following code:
+/*
+  .anchorPosition = {
+    {x: 0.99, y: 1.49, z: 1.80},
+    {x: 0.99, y: 3.29, z: 1.80},
+    {x: 4.67, y: 2.54, z: 1.80},
+    {x: 0.59, y: 2.27, z: 0.20},
+    {x: 4.70, y: 3.38, z: 0.20},
+    {x: 4.70, y: 1.14, z: 0.20},
+  },
+  .anchorPositionOk = true,
+*/
+};
+
+#if LPS_TDOA_ENABLE
+static uwbAlgorithm_t *algorithm = &uwbTdoaTagAlgorithm;
+#else
+static uwbAlgorithm_t *algorithm = &uwbTwrTagAlgorithm;
+#endif
+
+static bool isInit = false;
+static xSemaphoreHandle spiSemaphore;
+static SemaphoreHandle_t irqSemaphore;
+static dwDevice_t dwm_device;
+static dwDevice_t *dwm = &dwm_device;
+
+static uint32_t timeout;
+
+static void txCallback(dwDevice_t *dev)
+{
+  timeout = algorithm->onEvent(dev, eventPacketSent);
+}
+
+static void rxCallback(dwDevice_t *dev)
+{
+  timeout = algorithm->onEvent(dev, eventPacketReceived);
+}
+
+static void rxTimeoutCallback(dwDevice_t * dev) {
+  timeout = algorithm->onEvent(dev, eventReceiveTimeout);
+}
+
+// static void rxfailedcallback(dwDevice_t *dev) {
+//   timeout = algorithm->onEvent(dev, eventReceiveFailed);
+// }
+
+
+static void uwbTask(void* parameters)
+{
+  systemWaitStart();
+
+  algorithm->init(dwm, &algoOptions);
+
+  while(1) {
+    if (xSemaphoreTake(irqSemaphore, timeout/portTICK_PERIOD_MS)) {
+      do{
+          dwHandleInterrupt(dwm);
+      } while(digitalRead(DECK_GPIO_RX1) != 0);
+    } else {
+      timeout = algorithm->onEvent(dwm, eventTimeout);
+    }
+  }
+}
+
+static uint8_t spiTxBuffer[196];
+static uint8_t spiRxBuffer[196];
+
+/************ Low level ops for libdw **********/
+static void spiWrite(dwDevice_t* dev, const void *header, size_t headerLength,
+                                      const void* data, size_t dataLength)
+{
+  xSemaphoreTake(spiSemaphore, portMAX_DELAY);
+
+  digitalWrite(CS_PIN, LOW);
+  memcpy(spiTxBuffer, header, headerLength);
+  memcpy(spiTxBuffer+headerLength, data, dataLength);
+  spiExchange(headerLength+dataLength, spiTxBuffer, spiRxBuffer);
+  digitalWrite(CS_PIN, HIGH);
+
+  xSemaphoreGive(spiSemaphore);
+}
+
+static void spiRead(dwDevice_t* dev, const void *header, size_t headerLength,
+                                     void* data, size_t dataLength)
+{
+  xSemaphoreTake(spiSemaphore, portMAX_DELAY);
+
+  digitalWrite(CS_PIN, LOW);
+  memcpy(spiTxBuffer, header, headerLength);
+  memset(spiTxBuffer+headerLength, 0, dataLength);
+  spiExchange(headerLength+dataLength, spiTxBuffer, spiRxBuffer);
+  memcpy(data, spiRxBuffer+headerLength, dataLength);
+  digitalWrite(CS_PIN, HIGH);
+
+  xSemaphoreGive(spiSemaphore);
+}
+
+void __attribute__((used)) EXTI11_Callback(void)
+{
+  portBASE_TYPE  xHigherPriorityTaskWoken = pdFALSE;
+
+  NVIC_ClearPendingIRQ(EXTI15_10_IRQn);
+  EXTI_ClearITPendingBit(EXTI_Line11);
+
+  //To unlock RadioTask
+  xSemaphoreGiveFromISR(irqSemaphore, &xHigherPriorityTaskWoken);
+
+  if(xHigherPriorityTaskWoken)
+    portYIELD();
+}
+
+static void spiSetSpeed(dwDevice_t* dev, dwSpiSpeed_t speed)
+{
+  if (speed == dwSpiSpeedLow)
+  {
+    spiConfigureSlow();
+  }
+  else if (speed == dwSpiSpeedHigh)
+  {
+    spiConfigureFast();
+  }
+}
+
+static void delayms(dwDevice_t* dev, unsigned int delay)
+{
+  vTaskDelay(M2T(delay));
+}
+
+static dwOps_t dwOps = {
+  .spiRead = spiRead,
+  .spiWrite = spiWrite,
+  .spiSetSpeed = spiSetSpeed,
+  .delayms = delayms,
+};
+
+/*********** Deck driver initialization ***************/
+
+static void dwm1000Init(DeckInfo *info)
+{
+  EXTI_InitTypeDef EXTI_InitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  spiBegin();
+
+  // Init IRQ input
+  bzero(&GPIO_InitStructure, sizeof(GPIO_InitStructure));
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+  //GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
+  GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+  SYSCFG_EXTILineConfig(EXTI_PortSourceGPIOC, EXTI_PinSource11);
+
+  EXTI_InitStructure.EXTI_Line = EXTI_Line11;
+  EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+  EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+  EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+  EXTI_Init(&EXTI_InitStructure);
+
+  // Init reset output
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+  GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+  // Init CS pin
+  pinMode(CS_PIN, OUTPUT);
+
+  // Reset the DW1000 chip
+  GPIO_WriteBit(GPIOC, GPIO_Pin_10, 0);
+  vTaskDelay(M2T(10));
+  GPIO_WriteBit(GPIOC, GPIO_Pin_10, 1);
+  vTaskDelay(M2T(10));
+
+  // Semaphore that protect the SPI communication
+  spiSemaphore = xSemaphoreCreateMutex();
+
+  // Initialize the driver
+  dwInit(dwm, &dwOps);       // Init libdw
+
+  int result = dwConfigure(dwm);
+  if (result != 0) {
+    isInit = false;
+    DEBUG_PRINT("Failed to configure DW1000!\r\n");
+    return;
+  }
+
+  dwEnableAllLeds(dwm);
+
+  dwTime_t delay = {.full = 0};
+  dwSetAntenaDelay(dwm, delay);
+
+  dwAttachSentHandler(dwm, txCallback);
+  dwAttachReceivedHandler(dwm, rxCallback);
+  dwAttachReceiveTimeoutHandler(dwm, rxTimeoutCallback);
+
+  dwNewConfiguration(dwm);
+  dwSetDefaults(dwm);
+  dwEnableMode(dwm, MODE_SHORTDATA_FAST_ACCURACY);
+  dwSetChannel(dwm, CHANNEL_2);
+  dwSetPreambleCode(dwm, PREAMBLE_CODE_64MHZ_9);
+
+  dwSetReceiveWaitTimeout(dwm, RX_TIMEOUT);
+
+  dwCommitConfiguration(dwm);
+
+  // Enable interrupt
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_LOW_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  vSemaphoreCreateBinary(irqSemaphore);
+
+  xTaskCreate(uwbTask, "lps", 3*configMINIMAL_STACK_SIZE, NULL,
+                    5/*priority*/, NULL);
+
+  isInit = true;
+}
+
+static bool dwm1000Test()
+{
+  if (!isInit) {
+    DEBUG_PRINT("Error while initializing DWM1000\n");
+  }
+
+  return isInit;
+}
+
+static const DeckDriver dwm1000_deck = {
+  .vid = 0xBC,
+  .pid = 0x06,
+  .name = "bcDWM1000",
+
+  .usedGpio = 0,  // FIXME: set the used pins
+
+  .init = dwm1000Init,
+  .test = dwm1000Test,
+};
+
+DECK_DRIVER(dwm1000_deck);
+
+LOG_GROUP_START(ranging)
+LOG_ADD(LOG_FLOAT, distance1, &algoOptions.distance[0])
+LOG_ADD(LOG_FLOAT, distance2, &algoOptions.distance[1])
+LOG_ADD(LOG_FLOAT, distance3, &algoOptions.distance[2])
+LOG_ADD(LOG_FLOAT, distance4, &algoOptions.distance[3])
+LOG_ADD(LOG_FLOAT, distance5, &algoOptions.distance[4])
+LOG_ADD(LOG_FLOAT, distance6, &algoOptions.distance[5])
+LOG_ADD(LOG_FLOAT, distance7, &algoOptions.distance[6])
+LOG_ADD(LOG_FLOAT, distance8, &algoOptions.distance[7])
+LOG_ADD(LOG_FLOAT, pressure1, &algoOptions.pressures[0])
+LOG_ADD(LOG_FLOAT, pressure2, &algoOptions.pressures[1])
+LOG_ADD(LOG_FLOAT, pressure3, &algoOptions.pressures[2])
+LOG_ADD(LOG_FLOAT, pressure4, &algoOptions.pressures[3])
+LOG_ADD(LOG_FLOAT, pressure5, &algoOptions.pressures[4])
+LOG_ADD(LOG_FLOAT, pressure6, &algoOptions.pressures[5])
+LOG_ADD(LOG_FLOAT, pressure7, &algoOptions.pressures[6])
+LOG_ADD(LOG_FLOAT, pressure8, &algoOptions.pressures[7])
+LOG_ADD(LOG_UINT16, state, &algoOptions.rangingState)
+LOG_GROUP_STOP(ranging)
+
+PARAM_GROUP_START(anchorpos)
+PARAM_ADD(PARAM_FLOAT, anchor0x, &algoOptions.anchorPosition[0].x)
+PARAM_ADD(PARAM_FLOAT, anchor0y, &algoOptions.anchorPosition[0].y)
+PARAM_ADD(PARAM_FLOAT, anchor0z, &algoOptions.anchorPosition[0].z)
+PARAM_ADD(PARAM_FLOAT, anchor1x, &algoOptions.anchorPosition[1].x)
+PARAM_ADD(PARAM_FLOAT, anchor1y, &algoOptions.anchorPosition[1].y)
+PARAM_ADD(PARAM_FLOAT, anchor1z, &algoOptions.anchorPosition[1].z)
+PARAM_ADD(PARAM_FLOAT, anchor2x, &algoOptions.anchorPosition[2].x)
+PARAM_ADD(PARAM_FLOAT, anchor2y, &algoOptions.anchorPosition[2].y)
+PARAM_ADD(PARAM_FLOAT, anchor2z, &algoOptions.anchorPosition[2].z)
+PARAM_ADD(PARAM_FLOAT, anchor3x, &algoOptions.anchorPosition[3].x)
+PARAM_ADD(PARAM_FLOAT, anchor3y, &algoOptions.anchorPosition[3].y)
+PARAM_ADD(PARAM_FLOAT, anchor3z, &algoOptions.anchorPosition[3].z)
+PARAM_ADD(PARAM_FLOAT, anchor4x, &algoOptions.anchorPosition[4].x)
+PARAM_ADD(PARAM_FLOAT, anchor4y, &algoOptions.anchorPosition[4].y)
+PARAM_ADD(PARAM_FLOAT, anchor4z, &algoOptions.anchorPosition[4].z)
+PARAM_ADD(PARAM_FLOAT, anchor5x, &algoOptions.anchorPosition[5].x)
+PARAM_ADD(PARAM_FLOAT, anchor5y, &algoOptions.anchorPosition[5].y)
+PARAM_ADD(PARAM_FLOAT, anchor5z, &algoOptions.anchorPosition[5].z)
+PARAM_ADD(PARAM_UINT8, enable, &algoOptions.anchorPositionOk)
+PARAM_GROUP_STOP(anchorpos)
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/lpsTdoaTag.c b/crazyflie-firmware-src/src/deck/drivers/src/lpsTdoaTag.c
new file mode 100644
index 0000000000000000000000000000000000000000..d8fe88b3c8300dbe14af83ad92d4c5cb297d735e
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/lpsTdoaTag.c
@@ -0,0 +1,244 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * LPS node firmware.
+ *
+ * Copyright 2016, Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * lpsTdoaTag.c is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with lpsTdoaTag.c.  If not, see <http://www.gnu.org/licenses/>.
+ */
+
+
+#include <string.h>
+
+#include "log.h"
+#include "lpsTdoaTag.h"
+
+#include "stabilizer_types.h"
+#include "cfassert.h"
+
+#ifdef ESTIMATOR_TYPE_kalman
+#include "estimator_kalman.h"
+#endif // ESTIMATOR_TYPE_kalman
+
+
+static lpsAlgoOptions_t* options;
+
+static float uwbTdoaDistDiff[LOCODECK_NR_OF_ANCHORS];
+
+static uint8_t previousAnchor;
+static rangePacket_t rxPacketBuffer[LOCODECK_NR_OF_ANCHORS];
+static dwTime_t arrivals[LOCODECK_NR_OF_ANCHORS];
+
+static double frameTime_in_cl_A[LOCODECK_NR_OF_ANCHORS];
+static double clockCorrection_T_To_A[LOCODECK_NR_OF_ANCHORS];
+
+
+#define MEASUREMENT_NOISE_STD 0.15f
+
+// The maximum diff in distances that we consider to be valid
+// Used to sanity check results and remove results that are wrong due to packet loss
+#define MAX_DISTANCE_DIFF (5.0f)
+
+static uint32_t statsReceivedPackets = 0;
+static uint32_t statsAcceptedAnchorDataPackets = 0;
+static uint32_t statsAcceptedPackets = 0;
+
+static uint64_t timestampToUint64(const uint8_t *ts) {
+  dwTime_t timestamp = {.full = 0};
+  memcpy(timestamp.raw, ts, sizeof(timestamp.raw));
+
+  return timestamp.full;
+}
+
+static uint64_t truncateToTimeStamp(uint64_t fullTimeStamp) {
+  return fullTimeStamp & 0x00FFFFFFFFFFul;
+}
+
+#ifdef ESTIMATOR_TYPE_kalman
+static void enqueueTDOA(uint8_t anchor1, uint8_t anchor2, double distanceDiff, double timeBetweenMeasurements) {
+  tdoaMeasurement_t tdoa = {
+    .stdDev = MEASUREMENT_NOISE_STD,
+    .distanceDiff = distanceDiff,
+    .timeBetweenMeasurements = timeBetweenMeasurements,
+
+    .anchorPosition[0] = options->anchorPosition[anchor1],
+    .anchorPosition[1] = options->anchorPosition[anchor2]
+  };
+
+  stateEstimatorEnqueueTDOA(&tdoa);
+}
+#endif
+
+static double calcClockCorrection(const double frameTime, const double previuosFrameTime) {
+    double clockCorrection = 1.0;
+
+    if (frameTime != 0.0) {
+      clockCorrection = previuosFrameTime / frameTime;
+    }
+
+    return clockCorrection;
+}
+
+// The default receive time in the anchors for messages from other anchors is 0
+// and is overwritten with the actual receive time when a packet arrives.
+// That is, if no message was received the rx time will be 0.
+static bool isValidRxTime(const int64_t anchorRxTime) {
+  return anchorRxTime != 0;
+}
+
+// A note on variable names. They might seem a bit verbose but express quite a lot of information
+// We have three actors: Reference anchor (Ar), Anchor n (An) and the deck on the CF called Tag (T)
+// rxAr_by_An_in_cl_An should be interpreted as "The time when packet was received from the Referecne Anchor by Anchor N expressed in the clock of Anchor N"
+static void rxcallback(dwDevice_t *dev) {
+  statsReceivedPackets++;
+
+  int dataLength = dwGetDataLength(dev);
+  packet_t rxPacket;
+
+  dwGetData(dev, (uint8_t*)&rxPacket, dataLength);
+
+  dwTime_t arrival = {.full = 0};
+  dwGetReceiveTimestamp(dev, &arrival);
+
+  const uint8_t anchor = rxPacket.sourceAddress & 0xff;
+
+  if (anchor < LOCODECK_NR_OF_ANCHORS) {
+    const rangePacket_t* packet = (rangePacket_t*)rxPacket.payload;
+
+    const int64_t previous_rxAn_by_T_in_cl_T  = arrivals[anchor].full;
+    const int64_t rxAn_by_T_in_cl_T  = arrival.full;
+    const int64_t previous_txAn_in_cl_An = timestampToUint64(rxPacketBuffer[anchor].timestamps[anchor]);
+    const int64_t txAn_in_cl_An = timestampToUint64(packet->timestamps[anchor]);
+
+    if (anchor != previousAnchor) {
+      const int64_t previuos_rxAr_by_An_in_cl_An = timestampToUint64(rxPacketBuffer[anchor].timestamps[previousAnchor]);
+      const int64_t rxAr_by_An_in_cl_An = timestampToUint64(packet->timestamps[previousAnchor]);
+      const int64_t rxAn_by_Ar_in_cl_Ar = timestampToUint64(rxPacketBuffer[previousAnchor].timestamps[anchor]);
+
+      if (isValidRxTime(previuos_rxAr_by_An_in_cl_An) && isValidRxTime(rxAr_by_An_in_cl_An) && isValidRxTime(rxAn_by_Ar_in_cl_Ar)) {
+        statsAcceptedAnchorDataPackets++;
+
+        // Caclculate clock correction from anchor to reference anchor
+        const double frameTime_in_cl_An = truncateToTimeStamp(rxAr_by_An_in_cl_An - previuos_rxAr_by_An_in_cl_An);
+        const double clockCorrection_An_To_Ar = calcClockCorrection(frameTime_in_cl_An, frameTime_in_cl_A[previousAnchor]);
+
+        const int64_t rxAr_by_T_in_cl_T  = arrivals[previousAnchor].full;
+        const int64_t txAr_in_cl_Ar = timestampToUint64(rxPacketBuffer[previousAnchor].timestamps[previousAnchor]);
+
+        // Calculate distance diff
+        const int64_t tof_Ar_to_An_in_cl_Ar = (((truncateToTimeStamp(rxAr_by_An_in_cl_An - previous_txAn_in_cl_An) * clockCorrection_An_To_Ar) - truncateToTimeStamp(txAr_in_cl_Ar - rxAn_by_Ar_in_cl_Ar))) / 2.0;
+        const int64_t delta_txAr_to_txAn_in_cl_Ar = (tof_Ar_to_An_in_cl_Ar + truncateToTimeStamp(txAn_in_cl_An - rxAr_by_An_in_cl_An) * clockCorrection_An_To_Ar);
+        const int64_t timeDiffOfArrival_in_cl_Ar =  truncateToTimeStamp(rxAn_by_T_in_cl_T - rxAr_by_T_in_cl_T) * clockCorrection_T_To_A[previousAnchor] - delta_txAr_to_txAn_in_cl_Ar;
+
+        const float tdoaDistDiff = SPEED_OF_LIGHT * timeDiffOfArrival_in_cl_Ar / LOCODECK_TS_FREQ;
+
+        // Sanity check distances in case of missed packages
+        if (tdoaDistDiff > -MAX_DISTANCE_DIFF && tdoaDistDiff < MAX_DISTANCE_DIFF) {
+          uwbTdoaDistDiff[anchor] = tdoaDistDiff;
+
+          #ifdef ESTIMATOR_TYPE_kalman
+          const float timeBetweenMeasurements = truncateToTimeStamp(rxAn_by_T_in_cl_T - rxAr_by_T_in_cl_T) / LOCODECK_TS_FREQ;
+          enqueueTDOA(previousAnchor, anchor, tdoaDistDiff, timeBetweenMeasurements);
+          #endif
+
+          statsAcceptedPackets++;
+        }
+      }
+    }
+
+    // Calculate clock correction for tag to anchor
+    const double frameTime_in_T = truncateToTimeStamp(rxAn_by_T_in_cl_T - previous_rxAn_by_T_in_cl_T);
+    frameTime_in_cl_A[anchor] = truncateToTimeStamp(txAn_in_cl_An - previous_txAn_in_cl_An);
+    clockCorrection_T_To_A[anchor] = calcClockCorrection(frameTime_in_T, frameTime_in_cl_A[anchor]);
+
+    arrivals[anchor].full = arrival.full;
+    memcpy(&rxPacketBuffer[anchor], rxPacket.payload, sizeof(rangePacket_t));
+
+    previousAnchor = anchor;
+  }
+}
+
+static void setRadioInReceiveMode(dwDevice_t *dev) {
+  dwNewReceive(dev);
+  dwSetDefaults(dev);
+  dwStartReceive(dev);
+}
+
+static uint32_t onEvent(dwDevice_t *dev, uwbEvent_t event) {
+  switch(event) {
+    case eventPacketReceived:
+      rxcallback(dev);
+      setRadioInReceiveMode(dev);
+      break;
+    case eventTimeout:
+      setRadioInReceiveMode(dev);
+      break;
+    case eventReceiveTimeout:
+      setRadioInReceiveMode(dev);
+      break;
+    default:
+      ASSERT_FAILED();
+  }
+
+  return MAX_TIMEOUT;
+}
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-parameter"
+static void Initialize(dwDevice_t *dev, lpsAlgoOptions_t* algoOptions) {
+  options = algoOptions;
+
+  // Reset module state. Needed by unit tests
+  memset(rxPacketBuffer, 0, sizeof(rxPacketBuffer));
+  memset(arrivals, 0, sizeof(arrivals));
+
+  memset(frameTime_in_cl_A, 0, sizeof(frameTime_in_cl_A));
+  memset(clockCorrection_T_To_A, 0, sizeof(clockCorrection_T_To_A));
+
+  previousAnchor = 0;
+
+  memset(uwbTdoaDistDiff, 0, sizeof(uwbTdoaDistDiff));
+
+  statsReceivedPackets = 0;
+  statsAcceptedAnchorDataPackets = 0;
+  statsAcceptedPackets = 0;
+}
+#pragma GCC diagnostic pop
+
+uwbAlgorithm_t uwbTdoaTagAlgorithm = {
+  .init = Initialize,
+  .onEvent = onEvent,
+};
+
+
+LOG_GROUP_START(tdoa)
+LOG_ADD(LOG_FLOAT, d0, &uwbTdoaDistDiff[0])
+LOG_ADD(LOG_FLOAT, d1, &uwbTdoaDistDiff[1])
+LOG_ADD(LOG_FLOAT, d2, &uwbTdoaDistDiff[2])
+LOG_ADD(LOG_FLOAT, d3, &uwbTdoaDistDiff[3])
+LOG_ADD(LOG_FLOAT, d4, &uwbTdoaDistDiff[4])
+LOG_ADD(LOG_FLOAT, d5, &uwbTdoaDistDiff[5])
+LOG_ADD(LOG_FLOAT, d6, &uwbTdoaDistDiff[6])
+LOG_ADD(LOG_FLOAT, d7, &uwbTdoaDistDiff[7])
+
+LOG_ADD(LOG_UINT32, rxCnt, &statsReceivedPackets)
+LOG_ADD(LOG_UINT32, anCnt, &statsAcceptedAnchorDataPackets)
+LOG_ADD(LOG_UINT32, okCnt, &statsAcceptedPackets)
+
+LOG_GROUP_STOP(tdoa)
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/lpsTwrTag.c b/crazyflie-firmware-src/src/deck/drivers/src/lpsTwrTag.c
new file mode 100644
index 0000000000000000000000000000000000000000..2ff039faa8ea48dc7aecb0e6098848894cbbb9e2
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/lpsTwrTag.c
@@ -0,0 +1,314 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * LPS node firmware.
+ *
+ * Copyright 2016, Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Foobar is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Foobar.  If not, see <http://www.gnu.org/licenses/>.
+ */
+/* uwb_twr_anchor.c: Uwb two way ranging anchor implementation */
+
+
+#include <string.h>
+
+#include "lpsTwrTag.h"
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "log.h"
+
+#include "stabilizer_types.h"
+#ifdef ESTIMATOR_TYPE_kalman
+#include "estimator_kalman.h"
+#include "arm_math.h"
+#endif
+
+// Outlier rejection
+#ifdef ESTIMATOR_TYPE_kalman
+  #define RANGING_HISTORY_LENGTH 32
+  #define OUTLIER_TH 4
+  static struct {
+    float32_t history[RANGING_HISTORY_LENGTH];
+    size_t ptr;
+  } rangingStats[LOCODECK_NR_OF_ANCHORS];
+#endif
+
+// Rangin statistics
+static uint32_t rangingPerSec[LOCODECK_NR_OF_ANCHORS];
+static float rangingSuccessRate[LOCODECK_NR_OF_ANCHORS];
+// Used to calculate above values
+static uint32_t succededRanging[LOCODECK_NR_OF_ANCHORS];
+static uint32_t failedRanging[LOCODECK_NR_OF_ANCHORS];
+
+// Timestamps for ranging
+static dwTime_t poll_tx;
+static dwTime_t poll_rx;
+static dwTime_t answer_tx;
+static dwTime_t answer_rx;
+static dwTime_t final_tx;
+static dwTime_t final_rx;
+
+static packet_t txPacket;
+static volatile uint8_t curr_seq = 0;
+static int current_anchor = 0;
+
+static bool ranging_complete = false;
+
+static lpsAlgoOptions_t* options;
+
+static void txcallback(dwDevice_t *dev)
+{
+  dwTime_t departure;
+  dwGetTransmitTimestamp(dev, &departure);
+  departure.full += (options->antennaDelay / 2);
+
+  switch (txPacket.payload[0]) {
+    case LPS_TWR_POLL:
+      poll_tx = departure;
+      break;
+    case LPS_TWR_FINAL:
+      final_tx = departure;
+      break;
+  }
+}
+
+
+static uint32_t rxcallback(dwDevice_t *dev) {
+  dwTime_t arival = { .full=0 };
+  int dataLength = dwGetDataLength(dev);
+
+  if (dataLength == 0) return 0;
+
+  packet_t rxPacket;
+  memset(&rxPacket, 0, MAC802154_HEADER_LENGTH);
+
+  dwGetData(dev, (uint8_t*)&rxPacket, dataLength);
+
+  if (rxPacket.destAddress != options->tagAddress) {
+    dwNewReceive(dev);
+    dwSetDefaults(dev);
+    dwStartReceive(dev);
+    return MAX_TIMEOUT;
+  }
+
+  txPacket.destAddress = rxPacket.sourceAddress;
+  txPacket.sourceAddress = rxPacket.destAddress;
+
+  switch(rxPacket.payload[LPS_TWR_TYPE]) {
+    // Tag received messages
+    case LPS_TWR_ANSWER:
+      if (rxPacket.payload[LPS_TWR_SEQ] != curr_seq) {
+        return 0;
+      }
+
+      txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_FINAL;
+      txPacket.payload[LPS_TWR_SEQ] = rxPacket.payload[LPS_TWR_SEQ];
+
+      dwGetReceiveTimestamp(dev, &arival);
+      arival.full -= (options->antennaDelay / 2);
+      answer_rx = arival;
+
+      dwNewTransmit(dev);
+      dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2);
+
+      dwWaitForResponse(dev, true);
+      dwStartTransmit(dev);
+
+      break;
+    case LPS_TWR_REPORT:
+    {
+      lpsTwrTagReportPayload_t *report = (lpsTwrTagReportPayload_t *)(rxPacket.payload+2);
+      double tround1, treply1, treply2, tround2, tprop_ctn, tprop;
+
+      if (rxPacket.payload[LPS_TWR_SEQ] != curr_seq) {
+        return 0;
+      }
+
+      memcpy(&poll_rx, &report->pollRx, 5);
+      memcpy(&answer_tx, &report->answerTx, 5);
+      memcpy(&final_rx, &report->finalRx, 5);
+
+      tround1 = answer_rx.low32 - poll_tx.low32;
+      treply1 = answer_tx.low32 - poll_rx.low32;
+      tround2 = final_rx.low32 - answer_tx.low32;
+      treply2 = final_tx.low32 - answer_rx.low32;
+
+      tprop_ctn = ((tround1*tround2) - (treply1*treply2)) / (tround1 + tround2 + treply1 + treply2);
+
+      tprop = tprop_ctn / LOCODECK_TS_FREQ;
+      options->distance[current_anchor] = SPEED_OF_LIGHT * tprop;
+      options->pressures[current_anchor] = report->asl;
+
+#ifdef ESTIMATOR_TYPE_kalman
+      // Outliers rejection
+      rangingStats[current_anchor].ptr = (rangingStats[current_anchor].ptr + 1) % RANGING_HISTORY_LENGTH;
+      float32_t mean;
+      float32_t stddev;
+
+      arm_std_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &stddev);
+      arm_mean_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &mean);
+      float32_t diff = fabsf(mean - options->distance[current_anchor]);
+
+      rangingStats[current_anchor].history[rangingStats[current_anchor].ptr] = options->distance[current_anchor];
+
+      if (options->anchorPositionOk && (diff < (OUTLIER_TH*stddev))) {
+        distanceMeasurement_t dist;
+        dist.distance = options->distance[current_anchor];
+        dist.x = options->anchorPosition[current_anchor].x;
+        dist.y = options->anchorPosition[current_anchor].y;
+        dist.z = options->anchorPosition[current_anchor].z;
+        dist.stdDev = 0.25;
+        stateEstimatorEnqueueDistance(&dist);
+      }
+#endif
+
+      ranging_complete = true;
+
+      return 0;
+      break;
+    }
+  }
+  return MAX_TIMEOUT;
+}
+
+void initiateRanging(dwDevice_t *dev)
+{
+  current_anchor ++;
+  if (current_anchor >= LOCODECK_NR_OF_ANCHORS) {
+    current_anchor = 0;
+  }
+
+  dwIdle(dev);
+
+  txPacket.payload[LPS_TWR_TYPE] = LPS_TWR_POLL;
+  txPacket.payload[LPS_TWR_SEQ] = ++curr_seq;
+
+  txPacket.sourceAddress = options->tagAddress;
+  txPacket.destAddress = options->anchorAddress[current_anchor];
+
+  dwNewTransmit(dev);
+  dwSetDefaults(dev);
+  dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2);
+
+  dwWaitForResponse(dev, true);
+  dwStartTransmit(dev);
+}
+
+static uint32_t twrTagOnEvent(dwDevice_t *dev, uwbEvent_t event)
+{
+  static uint32_t statisticStartTick = 0;
+
+  if (statisticStartTick == 0) {
+    statisticStartTick = xTaskGetTickCount();
+  }
+
+  switch(event) {
+    case eventPacketReceived:
+      return rxcallback(dev);
+      break;
+    case eventPacketSent:
+      txcallback(dev);
+      return MAX_TIMEOUT;
+      break;
+    case eventTimeout:  // Comes back to timeout after each ranging attempt
+      if (!ranging_complete) {
+        options->rangingState &= ~(1<<current_anchor);
+        if (options->failedRanging[current_anchor] < options->rangingFailedThreshold) {
+          options->failedRanging[current_anchor] ++;
+          options->rangingState |= (1<<current_anchor);
+        }
+
+        failedRanging[current_anchor]++;
+      } else {
+        options->rangingState |= (1<<current_anchor);
+        options->failedRanging[current_anchor] = 0;
+
+        succededRanging[current_anchor]++;
+      }
+
+      // Handle ranging statistic
+      if (xTaskGetTickCount() > (statisticStartTick+1000)) {
+        statisticStartTick = xTaskGetTickCount();
+
+        for (int i=0; i<LOCODECK_NR_OF_ANCHORS; i++) {
+          rangingPerSec[i] = failedRanging[i] + succededRanging[i];
+          if (rangingPerSec[i] > 0) {
+            rangingSuccessRate[i] = 100.0f*(float)succededRanging[i] / (float)rangingPerSec[i];
+          } else {
+            rangingSuccessRate[i] = 0.0f;
+          }
+
+          failedRanging[i] = 0;
+          succededRanging[i] = 0;
+        }
+      }
+
+
+      ranging_complete = false;
+      initiateRanging(dev);
+      return MAX_TIMEOUT;
+      break;
+    case eventReceiveTimeout:
+    case eventReceiveFailed:
+      return 0;
+      break;
+    default:
+      configASSERT(false);
+  }
+
+  return MAX_TIMEOUT;
+}
+
+static void twrTagInit(dwDevice_t *dev, lpsAlgoOptions_t* algoOptions)
+{
+  options = algoOptions;
+
+  // Initialize the packet in the TX buffer
+  memset(&txPacket, 0, sizeof(txPacket));
+  MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA);
+  txPacket.pan = 0xbccf;
+
+  memset(&poll_tx, 0, sizeof(poll_tx));
+  memset(&poll_rx, 0, sizeof(poll_rx));
+  memset(&answer_tx, 0, sizeof(answer_tx));
+  memset(&answer_rx, 0, sizeof(answer_rx));
+  memset(&final_tx, 0, sizeof(final_tx));
+  memset(&final_rx, 0, sizeof(final_rx));
+
+  curr_seq = 0;
+  current_anchor = 0;
+
+  options->rangingState = 0;
+  ranging_complete = false;
+
+  memset(options->distance, 0, sizeof(options->distance));
+  memset(options->pressures, 0, sizeof(options->pressures));
+  memset(options->failedRanging, 0, sizeof(options->failedRanging));
+}
+
+uwbAlgorithm_t uwbTwrTagAlgorithm = {
+  .init = twrTagInit,
+  .onEvent = twrTagOnEvent,
+};
+
+LOG_GROUP_START(twr)
+LOG_ADD(LOG_FLOAT, rangingSuccessRate0, &rangingSuccessRate[0])
+LOG_ADD(LOG_UINT32, rangingPerSec0, &rangingPerSec[0])
+LOG_GROUP_STOP(twr)
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/lpsTwrTdmaTag.c b/crazyflie-firmware-src/src/deck/drivers/src/lpsTwrTdmaTag.c
new file mode 100644
index 0000000000000000000000000000000000000000..f07c8e41e3a17d68344dae024c4b7dc089ccae55
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/lpsTwrTdmaTag.c
@@ -0,0 +1,361 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * LPS node firmware.
+ *
+ * Copyright 2016, Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Foobar is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Foobar.  If not, see <http://www.gnu.org/licenses/>.
+ */
+/* uwb_twr_anchor.c: Uwb two way ranging tag with TDMA implementation */
+
+#include "locodeck.h"
+
+#include <string.h>
+
+#include "log.h"
+#include "param.h"
+
+#include "libdw1000.h"
+
+#include "mac.h"
+
+#include "stabilizer_types.h"
+#ifdef ESTIMATOR_TYPE_kalman
+#include "estimator_kalman.h"
+#include "arm_math.h"
+#endif
+
+#define RX_TIMEOUT 1000
+
+// TDMA handling
+bool tdmaSynchronized;
+dwTime_t frameStart;
+
+#ifndef TDMA_NSLOTS_BITS
+#define TDMA_NSLOTS_BITS 1
+#endif
+
+#ifndef TDMA_SLOT
+#define TDMA_SLOT 0
+#endif
+
+#define TDMA_SLOT_BITS 27
+
+#define TDMA_FRAME_BITS (TDMA_SLOT_BITS + TDMA_NSLOTS_BITS)
+#define TDMA_SLOT_LEN (1ull<<(TDMA_SLOT_BITS+1))
+#define TDMA_FRAME_LEN (1ull<<(TDMA_FRAME_BITS+1))
+
+#define TDMA_LAST_FRAME(NOW) ( NOW & ~(TDMA_FRAME_LEN-1) )
+
+
+// Amount of failed ranging before the ranging value is set as wrong
+#define RANGING_FAILED_TH 6
+
+#define N_ANCHORS 6
+int anchors[N_ANCHORS] = {1,2,3,4,5,6};
+
+#define TAG_ADDRESS 8+TDMA_SLOT
+
+// Outlier rejection
+#ifdef ESTIMATOR_TYPE_kalman
+  #define RANGING_HISTORY_LENGTH 32
+  #define OUTLIER_TH 4
+  static struct {
+    float32_t history[RANGING_HISTORY_LENGTH];
+    size_t ptr;
+  } rangingStats[N_ANCHORS];
+#endif
+
+static uint8_t tag_address[] = {TAG_ADDRESS,0,0,0,0,0,0xcf,0xbc};
+static uint8_t base_address[] = {0,0,0,0,0,0,0xcf,0xbc};
+
+// The four packets for ranging
+#define POLL 0x01   // Poll is initiated by the tag
+#define ANSWER 0x02
+#define FINAL 0x03
+#define REPORT 0x04 // Report contains all measurement from the anchor
+
+typedef struct {
+  uint8_t pollRx[5];
+  uint8_t answerTx[5];
+  uint8_t finalRx[5];
+
+  float pressure;
+  float temperature;
+  float asl;
+  uint8_t pressure_ok;
+} __attribute__((packed)) reportPayload_t;
+
+// Timestamps for ranging
+static dwTime_t poll_tx;
+static dwTime_t poll_rx;
+static dwTime_t answer_tx;
+static dwTime_t answer_rx;
+static dwTime_t final_tx;
+static dwTime_t final_rx;
+
+#define ANTENNA_OFFSET 154.6   // In meter
+static const uint64_t ANTENNA_DELAY = (ANTENNA_OFFSET*499.2e6*128)/299792458.0; // In radio tick
+
+static packet_t rxPacket;
+static packet_t txPacket;
+static volatile uint8_t curr_seq = 0;
+static int current_anchor = 0;
+
+static bool ranging_complete = false;
+
+static lpsAlgoOptions_t* options;
+
+static void txcallback(dwDevice_t *dev)
+{
+  dwTime_t departure;
+  dwGetTransmitTimestamp(dev, &departure);
+  departure.full += (options->antennaDelay / 2);
+
+  switch (txPacket.payload[0]) {
+    case POLL:
+      poll_tx = departure;
+      break;
+    case FINAL:
+      final_tx = departure;
+      break;
+  }
+}
+
+#define TYPE 0
+#define SEQ 1
+
+static uint32_t rxcallback(dwDevice_t *dev) {
+  dwTime_t arival = { .full=0 };
+  int dataLength = dwGetDataLength(dev);
+
+  if (dataLength == 0) return 0;
+
+  bzero(&rxPacket, MAC802154_HEADER_LENGTH);
+
+  dwGetData(dev, (uint8_t*)&rxPacket, dataLength);
+
+  if (memcmp(&rxPacket.destAddress, tag_address, 8)) {
+    dwNewReceive(dev);
+    dwSetDefaults(dev);
+    dwStartReceive(dev);
+    return MAX_TIMEOUT;
+  }
+
+  txPacket.destAddress = rxPacket.sourceAddress;
+  txPacket.sourceAddress = rxPacket.destAddress;
+
+  switch(rxPacket.payload[TYPE]) {
+    // Tag received messages
+    case ANSWER:
+      if (rxPacket.payload[SEQ] != curr_seq) {
+        return 0;
+      }
+
+      txPacket.payload[0] = FINAL;
+      txPacket.payload[SEQ] = rxPacket.payload[SEQ];
+
+      dwGetReceiveTimestamp(dev, &arival);
+      arival.full -= (ANTENNA_DELAY/2);
+      answer_rx = arival;
+
+      dwNewTransmit(dev);
+      dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2);
+
+      dwWaitForResponse(dev, true);
+      dwStartTransmit(dev);
+
+      break;
+    case REPORT:
+    {
+      reportPayload_t *report = (reportPayload_t *)(rxPacket.payload+2);
+      double tround1, treply1, treply2, tround2, tprop_ctn, tprop;
+
+      if (rxPacket.payload[SEQ] != curr_seq) {
+        return 0;
+      }
+
+
+      memcpy(&poll_rx, &report->pollRx, 5);
+      memcpy(&answer_tx, &report->answerTx, 5);
+      memcpy(&final_rx, &report->finalRx, 5);
+
+      tround1 = answer_rx.low32 - poll_tx.low32;
+      treply1 = answer_tx.low32 - poll_rx.low32;
+      tround2 = final_rx.low32 - answer_tx.low32;
+      treply2 = final_tx.low32 - answer_rx.low32;
+
+      tprop_ctn = ((tround1*tround2) - (treply1*treply2)) / (tround1 + tround2 + treply1 + treply2);
+
+      tprop = tprop_ctn/LOCODECK_TS_FREQ;
+      options->distance[current_anchor] = SPEED_OF_LIGHT * tprop;
+      options->pressures[current_anchor] = report->asl;
+
+#ifdef ESTIMATOR_TYPE_kalman
+      // Outliers rejection
+      rangingStats[current_anchor].ptr = (rangingStats[current_anchor].ptr + 1) % RANGING_HISTORY_LENGTH;
+      float32_t mean;
+      float32_t stddev;
+
+      arm_std_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &stddev);
+      arm_mean_f32(rangingStats[current_anchor].history, RANGING_HISTORY_LENGTH, &mean);
+      float32_t diff = fabsf(mean - options->distance[current_anchor]);
+
+      rangingStats[current_anchor].history[rangingStats[current_anchor].ptr] = options->distance[current_anchor];
+
+      if (options->anchorPositionOk && (diff < (OUTLIER_TH*stddev))) {
+        distanceMeasurement_t dist;
+        dist.distance = options->distance[current_anchor];
+        dist.x = options->anchorPosition[current_anchor].x;
+        dist.y = options->anchorPosition[current_anchor].y;
+        dist.z = options->anchorPosition[current_anchor].z;
+        dist.stdDev = 0.25;
+        stateEstimatorEnqueueDistance(&dist);
+      }
+#endif
+
+      if (current_anchor == 0) {
+        // Final packet is sent by us and received by the anchor
+        // We use it as synchonisation time for TDMA
+        dwTime_t offset = { .full =final_tx.full - final_rx.full };
+        frameStart.full = TDMA_LAST_FRAME(final_rx.full) + offset.full;
+        tdmaSynchronized = true;
+      }
+
+      ranging_complete = true;
+
+      return 0;
+      break;
+    }
+  }
+  return MAX_TIMEOUT;
+}
+
+/* Adjust time for schedule transfer by DW1000 radio. Set 9 LSB to 0 */
+uint32_t adjustTxRxTime(dwTime_t *time)
+{
+  uint32_t added = (1<<9) - (time->low32 & ((1<<9)-1));
+  time->low32 = (time->low32 & ~((1<<9)-1)) + (1<<9);
+  return added;
+}
+
+/* Calculate the transmit time for a given timeslot in the current frame */
+static dwTime_t transmitTimeForSlot(int slot)
+{
+  dwTime_t transmitTime = { .full = 0 };
+  // Calculate start of the slot
+  transmitTime.full = frameStart.full + slot*TDMA_SLOT_LEN;
+
+  // DW1000 can only schedule time with 9 LSB at 0, adjust for it
+  adjustTxRxTime(&transmitTime);
+  return transmitTime;
+}
+
+static void initiateRanging(dwDevice_t *dev)
+{
+  if (tdmaSynchronized) {
+    // go to next frame
+    frameStart.full += TDMA_FRAME_LEN;
+
+    current_anchor ++;
+    if (current_anchor >= N_ANCHORS) {
+      current_anchor = 0;
+    }
+  } else {
+    current_anchor = 0;
+  }
+
+  base_address[0] =  anchors[current_anchor];
+
+  dwIdle(dev);
+
+  txPacket.payload[TYPE] = POLL;
+  txPacket.payload[SEQ] = ++curr_seq;
+
+  memcpy(&txPacket.sourceAddress, &tag_address, 8);
+  memcpy(&txPacket.destAddress, &base_address, 8);
+
+
+  dwNewTransmit(dev);
+  dwSetDefaults(dev);
+  dwSetData(dev, (uint8_t*)&txPacket, MAC802154_HEADER_LENGTH+2);
+
+  if (tdmaSynchronized) {
+    dwTime_t txTime = transmitTimeForSlot(TDMA_SLOT);
+    dwSetTxRxTime(dev, txTime);
+  }
+
+  dwWaitForResponse(dev, true);
+  dwStartTransmit(dev);
+}
+
+static uint32_t twrTagOnEvent(dwDevice_t *dev, uwbEvent_t event)
+{
+  switch(event) {
+    case eventPacketReceived:
+      return rxcallback(dev);
+      break;
+    case eventPacketSent:
+      txcallback(dev);
+      return MAX_TIMEOUT;
+      break;
+    case eventTimeout:  // Comes back to timeout after each ranging attempt
+      if (!ranging_complete) {
+        options->rangingState &= ~(1<<current_anchor);
+        if (options->failedRanging[current_anchor] < RANGING_FAILED_TH) {
+          options->failedRanging[current_anchor] ++;
+          options->rangingState |= (1<<current_anchor);
+        }
+      } else {
+        options->rangingState |= (1<<current_anchor);
+        options->failedRanging[current_anchor] = 0;
+      }
+      ranging_complete = false;
+      initiateRanging(dev);
+      return MAX_TIMEOUT;
+      break;
+    case eventReceiveTimeout:
+    case eventReceiveFailed:
+      return 0;
+      break;
+    default:
+      configASSERT(false);
+  }
+
+  return MAX_TIMEOUT;
+}
+
+static void twrTagInit(dwDevice_t *dev, lpsAlgoOptions_t* newOptions)
+{
+  tdmaSynchronized = false;
+
+  options = newOptions;
+
+
+  // Initialize the packet in the TX buffer
+  MAC80215_PACKET_INIT(txPacket, MAC802154_TYPE_DATA);
+  txPacket.pan = 0xbccf;
+
+  // onEvent is going to be called with eventTimeout which will start ranging
+}
+
+uwbAlgorithm_t uwbTwrTagAlgorithm = {
+  .init = twrTagInit,
+  .onEvent = twrTagOnEvent,
+};
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/rzr.c b/crazyflie-firmware-src/src/deck/drivers/src/rzr.c
new file mode 100644
index 0000000000000000000000000000000000000000..f2e96e5b69d9e77de1fa33e61eaed1489d64489d
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/rzr.c
@@ -0,0 +1,122 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * rzr.c - Crazyflie RZR board.
+ */
+#define DEBUG_MODULE "RZR"
+
+#include <stdint.h>
+#include <string.h>
+
+#include "stm32fxxx.h"
+#include "config.h"
+#include "motors.h"
+#include "debug.h"
+#include "deck.h"
+#include "extrx.h"
+#include "pm.h"
+
+#define RZR_GPIO_RCC_M1_OVERRIDE    RCC_AHB1Periph_GPIOA
+#define RZR_GPIO_PORT_M1_OVERRIDE   GPIOA
+#define RZR_GPIO_PIN_M1_OVERRIDE    GPIO_Pin_0
+#define RZR_GPIO_RCC_M2_OVERRIDE    RCC_AHB1Periph_GPIOB
+#define RZR_GPIO_PORT_M2_OVERRIDE   GPIOB
+#define RZR_GPIO_PIN_M2_OVERRIDE    GPIO_Pin_12
+#define RZR_GPIO_RCC_M3_OVERRIDE    RCC_AHB1Periph_GPIOC
+#define RZR_GPIO_PORT_M3_OVERRIDE   GPIOC
+#define RZR_GPIO_PIN_M3_OVERRIDE    GPIO_Pin_8
+#define RZR_GPIO_RCC_M4_OVERRIDE    RCC_AHB1Periph_GPIOC
+#define RZR_GPIO_PORT_M4_OVERRIDE   GPIOC
+#define RZR_GPIO_PIN_M4_OVERRIDE    GPIO_Pin_15
+
+//Hardware configuration
+static bool isInit;
+
+static void rzrInit(DeckInfo *info)
+{
+  GPIO_InitTypeDef GPIO_InitStructure = {0};
+
+  if(isInit)
+    return;
+
+  DEBUG_PRINT("Switching to brushless.\n");
+
+
+  // Configure GPIO for power to BL motor connectors
+  RCC_AHB1PeriphClockCmd(RZR_GPIO_RCC_M1_OVERRIDE, ENABLE);
+  RCC_AHB1PeriphClockCmd(RZR_GPIO_RCC_M2_OVERRIDE, ENABLE);
+  RCC_AHB1PeriphClockCmd(RZR_GPIO_RCC_M3_OVERRIDE, ENABLE);
+  RCC_AHB1PeriphClockCmd(RZR_GPIO_RCC_M4_OVERRIDE, ENABLE);
+
+  GPIO_StructInit(&GPIO_InitStructure);
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+
+  GPIO_InitStructure.GPIO_Pin = RZR_GPIO_PIN_M1_OVERRIDE;
+  GPIO_Init(RZR_GPIO_PORT_M1_OVERRIDE, &GPIO_InitStructure);
+
+  GPIO_InitStructure.GPIO_Pin = RZR_GPIO_PIN_M2_OVERRIDE;
+  GPIO_Init(RZR_GPIO_PORT_M2_OVERRIDE, &GPIO_InitStructure);
+
+  GPIO_InitStructure.GPIO_Pin = RZR_GPIO_PIN_M3_OVERRIDE;
+  GPIO_Init(RZR_GPIO_PORT_M3_OVERRIDE, &GPIO_InitStructure);
+
+  GPIO_InitStructure.GPIO_Pin = RZR_GPIO_PIN_M4_OVERRIDE;
+  GPIO_Init(RZR_GPIO_PORT_M4_OVERRIDE, &GPIO_InitStructure);
+
+  // Enable for power to BL motor connectors
+  GPIO_WriteBit(RZR_GPIO_PORT_M1_OVERRIDE, RZR_GPIO_PIN_M1_OVERRIDE, 1);
+  GPIO_WriteBit(RZR_GPIO_PORT_M2_OVERRIDE, RZR_GPIO_PIN_M2_OVERRIDE, 1);
+  GPIO_WriteBit(RZR_GPIO_PORT_M3_OVERRIDE, RZR_GPIO_PIN_M3_OVERRIDE, 1);
+  GPIO_WriteBit(RZR_GPIO_PORT_M4_OVERRIDE, RZR_GPIO_PIN_M4_OVERRIDE, 1);
+
+  // Remap motor PWM output
+  motorsInit(motorMapRZRBrushless);
+
+  isInit = true;
+}
+
+static bool rzrTest()
+{
+  bool status = true;
+
+  if(!isInit)
+    return false;
+
+  status = motorsTest();
+
+  return status;
+}
+
+static const DeckDriver rzr_deck = {
+//  .vid = 0xBC,
+//  .pid = 0x08,
+  .name = "bcRZR",
+
+  .usedPeriph = 0,
+  .usedGpio = 0,
+  .init = rzrInit,
+  .test = rzrTest,
+};
+
+DECK_DRIVER(rzr_deck);
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/test/bigquadtest.c b/crazyflie-firmware-src/src/deck/drivers/src/test/bigquadtest.c
new file mode 100644
index 0000000000000000000000000000000000000000..5497bca1e442eb8ae36a31ff221add65ec366b78
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/test/bigquadtest.c
@@ -0,0 +1,144 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * bigquadtest.c - Testing of the Big Quad deck.
+ */
+#define DEBUG_MODULE "BQ-TEST"
+
+
+#include <stdint.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "stm32fxxx.h"
+#include "config.h"
+#include "debug.h"
+#include "deck.h"
+#include "deck_test.h"
+#include "param.h"
+
+#define VBAT_TEST_VOLTAGE_LOW      (3.0 / ((1.0 + 69.0 + 10.0) / 10.0) * 0.95) /* 0.35625 */
+#define VBAT_TEST_VOLTAGE_HIGH     (3.0 / ((1.0 + 69.0 + 10.0) / 10.0) * 1.05) /* 0.39375 */
+
+#define TEST(result, str, status) decktestEval(result, DEBUG_MODULE ": " str, status)
+
+static uint8_t testsPass = 0;
+
+static bool bigquadtestRun()
+{
+  bool status = true;
+  float readVoltage;
+  GpioRegBuf gpioSaved;
+  UBaseType_t prioSaved;
+
+  /* Raise priority to prevent task switch during testing */
+  prioSaved = uxTaskPriorityGet(NULL);
+  vTaskPrioritySet(NULL, configMAX_PRIORITIES - 1);
+
+  /* Save GPIO states */
+  decktestSaveGPIOStatesABC(&gpioSaved);
+
+  /* Test SDA and CPPM(MOSI) which should be bridged */
+  pinMode(DECK_GPIO_SDA, INPUT);
+  pinMode(DECK_GPIO_MOSI, INPUT);
+  TEST(digitalRead(DECK_GPIO_SDA) == HIGH, "SDA == HIGH", &status);
+  TEST(digitalRead(DECK_GPIO_MOSI) == HIGH, "CPPM == HIGH", &status);
+  pinMode(DECK_GPIO_MOSI, OUTPUT);
+  digitalWrite(DECK_GPIO_MOSI, LOW);
+  vTaskDelay(1);
+  TEST(digitalRead(DECK_GPIO_SDA) == LOW, "SDA == LOW", &status);
+  pinMode(DECK_GPIO_MOSI, INPUT);
+
+  /* Test SCL and BUZ(IO_4) which should be bridged */
+  pinMode(DECK_GPIO_SCL, INPUT);
+  pinMode(DECK_GPIO_IO4, INPUT);
+  TEST(digitalRead(DECK_GPIO_SCL) == HIGH, "SCL == HIGH", &status);
+  TEST(digitalRead(DECK_GPIO_IO4) == HIGH, "BUZ == HIGH", &status);
+  pinMode(DECK_GPIO_IO4, OUTPUT);
+  digitalWrite(DECK_GPIO_IO4, LOW);
+  vTaskDelay(1);
+  TEST(digitalRead(DECK_GPIO_SCL) == LOW, "SCL == LOW", &status);
+  pinMode(DECK_GPIO_IO4, INPUT);
+
+  /* Test M1(TX2), M2(IO_3), M3(IO_2), M4(RX2) */
+  /* which are pulled high with 1k */
+  pinMode(DECK_GPIO_TX2, INPUT_PULLDOWN);
+  pinMode(DECK_GPIO_RX2, INPUT_PULLDOWN);
+  pinMode(DECK_GPIO_IO2, INPUT_PULLDOWN);
+  pinMode(DECK_GPIO_IO3, INPUT_PULLDOWN);
+  TEST(digitalRead(DECK_GPIO_TX2) == HIGH, "M1(TX2) == HIGH", &status);
+  TEST(digitalRead(DECK_GPIO_IO3) == HIGH, "M2(IO_3) == HIGH", &status);
+  TEST(digitalRead(DECK_GPIO_IO2) == HIGH, "M3(IO_2) == HIGH", &status);
+  TEST(digitalRead(DECK_GPIO_RX2) == HIGH, "M4(RX2) == HIGH", &status);
+
+  /* Test TX and RX  which should be bridged */
+  pinMode(DECK_GPIO_RX1, INPUT_PULLUP);
+  pinMode(DECK_GPIO_TX1, OUTPUT);
+  digitalWrite(DECK_GPIO_TX1, LOW);
+  vTaskDelay(1);
+  TEST(digitalRead(DECK_GPIO_RX1) == LOW, "TX, RX", &status);
+  digitalWrite(DECK_GPIO_TX1, HIGH);
+  vTaskDelay(1);
+  TEST(digitalRead(DECK_GPIO_RX1) == HIGH, "TX, RX", &status);
+  pinMode(DECK_GPIO_TX1, INPUT); // restore
+
+  /* Test CUR(SCK) and VBAT(MISO) which should be bridged */
+  /* CUR set to output 3V and VBAT to measure */
+  pinMode(DECK_GPIO_SCK, OUTPUT);
+  digitalWrite(DECK_GPIO_SCK, HIGH);
+  vTaskDelay(10);
+  readVoltage = analogReadVoltage(DECK_GPIO_MISO);
+  TEST((readVoltage > VBAT_TEST_VOLTAGE_LOW &&
+        readVoltage < VBAT_TEST_VOLTAGE_HIGH),
+        "VBAT(MISO) voltage", &status);
+
+  decktestRestoreGPIOStatesABC(&gpioSaved);
+
+  if (status)
+  {
+    testsPass = 1;
+    DEBUG_PRINT("BigQuad deck test [OK]\n");
+  }
+
+  /* Restore priority */
+  vTaskPrioritySet(NULL, prioSaved);
+
+  return status;
+}
+
+static const DeckDriver bigquadtest_deck = {
+  .name = "bcBigQuadTest",
+
+  .usedPeriph = 0,
+  .usedGpio = 0,
+
+  .test = bigquadtestRun,
+};
+
+DECK_DRIVER(bigquadtest_deck);
+
+PARAM_GROUP_START(BigQuadTest)
+PARAM_ADD(PARAM_UINT8, pass, &testsPass)
+PARAM_GROUP_STOP(BigQuadTest)
+
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/test/exptest.c b/crazyflie-firmware-src/src/deck/drivers/src/test/exptest.c
new file mode 100644
index 0000000000000000000000000000000000000000..749ff7e2bdb7dbd7730be95680d21e2e31ec3d51
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/test/exptest.c
@@ -0,0 +1,224 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * exptest.c - Testing of expansion port.
+ */
+#define DEBUG_MODULE "ET"
+
+#include <stdint.h>
+
+#include "stm32fxxx.h"
+#include "config.h"
+#include "debug.h"
+#include "deck.h"
+#include "deck_test.h"
+
+#include "sensors.h"
+
+//Hardware configuration
+#define ET_GPIO_PERIF   (RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
+
+#define ET_GPIO_PORT_TX1  GPIOC
+#define ET_GPIO_PIN_TX1   GPIO_Pin_10
+#define ET_GPIO_PORT_RX1  GPIOC
+#define ET_GPIO_PIN_RX1   GPIO_Pin_11
+
+#define ET_GPIO_PORT_TX2  GPIOA
+#define ET_GPIO_PIN_TX2   GPIO_Pin_2
+#define ET_GPIO_PORT_RX2  GPIOA
+#define ET_GPIO_PIN_RX2   GPIO_Pin_3
+
+#define ET_GPIO_PORT_SCK  GPIOA
+#define ET_GPIO_PIN_SCK   GPIO_Pin_5
+#define ET_GPIO_PORT_MOSI GPIOA
+#define ET_GPIO_PIN_MOSI  GPIO_Pin_6
+#define ET_GPIO_PORT_MISO GPIOA
+#define ET_GPIO_PIN_MISO  GPIO_Pin_7
+
+#define ET_GPIO_PORT_SDA  GPIOB
+#define ET_GPIO_PIN_SDA   GPIO_Pin_7
+#define ET_GPIO_PORT_SCL  GPIOB
+#define ET_GPIO_PIN_SCL   GPIO_Pin_6
+
+#define ET_GPIO_PORT_IO1  GPIOB
+#define ET_GPIO_PIN_IO1   GPIO_Pin_8
+#define ET_GPIO_PORT_IO2  GPIOB
+#define ET_GPIO_PIN_IO2   GPIO_Pin_5
+#define ET_GPIO_PORT_IO3  GPIOB
+#define ET_GPIO_PIN_IO3   GPIO_Pin_4
+#define ET_GPIO_PORT_IO4  GPIOC
+#define ET_GPIO_PIN_IO4   GPIO_Pin_12
+
+#define ET_NBR_PINS         11
+#define ET_IO4_PIN          (ET_NBR_PINS - 1)
+
+typedef struct _etGpio
+{
+  GPIO_TypeDef     *port;
+  uint16_t          pin;
+  char              name[6];
+} EtGpio;
+
+EtGpio etGpioIn[ET_NBR_PINS] =
+{
+    {ET_GPIO_PORT_TX1,  ET_GPIO_PIN_TX1, "TX1"},
+    {ET_GPIO_PORT_RX1,  ET_GPIO_PIN_RX1, "RX1"},
+    {ET_GPIO_PORT_TX2,  ET_GPIO_PIN_TX2, "TX2"},
+    {ET_GPIO_PORT_RX2,  ET_GPIO_PIN_RX2, "RX2"},
+    {ET_GPIO_PORT_SCK,  ET_GPIO_PIN_SCK, "SCK"},
+    {ET_GPIO_PORT_MOSI, ET_GPIO_PIN_MOSI, "MOSI"},
+    {ET_GPIO_PORT_MISO, ET_GPIO_PIN_MISO, "MISO"},
+    {ET_GPIO_PORT_IO1,  ET_GPIO_PIN_IO1, "IO1"},
+    {ET_GPIO_PORT_IO2,  ET_GPIO_PIN_IO2, "IO2"},
+    {ET_GPIO_PORT_IO3,  ET_GPIO_PIN_IO3, "IO3"},
+    {ET_GPIO_PORT_IO4,  ET_GPIO_PIN_IO4, "IO4"}
+};
+
+EtGpio etGpioSDA = {ET_GPIO_PORT_SDA,  ET_GPIO_PIN_SDA, "SDA"};
+EtGpio etGpioSCL = {ET_GPIO_PORT_SCL,  ET_GPIO_PIN_SCL, "SCL"};
+
+static bool isInit;
+
+static bool exptestTestAllPins(bool test);
+static bool exptestTestPin(EtGpio *etPin, bool test);
+
+static bool exptestRun(void)
+{
+  int i;
+  volatile int delay;
+  bool status = true;
+  GPIO_InitTypeDef GPIO_InitStructure;
+  GpioRegBuf gpioSaved;
+
+  isInit = true;
+
+  status &= sensorsManufacturingTest();
+
+
+  // Enable GPIOs
+  RCC_AHB1PeriphClockCmd(ET_GPIO_PERIF, ENABLE);
+
+  decktestSaveGPIOStatesABC(&gpioSaved);
+
+  for (i = 0; i < ET_NBR_PINS; i++)
+  {
+    //Initialize the pins as inputs
+    GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin;
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+    GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+    GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed;
+    GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure);
+  }
+
+  for (i = 0; i < ET_NBR_PINS && status; i++)
+  {
+    // Configure pin as output to poke others
+    GPIO_InitStructure.GPIO_Pin = etGpioIn[i].pin;
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+    GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed;
+    GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure);
+
+    // Test high
+    GPIO_SetBits(etGpioIn[i].port, etGpioIn[i].pin);
+    for (delay = 0; delay < 1000; delay++);
+    if (!exptestTestAllPins(1))
+    {
+      status = false;
+    }
+
+    // Test low
+    GPIO_ResetBits(etGpioIn[i].port, etGpioIn[i].pin);
+    for (delay = 0; delay < 1000; delay++);
+    if (!exptestTestAllPins(0))
+    {
+      status = false;
+    }
+
+    // Restore
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+    GPIO_Init(etGpioIn[i].port, &GPIO_InitStructure);
+  }
+
+  decktestRestoreGPIOStatesABC(&gpioSaved);
+
+  if (status)
+  {
+    // Configure SDA & SCL to turn on OK leds
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+    GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Low_Speed;
+    GPIO_InitStructure.GPIO_Pin = etGpioSDA.pin;
+    GPIO_Init(etGpioSDA.port, &GPIO_InitStructure);
+    GPIO_InitStructure.GPIO_Pin = etGpioSCL.pin;
+    GPIO_Init(etGpioSCL.port, &GPIO_InitStructure);
+    // Turn on OK LEDs.
+    GPIO_ResetBits(etGpioSDA.port, etGpioSDA.pin);
+    GPIO_ResetBits(etGpioSCL.port, etGpioSCL.pin);
+  }
+
+  return status;
+}
+
+
+static bool exptestTestAllPins(bool test)
+{
+  int i;
+  bool status = true;
+
+  for (i = 0; i < ET_NBR_PINS; i++)
+  {
+    if (!exptestTestPin(&etGpioIn[i], test))
+    {
+      status = false;
+    }
+  }
+
+  return status;
+}
+
+static bool exptestTestPin(EtGpio *etPin, bool test)
+{
+  if (test == GPIO_ReadInputDataBit(etPin->port, etPin->pin))
+  {
+    return true;
+  }
+  else
+  {
+    DEBUG_PRINT("Pin:%s != %d [FAIL]\n", etPin->name, test);
+    return false;
+  }
+}
+
+static const DeckDriver exptest_deck = {
+  .vid = 0xBC,
+  .pid = 0xFF,
+  .name = "bcExpTest",
+
+  .usedGpio = 0,               // FIXME: Edit the used GPIOs
+
+  .test = exptestRun,
+};
+
+DECK_DRIVER(exptest_deck);
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/usddeck.c b/crazyflie-firmware-src/src/deck/drivers/src/usddeck.c
new file mode 100644
index 0000000000000000000000000000000000000000..b04157f6809c25f8766f5ef3028d3d8db498183f
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/usddeck.c
@@ -0,0 +1,219 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2016 Bitcraze AB
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.  IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * usddeck.c: micro SD deck driver. Implements logging to micro SD card.
+ */
+
+#define DEBUG_MODULE "uSD"
+
+#include <stdint.h>
+#include <string.h>
+#include "stm32fxxx.h"
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "timers.h"
+
+#include "ff.h"
+#include "fatfs_sd.h"
+
+#include "deck.h"
+#include "usddeck.h"
+#include "deck_spi.h"
+#include "system.h"
+#include "debug.h"
+#include "led.h"
+
+// Hardware defines
+#define USD_CS_PIN    DECK_GPIO_IO4
+
+// FATFS low lever driver functions.
+static void initSpi(void);
+static void setSlowSpiMode(void);
+static void setFastSpiMode(void);
+static BYTE xchgSpi(BYTE dat);
+static void rcvrSpiMulti(BYTE *buff, UINT btr);
+static void xmitSpiMulti(const BYTE *buff, UINT btx);
+static void csHigh(void);
+static void csLow(void);
+
+static BYTE exchangeBuff[512];
+#ifdef USD_RUN_DISKIO_FUNCTION_TESTS
+DWORD workBuff[512];  /* 2048 byte working buffer */
+#endif
+
+static xTimerHandle timer;
+static void usdTimer(xTimerHandle timer);
+
+//Fatfs object
+FATFS FatFs;
+//File object
+FIL logFile;
+
+// Low lever driver functions
+static sdSpiContext_t sdSpiContext =
+{
+  .initSpi = initSpi,
+  .setSlowSpiMode = setSlowSpiMode,
+  .setFastSpiMode = setFastSpiMode,
+  .xchgSpi = xchgSpi,
+  .rcvrSpiMulti = rcvrSpiMulti,
+  .xmitSpiMulti = xmitSpiMulti,
+  .csLow = csLow,
+  .csHigh = csHigh,
+
+  .stat = STA_NOINIT,
+  .timer1 = 0,
+  .timer2 = 0
+};
+
+static DISKIO_LowLevelDriver_t fatDrv =
+{
+    SD_disk_initialize,
+    SD_disk_status,
+    SD_disk_ioctl,
+    SD_disk_write,
+    SD_disk_read,
+    &sdSpiContext,
+};
+
+
+/*-----------------------------------------------------------------------*/
+/* FATFS SPI controls (Platform dependent)                               */
+/*-----------------------------------------------------------------------*/
+
+/* Initialize MMC interface */
+static void initSpi(void)
+{
+  spiBegin();   /* Enable SPI function */
+  pinMode(USD_CS_PIN, OUTPUT);
+  csHigh();
+
+  // FIXME: DELAY of 10ms?
+}
+
+static void setSlowSpiMode(void)
+{
+  spiConfigureSlow();
+}
+
+static void setFastSpiMode(void)
+{
+  spiConfigureFast();
+}
+
+/* Exchange a byte */
+static BYTE xchgSpi(BYTE dat)
+{
+  BYTE receive;
+
+  spiExchange(1, &dat, &receive);
+  return (BYTE)receive;
+}
+
+/* Receive multiple byte */
+static void rcvrSpiMulti(BYTE *buff, UINT btr)
+{
+  memset(exchangeBuff, 0xFFFFFFFF, btr);
+  spiExchange(btr, exchangeBuff, buff);
+}
+
+/* Send multiple byte */
+static void xmitSpiMulti(const BYTE *buff, UINT btx)
+{
+  spiExchange(btx, buff, exchangeBuff);
+}
+
+static void csHigh(void)
+{
+  digitalWrite(USD_CS_PIN, 1);
+}
+
+static void csLow(void)
+{
+  digitalWrite(USD_CS_PIN, 0);
+}
+
+
+
+/*********** Deck driver initialization ***************/
+
+static bool isInit = false;
+
+static void usdInit(DeckInfo *info)
+{
+  isInit = true;
+
+  FATFS_AddDriver(&fatDrv, 0);
+
+  timer = xTimerCreate( "usdTimer", M2T(SD_DISK_TIMER_PERIOD_MS), pdTRUE, NULL, usdTimer);
+  xTimerStart(timer, 0);
+}
+
+static bool usdTest()
+{
+  if (!isInit)
+  {
+    DEBUG_PRINT("Error while initializing uSD deck\n");
+  }
+#ifdef USD_RUN_DISKIO_FUNCTION_TESTS
+  int result;
+  extern int test_diskio (BYTE pdrv, UINT ncyc, DWORD* buff, UINT sz_buff);
+
+  result = test_diskio(0, 1, (DWORD*)&workBuff, sizeof(workBuff));
+  if (result)
+  {
+    DEBUG_PRINT("(result=%d)\nFatFs diskio functions test [FAIL].\n", result);
+    isInit = false;
+  }
+  else
+  {
+    DEBUG_PRINT("FatFs diskio functions test [OK].\n");
+  }
+#endif
+
+  return isInit;
+}
+
+static void usdTimer(xTimerHandle timer)
+{
+  SD_disk_timerproc(&sdSpiContext);
+}
+
+static const DeckDriver usd_deck = {
+  .vid = 0xBC,
+  .pid = 0x08,
+  .name = "bcUSD",
+  .usedGpio = DECK_USING_MISO|DECK_USING_MOSI|DECK_USING_SCK|DECK_USING_IO_4,
+  .usedPeriph = DECK_USING_SPI,
+  .init = usdInit,
+  .test = usdTest,
+};
+
+DECK_DRIVER(usd_deck);
diff --git a/crazyflie-firmware-src/src/deck/drivers/src/vl53l0x.c b/crazyflie-firmware-src/src/deck/drivers/src/vl53l0x.c
new file mode 100644
index 0000000000000000000000000000000000000000..7205227656f8c57043018d839e1db17f5bfc8c9e
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/drivers/src/vl53l0x.c
@@ -0,0 +1,1158 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * vl53l0x.c: Time-of-flight distance sensor driver
+ */
+
+#define DEBUG_MODULE "VLX"
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "deck.h"
+#include "system.h"
+#include "debug.h"
+#include "log.h"
+
+#include "i2cdev.h"
+#include "vl53l0x.h"
+
+#include "stabilizer_types.h"
+#ifdef ESTIMATOR_TYPE_kalman
+
+#include "estimator_kalman.h"
+#include "arm_math.h"
+
+//#define UPDATE_KALMAN_WITH_RANGING // uncomment to push into the kalman
+#ifdef UPDATE_KALMAN_WITH_RANGING
+#define RANGE_OUTLIER_LIMIT 1500 // the measured range is in [mm]
+// Measurement noise model
+static float expPointA = 1.0f;
+static float expStdA = 0.0025f; // STD at elevation expPointA [m]
+static float expPointB = 1.3f;
+static float expStdB = 0.2f;    // STD at elevation expPointB [m]
+static float expCoeff;
+#endif // UPDATE_KALMAN_WITH_RANGING
+#endif // ESTIMATOR_TYPE_kalman
+
+static uint8_t devAddr;
+static I2C_Dev *I2Cx;
+static bool isInit;
+
+static uint16_t io_timeout = 0;
+static bool did_timeout;
+static uint16_t timeout_start_ms;
+
+static uint16_t range_last = 0;
+
+// Record the current time to check an upcoming timeout against
+#define startTimeout() (timeout_start_ms = xTaskGetTickCount())
+
+// Check if timeout is enabled (set to nonzero value) and has expired
+#define checkTimeoutExpired() (io_timeout > 0 && ((uint16_t)xTaskGetTickCount() - timeout_start_ms) > io_timeout)
+
+// Decode VCSEL (vertical cavity surface emitting laser) pulse period in PCLKs
+// from register value
+// based on VL53L0X_decode_vcsel_period()
+#define decodeVcselPeriod(reg_val)      (((reg_val) + 1) << 1)
+
+// Encode VCSEL pulse period register value from period in PCLKs
+// based on VL53L0X_encode_vcsel_period()
+#define encodeVcselPeriod(period_pclks) (((period_pclks) >> 1) - 1)
+
+// Calculate macro period in *nanoseconds* from VCSEL period in PCLKs
+// based on VL53L0X_calc_macro_period_ps()
+// PLL_period_ps = 1655; macro_period_vclks = 2304
+#define calcMacroPeriod(vcsel_period_pclks) ((((uint32_t)2304 * (vcsel_period_pclks) * 1655) + 500) / 1000)
+
+// read by init and used when starting measurement;
+// is StopVariable field of VL53L0X_DevData_t structure in API
+static uint8_t stop_variable;
+
+static uint32_t measurement_timing_budget_us;
+static uint16_t measurement_timing_budget_ms;
+
+// Get reference SPAD (single photon avalanche diode) count and type
+// based on VL53L0X_get_info_from_device(),
+// but only gets reference SPAD count and type
+static bool vl53l0xGetSpadInfo(uint8_t * count, bool * type_is_aperture);
+
+// Get sequence step enables
+// based on VL53L0X_GetSequenceStepEnables()
+static void vl53l0xGetSequenceStepEnables(SequenceStepEnables * enables);
+
+// Get sequence step timeouts
+// based on get_sequence_step_timeout(),
+// but gets all timeouts instead of just the requested one, and also stores
+// intermediate values
+static void vl53l0xGetSequenceStepTimeouts(SequenceStepEnables const * enables, SequenceStepTimeouts * timeouts);
+
+// based on VL53L0X_perform_single_ref_calibration()
+static bool vl53l0xPerformSingleRefCalibration(uint8_t vhv_init_byte);
+
+// Decode sequence step timeout in MCLKs from register value
+// based on VL53L0X_decode_timeout()
+// Note: the original function returned a uint32_t, but the return value is
+// always stored in a uint16_t.
+static uint16_t vl53l0xDecodeTimeout(uint16_t reg_val);
+
+// Encode sequence step timeout register value from timeout in MCLKs
+// based on VL53L0X_encode_timeout()
+// Note: the original function took a uint16_t, but the argument passed to it
+// is always a uint16_t.
+static uint16_t vl53l0xEncodeTimeout(uint16_t timeout_mclks);
+
+// Convert sequence step timeout from MCLKs to microseconds with given VCSEL period in PCLKs
+// based on VL53L0X_calc_timeout_us()
+static uint32_t vl53l0xTimeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks);
+
+// Convert sequence step timeout from microseconds to MCLKs with given VCSEL period in PCLKs
+// based on VL53L0X_calc_timeout_mclks()
+static uint32_t vl53l0xTimeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks);
+
+static uint16_t vl53l0xReadReg16Bit(uint8_t reg);
+static bool vl53l0xWriteReg16Bit(uint8_t reg, uint16_t val);
+static bool vl53l0xWriteReg32Bit(uint8_t reg, uint32_t val);
+
+/** Default constructor, uses default I2C address.
+ * @see VL53L0X_DEFAULT_ADDRESS
+ */
+
+void vl53l0xInit(DeckInfo* info)
+{
+  if (isInit)
+    return;
+
+  i2cdevInit(I2C1_DEV);
+  I2Cx = I2C1_DEV;
+  devAddr = VL53L0X_DEFAULT_ADDRESS;
+  xTaskCreate(vl53l0xTask, "vl53l0x", 2*configMINIMAL_STACK_SIZE, NULL, 3, NULL);
+  
+#if defined(ESTIMATOR_TYPE_kalman) && defined(UPDATE_KALMAN_WITH_RANGING)
+  // pre-compute constant in the measurement noise mdoel
+  expCoeff = logf(expStdB / expStdA) / (expPointB - expPointA);
+#endif
+  
+  isInit = true;
+}
+
+bool vl53l0xTest(void)
+{
+  bool testStatus;
+
+  if (!isInit)
+    return false;
+       // Measurement noise model
+  testStatus  = vl53l0xTestConnection();
+  testStatus &= vl53l0xInitSensor(true);
+
+  return testStatus;
+}
+
+void vl53l0xTask(void* arg)
+{
+  systemWaitStart();
+  TickType_t xLastWakeTime;
+
+  vl53l0xSetVcselPulsePeriod(VcselPeriodPreRange, 18);
+  vl53l0xSetVcselPulsePeriod(VcselPeriodFinalRange, 14);
+  vl53l0xStartContinuous(100);
+  while (1) {
+    xLastWakeTime = xTaskGetTickCount();
+    range_last = vl53l0xReadRangeContinuousMillimeters();
+#if defined(ESTIMATOR_TYPE_kalman) && defined(UPDATE_KALMAN_WITH_RANGING)
+    // check if range is feasible and push into the kalman filter
+    // the sensor should not be able to measure >3 [m], and outliers typically
+    // occur as >8 [m] measurements
+    if (range_last < RANGE_OUTLIER_LIMIT){
+    
+      // Form measurement
+      tofMeasurement_t tofData;
+      tofData.timestamp = xTaskGetTickCount();
+      tofData.distance = (float)range_last * 0.001f; // Scale from [mm] to [m]
+      tofData.stdDev = expStdA * (1.0f  + expf( expCoeff * ( tofData.distance - expPointA)));
+      stateEstimatorEnqueueTOF(&tofData);
+    }
+#endif
+    vTaskDelayUntil(&xLastWakeTime, M2T(measurement_timing_budget_ms));
+  }
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool vl53l0xTestConnection()
+{
+  bool ret = true;
+  ret &= vl53l0xGetModelID() == VL53L0X_IDENTIFICATION_MODEL_ID;
+  ret &= vl53l0xGetRevisionID() == VL53L0X_IDENTIFICATION_REVISION_ID;
+  return ret;
+}
+
+/** Get Model ID.
+ * This register is used to verify the model number of the device,
+ * but only before it has been configured to run
+ * @return Model ID
+ * @see VL53L0X_RA_IDENTIFICATION_MODEL_ID
+ * @see VL53L0X_IDENTIFICATION_MODEL_ID
+ */
+uint16_t vl53l0xGetModelID()
+{
+  return vl53l0xReadReg16Bit(VL53L0X_RA_IDENTIFICATION_MODEL_ID);
+}
+
+/** Get Revision ID.
+ * This register is used to verify the revision number of the device,
+ * but only before it has been configured to run
+ * @return Revision ID
+ * @see VL53L0X_RA_IDENTIFICATION_REVISION_ID
+ * @see VL53L0X_IDENTIFICATION_REVISION_ID
+ */
+uint8_t vl53l0xGetRevisionID()
+{
+  uint8_t output = 0;
+  i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_IDENTIFICATION_REVISION_ID, &output);
+  return output;
+}
+
+// Initialize sensor using sequence based on VL53L0X_DataInit(),
+// VL53L0X_StaticInit(), and VL53L0X_PerformRefCalibration().
+// This function does not perform reference SPAD calibration
+// (VL53L0X_PerformRefSpadManagement()), since the API user manual says that it
+// is performed by ST on the bare modules; it seems like that should work well
+// enough unless a cover glass is added.
+// If io_2v8 (optional) is true or not given, the sensor is configured for 2V8
+// mode.
+bool vl53l0xInitSensor(bool io_2v8)
+{
+  uint8_t temp;
+  // VL53L0X_DataInit() begin
+
+  // sensor uses 1V8 mode for I/O by default; switch to 2V8 mode if necessary
+  if (io_2v8)
+  {
+    i2cdevWriteBit(I2Cx, devAddr, VL53L0X_RA_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV, 0, 0x01);
+  }
+
+  // "Set I2C standard mode"
+  i2cdevWriteByte(I2Cx, devAddr, 0x88, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x00);
+  i2cdevReadByte(I2Cx, devAddr, 0x91, &stop_variable);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x00);
+
+  // disable SIGNAL_RATE_MSRC (bit 1) and SIGNAL_RATE_PRE_RANGE (bit 4) limit checks
+  i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_MSRC_CONFIG_CONTROL, &temp);
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_MSRC_CONFIG_CONTROL, temp | 0x12);
+
+  // set final range signal rate limit to 0.25 MCPS (million counts per second)
+  vl53l0xSetSignalRateLimit(0.25);
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, 0xFF);
+
+  // VL53L0X_DataInit() end
+
+  // VL53L0X_StaticInit() begin
+
+  uint8_t spad_count;
+  bool spad_type_is_aperture;
+  if (!vl53l0xGetSpadInfo(&spad_count, &spad_type_is_aperture)) { return false; }
+
+  // The SPAD map (RefGoodSpadMap) is read by VL53L0X_get_info_from_device() in
+  // the API, but the same data seems to be more easily readable from
+  // GLOBAL_CONFIG_SPAD_ENABLES_REF_0 through _6, so read it from there
+  uint8_t ref_spad_map[6];
+  i2cdevRead(I2Cx, devAddr, VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_0, 6, ref_spad_map);
+
+  // -- VL53L0X_set_reference_spads() begin (assume NVM values are valid)
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_DYNAMIC_SPAD_REF_EN_START_OFFSET, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD, 0x2C);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_GLOBAL_CONFIG_REF_EN_START_SELECT, 0xB4);
+
+  uint8_t first_spad_to_enable = spad_type_is_aperture ? 12 : 0; // 12 is the first aperture spad
+  uint8_t spads_enabled = 0;
+
+  for (uint8_t i = 0; i < 48; i++)
+  {
+    if (i < first_spad_to_enable || spads_enabled == spad_count)
+    {
+      // This bit is lower than the first one that should be enabled, or
+      // (reference_spad_count) bits have already been enabled, so zero this bit
+      ref_spad_map[i / 8] &= ~(1 << (i % 8));
+    }
+    else if ((ref_spad_map[i / 8] >> (i % 8)) & 0x1)
+    {
+      spads_enabled++;
+    }
+  }
+
+  i2cdevWrite(I2Cx, devAddr, VL53L0X_RA_GLOBAL_CONFIG_SPAD_ENABLES_REF_0, 6, ref_spad_map);
+
+  // -- VL53L0X_set_reference_spads() end
+
+  // -- VL53L0X_load_tuning_settings() begin
+  // DefaultTuningSettings from vl53l0x_tuning.h
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x09, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x10, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x11, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0x24, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x25, 0xFF);
+  i2cdevWriteByte(I2Cx, devAddr, 0x75, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x4E, 0x2C);
+  i2cdevWriteByte(I2Cx, devAddr, 0x48, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x30, 0x20);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x30, 0x09);
+  i2cdevWriteByte(I2Cx, devAddr, 0x54, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x31, 0x04);
+  i2cdevWriteByte(I2Cx, devAddr, 0x32, 0x03);
+  i2cdevWriteByte(I2Cx, devAddr, 0x40, 0x83);
+  i2cdevWriteByte(I2Cx, devAddr, 0x46, 0x25);
+  i2cdevWriteByte(I2Cx, devAddr, 0x60, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x27, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x50, 0x06);
+  i2cdevWriteByte(I2Cx, devAddr, 0x51, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x52, 0x96);
+  i2cdevWriteByte(I2Cx, devAddr, 0x56, 0x08);
+  i2cdevWriteByte(I2Cx, devAddr, 0x57, 0x30);
+  i2cdevWriteByte(I2Cx, devAddr, 0x61, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x62, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x64, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x65, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x66, 0xA0);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x22, 0x32);
+  i2cdevWriteByte(I2Cx, devAddr, 0x47, 0x14);
+  i2cdevWriteByte(I2Cx, devAddr, 0x49, 0xFF);
+  i2cdevWriteByte(I2Cx, devAddr, 0x4A, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x7A, 0x0A);
+  i2cdevWriteByte(I2Cx, devAddr, 0x7B, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x78, 0x21);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x23, 0x34);
+  i2cdevWriteByte(I2Cx, devAddr, 0x42, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x44, 0xFF);
+  i2cdevWriteByte(I2Cx, devAddr, 0x45, 0x26);
+  i2cdevWriteByte(I2Cx, devAddr, 0x46, 0x05);
+  i2cdevWriteByte(I2Cx, devAddr, 0x40, 0x40);
+  i2cdevWriteByte(I2Cx, devAddr, 0x0E, 0x06);
+  i2cdevWriteByte(I2Cx, devAddr, 0x20, 0x1A);
+  i2cdevWriteByte(I2Cx, devAddr, 0x43, 0x40);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x34, 0x03);
+  i2cdevWriteByte(I2Cx, devAddr, 0x35, 0x44);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x31, 0x04);
+  i2cdevWriteByte(I2Cx, devAddr, 0x4B, 0x09);
+  i2cdevWriteByte(I2Cx, devAddr, 0x4C, 0x05);
+  i2cdevWriteByte(I2Cx, devAddr, 0x4D, 0x04);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x44, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x45, 0x20);
+  i2cdevWriteByte(I2Cx, devAddr, 0x47, 0x08);
+  i2cdevWriteByte(I2Cx, devAddr, 0x48, 0x28);
+  i2cdevWriteByte(I2Cx, devAddr, 0x67, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x70, 0x04);
+  i2cdevWriteByte(I2Cx, devAddr, 0x71, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x72, 0xFE);
+  i2cdevWriteByte(I2Cx, devAddr, 0x76, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x77, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x0D, 0x01);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x01, 0xF8);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x8E, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x00);
+
+  // -- VL53L0X_load_tuning_settings() end
+
+  // "Set interrupt config to new sample ready"
+  // -- VL53L0X_SetGpioConfig() begin
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_INTERRUPT_CONFIG_GPIO, 0x04);
+  i2cdevWriteBit(I2Cx, devAddr, VL53L0X_RA_GPIO_HV_MUX_ACTIVE_HIGH, 4, 0); // active low
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_INTERRUPT_CLEAR, 0x01);
+
+  // -- VL53L0X_SetGpioConfig() end
+
+  measurement_timing_budget_us = vl53l0xGetMeasurementTimingBudget();
+  measurement_timing_budget_ms = (uint16_t)(measurement_timing_budget_us / 1000.0f);
+
+  // "Disable MSRC and TCC by default"
+  // MSRC = Minimum Signal Rate Check
+  // TCC = Target CentreCheck
+  // -- VL53L0X_SetSequenceStepEnable() begin
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, 0xE8);
+
+  // -- VL53L0X_SetSequenceStepEnable() end
+
+  // "Recalculate timing budget"
+  vl53l0xSetMeasurementTimingBudget(measurement_timing_budget_us);
+
+  // VL53L0X_StaticInit() end
+
+  // VL53L0X_PerformRefCalibration() begin (VL53L0X_perform_ref_calibration())
+
+  // -- VL53L0X_perform_vhv_calibration() begin
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, 0x01);
+  if (!vl53l0xPerformSingleRefCalibration(0x40)) { DEBUG_PRINT("Failed VHV calibration\n"); return false; }
+
+  // -- VL53L0X_perform_vhv_calibration() end
+
+  // -- VL53L0X_perform_phase_calibration() begin
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, 0x02);
+  if (!vl53l0xPerformSingleRefCalibration(0x00)) { DEBUG_PRINT("Failed phase calibration\n"); return false; }
+
+  // -- VL53L0X_perform_phase_calibration() end
+
+  // "restore the previous Sequence Config"
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, 0xE8);
+
+  // VL53L0X_PerformRefCalibration() end
+
+  return true;
+}
+
+// Set the return signal rate limit check value in units of MCPS (mega counts
+// per second). "This represents the amplitude of the signal reflected from the
+// target and detected by the device"; setting this limit presumably determines
+// the minimum measurement necessary for the sensor to report a valid reading.
+// Setting a lower limit increases the potential range of the sensor but also
+// seems to increase the likelihood of getting an inaccurate reading because of
+// unwanted reflections from objects other than the intended target.
+// Defaults to 0.25 MCPS as initialized by the ST API and this library.
+bool vl53l0xSetSignalRateLimit(float limit_Mcps)
+{
+  if (limit_Mcps < 0 || limit_Mcps > 511.99) { return false; }
+
+  // Q9.7 fixed point format (9 integer bits, 7 fractional bits)
+  uint16_t fixed_pt = limit_Mcps * (1 << 7);
+  return vl53l0xWriteReg16Bit(VL53L0X_RA_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT, fixed_pt);
+}
+
+// Set the measurement timing budget in microseconds, which is the time allowed
+// for one measurement; the ST API and this library take care of splitting the
+// timing budget among the sub-steps in the ranging sequence. A longer timing
+// budget allows for more accurate measurements. Increasing the budget by a
+// factor of N decreases the range measurement standard deviation by a factor of
+// sqrt(N). Defaults to about 33 milliseconds; the minimum is 20 ms.
+// based on VL53L0X_set_measurement_timing_budget_micro_seconds()
+bool vl53l0xSetMeasurementTimingBudget(uint32_t budget_us)
+{
+  SequenceStepEnables enables;
+  SequenceStepTimeouts timeouts;
+
+  uint16_t const StartOverhead      = 1320; // note that this is different than the value in get_
+  uint16_t const EndOverhead        = 960;
+  uint16_t const MsrcOverhead       = 660;
+  uint16_t const TccOverhead        = 590;
+  uint16_t const DssOverhead        = 690;
+  uint16_t const PreRangeOverhead   = 660;
+  uint16_t const FinalRangeOverhead = 550;
+
+  uint32_t const MinTimingBudget = 20000;
+
+  if (budget_us < MinTimingBudget) { return false; }
+
+  uint32_t used_budget_us = StartOverhead + EndOverhead;
+
+  vl53l0xGetSequenceStepEnables(&enables);
+  vl53l0xGetSequenceStepTimeouts(&enables, &timeouts);
+
+  if (enables.tcc)
+  {
+    used_budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead);
+  }
+
+  if (enables.dss)
+  {
+    used_budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead);
+  }
+  else if (enables.msrc)
+  {
+    used_budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead);
+  }
+
+  if (enables.pre_range)
+  {
+    used_budget_us += (timeouts.pre_range_us + PreRangeOverhead);
+  }
+
+  if (enables.final_range)
+  {
+    used_budget_us += FinalRangeOverhead;
+
+    // "Note that the final range timeout is determined by the timing
+    // budget and the sum of all other timeouts within the sequence.
+    // If there is no room for the final range timeout, then an error
+    // will be set. Otherwise the remaining time will be applied to
+    // the final range."
+
+    if (used_budget_us > budget_us)
+    {
+      // "Requested timeout too big."
+      return false;
+    }
+
+    uint32_t final_range_timeout_us = budget_us - used_budget_us;
+
+    // set_sequence_step_timeout() begin
+    // (SequenceStepId == VL53L0X_SEQUENCESTEP_FINAL_RANGE)
+
+    // "For the final range timeout, the pre-range timeout
+    //  must be added. To do this both final and pre-range
+    //  timeouts must be expressed in macro periods MClks
+    //  because they have different vcsel periods."
+
+    uint16_t final_range_timeout_mclks =
+      vl53l0xTimeoutMicrosecondsToMclks(final_range_timeout_us,
+                                 timeouts.final_range_vcsel_period_pclks);
+
+    if (enables.pre_range)
+    {
+      final_range_timeout_mclks += timeouts.pre_range_mclks;
+    }
+
+    uint16_t temp = vl53l0xEncodeTimeout(final_range_timeout_mclks);
+    vl53l0xWriteReg16Bit(VL53L0X_RA_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI, temp);
+
+    // set_sequence_step_timeout() end
+
+    measurement_timing_budget_us = budget_us; // store for internal reuse
+    measurement_timing_budget_ms = (uint16_t)(measurement_timing_budget_us / 1000.0f);
+  }
+  return true;
+}
+
+// Get the measurement timing budget in microseconds
+// based on VL53L0X_get_measurement_timing_budget_micro_seconds()
+// in us
+uint32_t vl53l0xGetMeasurementTimingBudget(void)
+{
+  SequenceStepEnables enables;
+  SequenceStepTimeouts timeouts;
+
+  uint16_t const StartOverhead     = 1910; // note that this is different than the value in set_
+  uint16_t const EndOverhead        = 960;
+  uint16_t const MsrcOverhead       = 660;
+  uint16_t const TccOverhead        = 590;
+  uint16_t const DssOverhead        = 690;
+  uint16_t const PreRangeOverhead   = 660;
+  uint16_t const FinalRangeOverhead = 550;
+
+  // "Start and end overhead times always present"
+  uint32_t budget_us = StartOverhead + EndOverhead;
+
+  vl53l0xGetSequenceStepEnables(&enables);
+  vl53l0xGetSequenceStepTimeouts(&enables, &timeouts);
+
+  if (enables.tcc)
+  {
+    budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead);
+  }
+
+  if (enables.dss)
+  {
+    budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead);
+  }
+  else if (enables.msrc)
+  {
+    budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead);
+  }
+
+  if (enables.pre_range)
+  {
+    budget_us += (timeouts.pre_range_us + PreRangeOverhead);
+  }
+
+  if (enables.final_range)
+  {
+    budget_us += (timeouts.final_range_us + FinalRangeOverhead);
+  }
+
+  measurement_timing_budget_us = budget_us; // store for internal reuse
+  measurement_timing_budget_ms = (uint16_t)(measurement_timing_budget_us / 1000.0f);
+  return budget_us;
+}
+
+
+// Set the VCSEL (vertical cavity surface emitting laser) pulse period for the
+// given period type (pre-range or final range) to the given value in PCLKs.
+// Longer periods seem to increase the potential range of the sensor.
+// Valid values are (even numbers only):
+//  pre:  12 to 18 (initialized default: 14)
+//  final: 8 to 14 (initialized default: 10)
+// based on VL53L0X_set_vcsel_pulse_period()
+bool vl53l0xSetVcselPulsePeriod(vcselPeriodType type, uint8_t period_pclks)
+{
+  uint8_t vcsel_period_reg = encodeVcselPeriod(period_pclks);
+
+  SequenceStepEnables enables;
+  SequenceStepTimeouts timeouts;
+
+  vl53l0xGetSequenceStepEnables(&enables);
+  vl53l0xGetSequenceStepTimeouts(&enables, &timeouts);
+
+  // "Apply specific settings for the requested clock period"
+  // "Re-calculate and apply timeouts, in macro periods"
+
+  // "When the VCSEL period for the pre or final range is changed,
+  // the corresponding timeout must be read from the device using
+  // the current VCSEL period, then the new VCSEL period can be
+  // applied. The timeout then must be written back to the device
+  // using the new VCSEL period.
+  //
+  // For the MSRC timeout, the same applies - this timeout being
+  // dependant on the pre-range vcsel period."
+
+
+  if (type == VcselPeriodPreRange)
+  {
+    // "Set phase check limits"
+    switch (period_pclks)
+    {
+      case 12:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x18);
+        break;
+
+      case 14:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x30);
+        break;
+
+      case 16:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x40);
+        break;
+
+      case 18:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x50);
+        break;
+
+      default:
+        // invalid period
+        return false;
+    }
+    i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_PRE_RANGE_CONFIG_VALID_PHASE_LOW, 0x08);
+
+    // apply new VCSEL period
+    i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_PRE_RANGE_CONFIG_VCSEL_PERIOD, vcsel_period_reg);
+
+    // update timeouts
+
+    // set_sequence_step_timeout() begin
+    // (SequenceStepId == VL53L0X_SEQUENCESTEP_PRE_RANGE)
+
+    uint16_t new_pre_range_timeout_mclks =
+      vl53l0xTimeoutMicrosecondsToMclks(timeouts.pre_range_us, period_pclks);
+
+    uint16_t new_pre_range_timeout_encoded = vl53l0xEncodeTimeout(new_pre_range_timeout_mclks);
+    vl53l0xWriteReg16Bit(VL53L0X_RA_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI, new_pre_range_timeout_encoded);
+
+    // set_sequence_step_timeout() end
+
+    // set_sequence_step_timeout() begin
+    // (SequenceStepId == VL53L0X_SEQUENCESTEP_MSRC)
+
+    uint16_t new_msrc_timeout_mclks =
+      vl53l0xTimeoutMicrosecondsToMclks(timeouts.msrc_dss_tcc_us, period_pclks);
+
+    i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_MSRC_CONFIG_TIMEOUT_MACROP,
+      (new_msrc_timeout_mclks > 256) ? 255 : (new_msrc_timeout_mclks - 1));
+
+    // set_sequence_step_timeout() end
+  }
+  else if (type == VcselPeriodFinalRange)
+  {
+    switch (period_pclks)
+    {
+      case 8:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x10);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_LOW,  0x08);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_GLOBAL_CONFIG_VCSEL_WIDTH, 0x02);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x0C);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_LIM, 0x30);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+        break;
+
+      case 10:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x28);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_LOW,  0x08);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_GLOBAL_CONFIG_VCSEL_WIDTH, 0x03);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x09);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_LIM, 0x20);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+        break;
+
+      case 12:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x38);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_LOW,  0x08);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_GLOBAL_CONFIG_VCSEL_WIDTH, 0x03);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x08);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_LIM, 0x20);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+        break;
+
+      case 14:
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x48);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VALID_PHASE_LOW,  0x08);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_GLOBAL_CONFIG_VCSEL_WIDTH, 0x03);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x07);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+        i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_ALGO_PHASECAL_LIM, 0x20);
+        i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+        break;
+
+      default:
+        // invalid period
+        return false;
+    }
+
+    // apply new VCSEL period
+    i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VCSEL_PERIOD, vcsel_period_reg);
+
+    // update timeouts
+
+    // set_sequence_step_timeout() begin
+    // (SequenceStepId == VL53L0X_SEQUENCESTEP_FINAL_RANGE)
+
+    // "For the final range timeout, the pre-range timeout
+    //  must be added. To do this both final and pre-range
+    //  timeouts must be expressed in macro periods MClks
+    //  because they have different vcsel periods."
+
+    uint16_t new_final_range_timeout_mclks =
+      vl53l0xTimeoutMicrosecondsToMclks(timeouts.final_range_us, period_pclks);
+
+    if (enables.pre_range)
+    {
+      new_final_range_timeout_mclks += timeouts.pre_range_mclks;
+    }
+
+    uint16_t new_final_range_timeout_encoded = vl53l0xEncodeTimeout(new_final_range_timeout_mclks);
+    vl53l0xWriteReg16Bit(VL53L0X_RA_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI, new_final_range_timeout_encoded);
+
+    // set_sequence_step_timeout end
+  }
+  else
+  {
+    // invalid type
+    return false;
+  }
+
+  // "Finally, the timing budget must be re-applied"
+
+  vl53l0xSetMeasurementTimingBudget(measurement_timing_budget_us);
+
+  // "Perform the phase calibration. This is needed after changing on vcsel period."
+  // VL53L0X_perform_phase_calibration() begin
+
+  uint8_t sequence_config = 0;
+  i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, &sequence_config);
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, 0x02);
+  bool ret = vl53l0xPerformSingleRefCalibration(0x0);
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, sequence_config);
+
+  // VL53L0X_perform_phase_calibration() end
+
+  return ret;
+}
+
+// Get the VCSEL pulse period in PCLKs for the given period type.
+// based on VL53L0X_get_vcsel_pulse_period()
+uint8_t vl53l0xGetVcselPulsePeriod(vcselPeriodType type)
+{
+  if (type == VcselPeriodPreRange)
+  {
+    uint8_t temp = 0;
+    i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_PRE_RANGE_CONFIG_VCSEL_PERIOD, &temp);
+    return decodeVcselPeriod(temp);
+  }
+  else if (type == VcselPeriodFinalRange)
+  {
+    uint8_t temp = 0;
+    i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_FINAL_RANGE_CONFIG_VCSEL_PERIOD, &temp);
+    return decodeVcselPeriod(temp);
+  }
+  else { return 255; }
+}
+
+// Start continuous ranging measurements. If period_ms (optional) is 0 or not
+// given, continuous back-to-back mode is used (the sensor takes measurements as
+// often as possible); otherwise, continuous timed mode is used, with the given
+// inter-measurement period in milliseconds determining how often the sensor
+// takes a measurement.
+// based on VL53L0X_StartMeasurement()
+void vl53l0xStartContinuous(uint32_t period_ms)
+{
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x91, stop_variable);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x00);
+
+  if (period_ms != 0)
+  {
+    // continuous timed mode
+
+    // VL53L0X_SetInterMeasurementPeriodMilliSeconds() begin
+
+    uint16_t osc_calibrate_val = vl53l0xReadReg16Bit(VL53L0X_RA_OSC_CALIBRATE_VAL);
+
+    if (osc_calibrate_val != 0)
+    {
+      period_ms *= osc_calibrate_val;
+    }
+
+    vl53l0xWriteReg32Bit(VL53L0X_RA_SYSTEM_INTERMEASUREMENT_PERIOD, period_ms);
+
+    // VL53L0X_SetInterMeasurementPeriodMilliSeconds() end
+
+    i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSRANGE_START, 0x04); // VL53L0X_REG_SYSRANGE_MODE_TIMED
+  }
+  else
+  {
+    // continuous back-to-back mode
+    i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSRANGE_START, 0x02); // VL53L0X_REG_SYSRANGE_MODE_BACKTOBACK
+  }
+}
+
+// Stop continuous measurements
+// based on VL53L0X_StopMeasurement()
+void vl53l0xStopContinuous(void)
+{
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSRANGE_START, 0x01); // VL53L0X_REG_SYSRANGE_MODE_SINGLESHOT
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x91, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+}
+
+// Returns a range reading in millimeters when continuous mode is active
+// (readRangeSingleMillimeters() also calls this function after starting a
+// single-shot range measurement)
+uint16_t vl53l0xReadRangeContinuousMillimeters(void)
+{
+  startTimeout();
+  uint8_t val = 0;
+  while ((val & 0x07) == 0)
+  {
+    i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_RESULT_INTERRUPT_STATUS, &val);
+    if (checkTimeoutExpired())
+    {
+      did_timeout = true;
+      return 65535;
+    }
+  }
+
+  // assumptions: Linearity Corrective Gain is 1000 (default);
+  // fractional ranging is not enabled
+  uint16_t range = vl53l0xReadReg16Bit(VL53L0X_RA_RESULT_RANGE_STATUS + 10);
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_INTERRUPT_CLEAR, 0x01);
+
+  return range;
+}
+
+// Performs a single-shot range measurement and returns the reading in
+// millimeters
+// based on VL53L0X_PerformSingleRangingMeasurement()
+uint16_t vl53l0xReadRangeSingleMillimeters(void)
+{
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x91, stop_variable);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSRANGE_START, 0x01);
+
+  // "Wait until start bit has been cleared"
+  startTimeout();
+  uint8_t val = 0x01;
+  while (val & 0x01)
+  {
+    i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_SYSRANGE_START, &val);
+    if (checkTimeoutExpired())
+    {
+      did_timeout = true;
+      return 65535;
+    }
+  }
+
+  return vl53l0xReadRangeContinuousMillimeters();
+}
+
+// Get reference SPAD (single photon avalanche diode) count and type
+// based on VL53L0X_get_info_from_device(),
+// but only gets reference SPAD count and type
+bool vl53l0xGetSpadInfo(uint8_t * count, bool * type_is_aperture)
+{
+  uint8_t tmp;
+
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x00);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x06);
+  i2cdevWriteBit(I2Cx, devAddr, 0x83, 2, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x07);
+  i2cdevWriteByte(I2Cx, devAddr, 0x81, 0x01);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x01);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0x94, 0x6b);
+  i2cdevWriteByte(I2Cx, devAddr, 0x83, 0x00);
+  startTimeout();
+
+  uint8_t val = 0x00;
+  while (val == 0x00) {
+    i2cdevReadByte(I2Cx, devAddr, 0x83, &val);
+    if (checkTimeoutExpired()) { return false; }
+  };
+  i2cdevWriteByte(I2Cx, devAddr, 0x83, 0x01);
+  i2cdevReadByte(I2Cx, devAddr, 0x92, &tmp);
+
+  *count = tmp & 0x7f;
+  *type_is_aperture = (tmp >> 7) & 0x01;
+
+  i2cdevWriteByte(I2Cx, devAddr, 0x81, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x06);
+  i2cdevWriteBit(I2Cx, devAddr, 0x83, 2, 0);
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x01);
+  i2cdevWriteByte(I2Cx, devAddr, 0x00, 0x01);
+
+  i2cdevWriteByte(I2Cx, devAddr, 0xFF, 0x00);
+  i2cdevWriteByte(I2Cx, devAddr, 0x80, 0x00);
+
+  return true;
+}
+
+// Get sequence step enables
+// based on VL53L0X_GetSequenceStepEnables()
+void vl53l0xGetSequenceStepEnables(SequenceStepEnables * enables)
+{
+  uint8_t sequence_config = 0;
+  i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_SEQUENCE_CONFIG, &sequence_config);
+
+  enables->tcc          = (sequence_config >> 4) & 0x1;
+  enables->dss          = (sequence_config >> 3) & 0x1;
+  enables->msrc         = (sequence_config >> 2) & 0x1;
+  enables->pre_range    = (sequence_config >> 6) & 0x1;
+  enables->final_range  = (sequence_config >> 7) & 0x1;
+}
+
+// Get sequence step timeouts
+// based on get_sequence_step_timeout(),
+// but gets all timeouts instead of just the requested one, and also stores
+// intermediate values
+void vl53l0xGetSequenceStepTimeouts(SequenceStepEnables const * enables, SequenceStepTimeouts * timeouts)
+{
+  timeouts->pre_range_vcsel_period_pclks = vl53l0xGetVcselPulsePeriod(VcselPeriodPreRange);
+
+  uint8_t temp = 0;
+  i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_MSRC_CONFIG_TIMEOUT_MACROP, &temp);
+  timeouts->msrc_dss_tcc_mclks = temp + 1;
+  timeouts->msrc_dss_tcc_us =
+    vl53l0xTimeoutMclksToMicroseconds(timeouts->msrc_dss_tcc_mclks,
+                               timeouts->pre_range_vcsel_period_pclks);
+
+  uint16_t pre_range_encoded = vl53l0xReadReg16Bit(VL53L0X_RA_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI);
+  timeouts->pre_range_mclks = vl53l0xDecodeTimeout(pre_range_encoded);
+  timeouts->pre_range_us =
+    vl53l0xTimeoutMclksToMicroseconds(timeouts->pre_range_mclks,
+                               timeouts->pre_range_vcsel_period_pclks);
+
+  timeouts->final_range_vcsel_period_pclks = vl53l0xGetVcselPulsePeriod(VcselPeriodFinalRange);
+
+  uint16_t final_range_encoded = vl53l0xReadReg16Bit(VL53L0X_RA_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI);
+  timeouts->final_range_mclks = vl53l0xDecodeTimeout(final_range_encoded);
+
+  if (enables->pre_range)
+  {
+    timeouts->final_range_mclks -= timeouts->pre_range_mclks;
+  }
+
+  timeouts->final_range_us =
+    vl53l0xTimeoutMclksToMicroseconds(timeouts->final_range_mclks,
+                               timeouts->final_range_vcsel_period_pclks);
+}
+
+// Decode sequence step timeout in MCLKs from register value
+// based on VL53L0X_decode_timeout()
+// Note: the original function returned a uint32_t, but the return value is
+// always stored in a uint16_t.
+uint16_t vl53l0xDecodeTimeout(uint16_t reg_val)
+{
+  // format: "(LSByte * 2^MSByte) + 1"
+  return (uint16_t)((reg_val & 0x00FF) <<
+         (uint16_t)((reg_val & 0xFF00) >> 8)) + 1;
+}
+
+// Encode sequence step timeout register value from timeout in MCLKs
+// based on VL53L0X_encode_timeout()
+// Note: the original function took a uint16_t, but the argument passed to it
+// is always a uint16_t.
+uint16_t vl53l0xEncodeTimeout(uint16_t timeout_mclks)
+{
+  // format: "(LSByte * 2^MSByte) + 1"
+
+  uint32_t ls_byte = 0;
+  uint16_t ms_byte = 0;
+
+  if (timeout_mclks > 0)
+  {
+    ls_byte = timeout_mclks - 1;
+
+    while ((ls_byte & 0xFFFFFF00LU) > 0)
+    {
+      ls_byte >>= 1;
+      ms_byte++;
+    }
+
+    return (ms_byte << 8) | (ls_byte & 0xFF);
+  }
+  else { return 0; }
+}
+
+// Convert sequence step timeout from MCLKs to microseconds with given VCSEL period in PCLKs
+// based on VL53L0X_calc_timeout_us()
+uint32_t vl53l0xTimeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks)
+{
+  uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks);
+
+  return ((timeout_period_mclks * macro_period_ns) + (macro_period_ns / 2)) / 1000;
+}
+
+// Convert sequence step timeout from microseconds to MCLKs with given VCSEL period in PCLKs
+// based on VL53L0X_calc_timeout_mclks()
+uint32_t vl53l0xTimeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks)
+{
+  uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks);
+
+  return (((timeout_period_us * 1000) + (macro_period_ns / 2)) / macro_period_ns);
+}
+
+// based on VL53L0X_perform_single_ref_calibration()
+bool vl53l0xPerformSingleRefCalibration(uint8_t vhv_init_byte)
+{
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSRANGE_START, 0x01 | vhv_init_byte); // VL53L0X_REG_SYSRANGE_MODE_START_STOP
+
+  startTimeout();
+  uint8_t temp = 0x00;
+  while ((temp & 0x07) == 0)
+  {
+    i2cdevReadByte(I2Cx, devAddr, VL53L0X_RA_RESULT_INTERRUPT_STATUS, &temp);
+    if (checkTimeoutExpired()) { return false; }
+  }
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSTEM_INTERRUPT_CLEAR, 0x01);
+
+  i2cdevWriteByte(I2Cx, devAddr, VL53L0X_RA_SYSRANGE_START, 0x00);
+
+  return true;
+}
+
+uint16_t vl53l0xReadReg16Bit(uint8_t reg)
+{
+  uint8_t buffer[2] = {};
+  i2cdevRead(I2Cx, devAddr, reg, 2, (uint8_t *)&buffer);
+  return ((uint16_t)(buffer[0]) << 8) | buffer[1];
+}
+
+bool vl53l0xWriteReg16Bit(uint8_t reg, uint16_t val)
+{
+  uint8_t buffer[2] = {};
+  buffer[0] = ((val >> 8) & 0xFF);
+  buffer[1] = ((val     ) & 0xFF);
+  return i2cdevWrite(I2Cx, devAddr, reg, 2, (uint8_t *)&buffer);
+}
+
+bool vl53l0xWriteReg32Bit(uint8_t reg, uint32_t val)
+{
+  uint8_t buffer[4] = {};
+  buffer[0] = ((val >> 24) & 0xFF);
+  buffer[1] = ((val >> 16) & 0xFF);
+  buffer[2] = ((val >>  8) & 0xFF);
+  buffer[3] = ((val      ) & 0xFF);
+  return i2cdevWrite(I2Cx, devAddr, reg, 4, (uint8_t *)&buffer);
+}
+
+// TODO: Decide on vid:pid and set the used pins
+static const DeckDriver vl53l0x_deck = {
+  .vid = 0, // Changed this from 0
+  .pid = 0, // Changed this from 0
+  .name = "vl53l0x",
+  .usedGpio = 0,
+
+  .init = vl53l0xInit,
+  .test = vl53l0xTest,
+};
+
+DECK_DRIVER(vl53l0x_deck);
+
+LOG_GROUP_START(range)
+LOG_ADD(LOG_UINT16, range, &range_last)
+LOG_GROUP_STOP(range)
+
diff --git a/crazyflie-firmware-src/src/deck/interface/deck.h b/crazyflie-firmware-src/src/deck/interface/deck.h
new file mode 100644
index 0000000000000000000000000000000000000000..3de5d65646df1d3275281d297e10e4e0d7df3c68
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/interface/deck.h
@@ -0,0 +1,15 @@
+// Includes all the deck C API headers
+
+#ifndef __DECK_H__
+#define __DECK_H__
+
+/* Core: handles initialisation, discovery and drivers */
+#include "deck_core.h"
+
+/* Deck APIs */
+#include "deck_constants.h"
+#include "deck_digital.h"
+#include "deck_analog.h"
+#include "deck_spi.h"
+
+#endif
diff --git a/crazyflie-firmware-src/src/deck/interface/deck_analog.h b/crazyflie-firmware-src/src/deck/interface/deck_analog.h
new file mode 100644
index 0000000000000000000000000000000000000000..324827804042a6ebf4d89449f955057feb89d730
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/interface/deck_analog.h
@@ -0,0 +1,51 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_analog.h - Arduino-compatible analog input API
+ */
+
+#ifndef __DECK_ANALOG_H__
+#define __DECK_ANALOG_H__
+
+#include <stdint.h>
+
+/* Voltage reference types for the analogReference() function. */
+#define DEFAULT 0
+#define VREF    3.0
+
+void adcInit(void);
+
+uint16_t analogRead(uint32_t pin);
+
+void analogReference(uint8_t type);
+
+void analogReadResolution(uint8_t bits);
+
+/*
+ * Read the voltage on a deck pin.
+ * @param[in] pin   deck pin to measure.
+ * @return          voltage in volts
+ */
+float analogReadVoltage(uint32_t pin);
+
+#endif
diff --git a/crazyflie-firmware-src/src/deck/interface/deck_constants.h b/crazyflie-firmware-src/src/deck/interface/deck_constants.h
new file mode 100644
index 0000000000000000000000000000000000000000..d83927ac9b07e0976c1f9244d203fd80c2048df8
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/interface/deck_constants.h
@@ -0,0 +1,70 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_contants.h - Arduino-compatible constant definition
+ */
+
+#ifndef __DECK_CONSTANTS_H__
+#define __DECK_CONSTANTS_H__
+
+// For true and false
+#include <stdbool.h>
+
+#include "stm32fxxx.h"
+
+#define LOW 0x0
+#define HIGH 0x1
+
+#define INPUT           0x0
+#define OUTPUT          0x1
+#define INPUT_PULLUP    0x2
+#define INPUT_PULLDOWN  0x3
+
+/*
+ * The Deck port GPIO pins, as named by the deck port / expansion port / expansion breakout documentation on bitcraze.io.
+ * Sequenced according to the deckGPIOMapping struct, so that these can be used for lookup in the struct.
+ */
+#define DECK_GPIO_RX1   1
+#define DECK_GPIO_TX1   2
+#define DECK_GPIO_SDA   3
+#define DECK_GPIO_SCL   4
+#define DECK_GPIO_IO1   5
+#define DECK_GPIO_IO2   6
+#define DECK_GPIO_IO3   7
+#define DECK_GPIO_IO4   8
+#define DECK_GPIO_TX2   9
+#define DECK_GPIO_RX2  10
+#define DECK_GPIO_SCK  11
+#define DECK_GPIO_MISO 12
+#define DECK_GPIO_MOSI 13
+
+typedef const struct {
+  uint32_t periph;
+  GPIO_TypeDef* port;
+  uint16_t pin;
+  int8_t adcCh; /* -1 means no ADC available for this pin. */
+} deckGPIOMapping_t;
+
+extern deckGPIOMapping_t deckGPIOMapping[];
+
+#endif
diff --git a/crazyflie-firmware-src/src/deck/interface/deck_core.h b/crazyflie-firmware-src/src/deck/interface/deck_core.h
new file mode 100644
index 0000000000000000000000000000000000000000..14a6f5e79b2c608ccbb5587db02b45a16c4bb0bb
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/interface/deck_core.h
@@ -0,0 +1,166 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_core.h - Definitions and interface to handle deck init and drivers
+ *               Implementation is in deck.c, deck_info.c and deck_drivers.c
+ */
+
+#ifndef __DECK_CODE_H__
+#define __DECK_CODE_H__
+
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/* Maximum number of decks that can be enumerated */
+#define DECK_MAX_COUNT 4
+
+/* Main functions to init and test the decks, called during system initialisation */
+void deckInit(void);
+bool deckTest(void);
+
+/***** Driver TOC definitions ******/
+
+/* Used peripherals */
+#define DECK_USING_UART1   (1<<0)
+#define DECK_USING_UART2   (1<<1)
+#define DECK_USING_SPI     (1<<2)
+#define DECK_USING_TIMER3  (1<<3)
+#define DECK_USING_TIMER5  (1<<4)
+#define DECK_USING_TIMER14 (1<<5)
+
+/* Used GPIO */
+#define DECK_USING_PC11 (1<<0)
+#define DECK_USING_RX1  (1<<0)
+#define DECK_USING_PC10 (1<<1)
+#define DECK_USING_TX1  (1<<1)
+#define DECK_USING_PB7  (1<<2)
+#define DECK_USING_SDA  (1<<2)
+#define DECK_USING_PB6  (1<<3)
+#define DECK_USING_SCL  (1<<3)
+#define DECK_USING_PB8  (1<<4)
+#define DECK_USING_IO_1 (1<<4)
+#define DECK_USING_PB5  (1<<5)
+#define DECK_USING_IO_2 (1<<5)
+#define DECK_USING_PB4  (1<<6)
+#define DECK_USING_IO_3 (1<<6)
+#define DECK_USING_PC12 (1<<7)
+#define DECK_USING_IO_4 (1<<7)
+#define DECK_USING_PA2  (1<<8)
+#define DECK_USING_TX2  (1<<8)
+#define DECK_USING_PA3  (1<<9)
+#define DECK_USING_RX2  (1<<9)
+#define DECK_USING_PA5  (1<<10)
+#define DECK_USING_SCK  (1<<10)
+#define DECK_USING_PA6  (1<<11)
+#define DECK_USING_MISO (1<<11)
+#define DECK_USING_PA7  (1<<12)
+#define DECK_USING_MOSI (1<<12)
+
+struct deckInfo_s;
+
+/* Structure definition and registering macro */
+typedef struct deck_driver {
+  /* Identification of the deck (written in the board) */
+  uint8_t vid;
+  uint8_t pid;
+  char *name;
+
+  /* Periphreal and Gpio used _dirrectly_ by the driver */
+  uint32_t usedPeriph;
+  uint32_t usedGpio;
+
+  /* Init and test functions */
+  void (*init)(struct deckInfo_s *);
+  bool (*test)(void);
+} DeckDriver;
+
+#define DECK_DRIVER(NAME) const struct deck_driver * driver_##NAME __attribute__((section(".deckDriver." #NAME), used)) = &(NAME)
+
+/****** Deck_info *******/
+
+#define DECK_INFO_HEADER_ID 0xeb
+#define DECK_INFO_HEADER_SIZE 7
+#define DECK_INFO_TLV_VERSION 0
+#define DECK_INFO_TLV_VERSION_POS 8
+#define DECK_INFO_TLV_LENGTH_POS 9
+#define DECK_INFO_TLV_DATA_POS 10
+
+typedef struct {
+  uint8_t *data;
+  int length;
+} TlvArea;
+
+typedef struct deckInfo_s {
+
+  union {
+    struct {
+      uint8_t header;
+      uint32_t usedPins;
+      uint8_t vid;
+      uint8_t pid;
+      uint8_t crc;
+
+      uint8_t rawTlv[104];
+    } __attribute__((packed));
+
+    uint8_t raw[112];
+  };
+
+  TlvArea tlv;
+  const DeckDriver *driver;
+} DeckInfo;
+
+int deckCount(void);
+
+DeckInfo * deckInfo(int i);
+
+/* Key/value area handling */
+bool deckTlvHasElement(TlvArea *tlv, int type);
+
+int deckTlvGetString(TlvArea *tlv, int type, char *string, int maxLength);
+
+char* deckTlvGetBuffer(TlvArea *tlv, int type, int *length);
+
+void deckTlvGetTlv(TlvArea *tlv, int type, TlvArea *output);
+
+/* Defined Types */
+#define DECK_INFO_NAME 1
+#define DECK_INFO_REVISION 2
+#define DECK_INFO_CUSTOMDATA 3
+
+/***** Drivers introspection API ******/
+
+/* Returns the number of driver registered */
+int deckDriverCount();
+
+/* Returns one driver definition */
+const struct deck_driver* deckGetDriver(int i);
+
+/* Find driver by pid/vid */
+const struct deck_driver* deckFindDriverByVidPid(uint8_t vid, uint8_t pid);
+
+/*find driver by name */
+const struct deck_driver* deckFindDriverByName(char* name);
+
+#endif //__DECK_CODE_H__
diff --git a/crazyflie-firmware-src/src/deck/interface/deck_digital.h b/crazyflie-firmware-src/src/deck/interface/deck_digital.h
new file mode 100644
index 0000000000000000000000000000000000000000..651e7584934117808ae17d64a93d42f2c86f868f
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/interface/deck_digital.h
@@ -0,0 +1,38 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_digital.h - Arduino-compatible digital I/O API
+ */
+
+#ifndef __DECK_DIGITAL_H__
+#define __DECK_DIGITAL_H__
+
+#include <stdint.h>
+
+void pinMode(uint32_t pin, uint32_t mode);
+
+void digitalWrite(uint32_t pin, uint32_t val);
+
+int digitalRead(uint32_t pin);
+
+#endif
diff --git a/crazyflie-firmware-src/src/deck/interface/deck_spi.h b/crazyflie-firmware-src/src/deck/interface/deck_spi.h
new file mode 100644
index 0000000000000000000000000000000000000000..169149fa2afe7dbc109d380cd3493d94b3f14d33
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/interface/deck_spi.h
@@ -0,0 +1,43 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_spi.h - Deck-API SPI communication header
+ */
+#ifndef SPI_H_
+#define SPI_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <string.h>
+
+/**
+ * Initialize the SPI.
+ */
+void spiBegin(void);
+void spiConfigureSlow(void);
+void spiConfigureFast(void);
+
+/* Send the data_tx buffer and receive into the data_rx buffer */
+bool spiExchange(size_t length, const uint8_t *data_tx, uint8_t *data_rx);
+
+#endif /* SPI_H_ */
diff --git a/crazyflie-firmware-src/src/deck/interface/deck_test.h b/crazyflie-firmware-src/src/deck/interface/deck_test.h
new file mode 100644
index 0000000000000000000000000000000000000000..6e3f5e8125258b1a00b07521ad1d963a8b40942e
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/interface/deck_test.h
@@ -0,0 +1,65 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * deck_test.h - Deck test utility functions
+ */
+
+#ifndef __DECK_TEST_H__
+#define __DECK_TEST_H__
+
+#include <stdint.h>
+#include "stm32fxxx.h"
+
+typedef struct
+{
+  GPIO_TypeDef gpioBuffA;
+  GPIO_TypeDef gpioBuffB;
+  GPIO_TypeDef gpioBuffC;
+} GpioRegBuf;
+
+/**
+ * Deck test evaluation function which makes evaluation
+ * a bit less messy. Outputs failstring on console if test
+ * failed.
+ *
+ * param[in]   result      The result of the test.
+ * param[in]   failstring  Pointer to fail string.
+ * param[out]  status      Saves the test result.
+ */
+void decktestEval(bool result, char *failString, bool *status);
+
+/**
+ * Save GPIO registers into buffer so it can be restored later
+ *
+ * param[out] gpioRegBuf  Buffer to which registers will be copied
+ */
+void decktestSaveGPIOStatesABC(GpioRegBuf *gpioRegBuf);
+
+/**
+ * Restore saved GPIO registers
+ *
+ * param[in] gpioRegBuf Buffer of saved registers
+ */
+void decktestRestoreGPIOStatesABC(GpioRegBuf *gpioRegBuf);
+
+#endif
diff --git a/crazyflie-firmware-src/src/deck/readme b/crazyflie-firmware-src/src/deck/readme
new file mode 100644
index 0000000000000000000000000000000000000000..5b5d4a462c5f4384caacbf72866572f00f7313c6
--- /dev/null
+++ b/crazyflie-firmware-src/src/deck/readme
@@ -0,0 +1,8 @@
+Deck API
+========
+
+This folder contains files implementing the deck I/O API. Currently only the
+Crazyflie 2.0 implements this api for the Deck expantion port I/Os.
+
+The API is inspired by the Arduino API. It implements the arduino API mapping
+C++ to C function in a consistent way.
diff --git a/crazyflie-firmware-src/src/drivers/interface/adc.h b/crazyflie-firmware-src/src/drivers/interface/adc.h
new file mode 100644
index 0000000000000000000000000000000000000000..863f58abdc9f35c5c05701a25d29056a1d5f7a54
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/adc.h
@@ -0,0 +1,120 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * adc.h - Analog Digital Conversion header file
+ */
+#ifndef ADC_H_
+#define ADC_H_
+
+#include <stdbool.h>
+#include <stdint.h>
+#include "FreeRTOS.h"
+#include "semphr.h"
+#include "config.h"
+
+/******** Defines ********/
+
+/**
+ * \def ADC_MEAN_SIZE
+ * Number of samples used in the mean value calculation.
+ * Mean size should be evenly dividable by decimation bits.
+ */
+#define ADC_DECIMATE_TO_BITS  12
+#define ADC_MEAN_SIZE         8
+
+#define ADC_RESOLUTION        12
+#define ADC_DECIMATE_DIVEDEND (ADC_MEAN_SIZE / (1 << (ADC_DECIMATE_TO_BITS - ADC_RESOLUTION)))
+
+#if ADC_DECIMATE_TO_BITS < ADC_RESOLUTION
+#  error "ADC_DECIMATE_TO_BITS must be bigger or equal to ADC_RESOLUTION"
+#endif
+
+#define ADC_SAMPLING_FREQ      100
+#define ADC_OVERSAMPLING_FREQ  (ADC_SAMPLING_FREQ * ADC_MEAN_SIZE)
+
+#define ADC_TRIG_PRESCALE       1
+#define ADC_TRIG_PRESCALE_FREQ  (72000000 / (ADC_TRIG_PRESCALE + 1))
+#define ADC_TRIG_PERIOD         (ADC_TRIG_PRESCALE_FREQ / (ADC_OVERSAMPLING_FREQ))
+
+#define ADC_INTERNAL_VREF   1.20
+
+/******** Types ********/
+
+typedef struct __attribute__((packed))
+{
+  uint16_t vref;
+  uint16_t val;
+} AdcPair;
+
+typedef struct __attribute__((packed))
+{
+  AdcPair vbat;
+} AdcGroup;
+
+typedef struct
+{
+  uint16_t vbat;
+  uint16_t vbatVref;
+} AdcDeciGroup;
+
+/*** Public interface ***/
+
+/**
+ * Initialize analog to digital converter. Configures gyro and vref channels.
+ * Configures DMA to transfer the result.
+ */
+void adcInit(void);
+
+bool adcTest(void);
+
+/**
+ * Converts a 12 bit ADC value to battery voltage
+ * @param vbat  12 bit adc value
+ * @param vref  12 bit adc value of the internal voltage
+ *              reference, 1.2V
+ *
+ * @return The voltage in a float value
+ */
+float adcConvertToVoltageFloat(uint16_t v, uint16_t vref);
+
+/**
+ * Starts converting ADC samples by activating the DMA.
+ */
+void adcDmaStart(void);
+
+/**
+ * Stop converting ADC samples.
+ */
+void adcDmaStop(void);
+
+/**
+ * ADC interrupt handler
+ */
+void adcInterruptHandler(void);
+
+/**
+ * ADC task
+ */
+void adcTask(void *param);
+
+#endif /* ADC_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/ak8963.h b/crazyflie-firmware-src/src/drivers/interface/ak8963.h
new file mode 100644
index 0000000000000000000000000000000000000000..81f9e87ebc1818256a4d7029beabed3be69feeab
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/ak8963.h
@@ -0,0 +1,140 @@
+// I2Cdev library collection - AK8975 I2C device class header file
+// Based on AKM AK8975/B datasheet, 12/2009
+// 8/27/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     2011-08-27 - initial release
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2011 Jeff Rowberg
+Adapted to Crazyflie FW by Bitcraze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _AK8963_H_
+#define _AK8963_H_
+
+#include "i2cdev.h"
+#include <stdint.h>
+
+#define AK8963_ADDRESS_00         0x0C
+#define AK8963_ADDRESS_01         0x0D
+#define AK8963_ADDRESS_10         0x0E // default for InvenSense MPU-6050 evaluation board
+#define AK8963_ADDRESS_11         0x0F
+#define AK8963_DEFAULT_ADDRESS    AK8963_ADDRESS_00
+
+#define AK8963_RA_WIA             0x00
+#define AK8963_RA_INFO            0x01
+#define AK8963_RA_ST1             0x02
+#define AK8963_RA_HXL             0x03
+#define AK8963_RA_HXH             0x04
+#define AK8963_RA_HYL             0x05
+#define AK8963_RA_HYH             0x06
+#define AK8963_RA_HZL             0x07
+#define AK8963_RA_HZH             0x08
+#define AK8963_RA_ST2             0x09
+#define AK8963_RA_CNTL            0x0A
+#define AK8963_RA_CNTL2           0x0B
+#define AK8963_RA_ASTC            0x0C
+#define AK8963_RA_TS1             0x0D // SHIPMENT TEST, DO NOT USE
+#define AK8963_RA_TS2             0x0E // SHIPMENT TEST, DO NOT USE
+#define AK8963_RA_I2CDIS          0x0F
+#define AK8963_RA_ASAX            0x10
+#define AK8963_RA_ASAY            0x11
+#define AK8963_RA_ASAZ            0x12
+
+#define AK8963_ST1_DRDY_BIT       0
+
+#define AK8963_ST2_HOFL_BIT       3
+#define AK8963_ST2_DERR_BIT       2
+
+#define AK8963_CNTL_MODE_BIT      3
+#define AK8963_CNTL_MODE_LENGTH   4
+
+#define AK8963_MODE_POWERDOWN     0x00
+#define AK8963_MODE_SINGLE        0x01
+#define AK8963_MODE_CONT1         0x02
+#define AK8963_MODE_CONT2         0x06
+#define AK8963_MODE_EXTTRIG       0x04
+#define AK8963_MODE_SELFTEST      0x08
+#define AK8963_MODE_FUSEROM       0x0F
+#define AK8963_MODE_14BIT         0x00
+#define AK8963_MODE_16BIT         0x10
+
+#define AK8963_ASTC_SELF_BIT      6
+
+#define AK8963_I2CDIS_BIT         0
+
+#define AK8963_ST_X_MIN           (int16_t)(-200)
+#define AK8963_ST_X_MAX           (int16_t)(200)
+#define AK8963_ST_Y_MIN           (int16_t)(-200)
+#define AK8963_ST_Y_MAX           (int16_t)(200)
+#define AK8963_ST_Z_MIN           (int16_t)(-3200)
+#define AK8963_ST_Z_MAX           (int16_t)(-800)
+
+
+void ak8963Init(I2C_Dev *i2cPort);
+bool ak8963TestConnection();
+bool ak8963SelfTest();
+
+// WIA register
+uint8_t ak8963GetDeviceID();
+
+// INFO register
+uint8_t ak8963GetInfo();
+
+// ST1 register
+bool ak8963GetDataReady();
+
+// H* registers
+void ak8963GetHeading(int16_t *x, int16_t *y, int16_t *z);
+int16_t ak8963GetHeadingX();
+int16_t ak8963GetHeadingY();
+int16_t ak8963GetHeadingZ();
+
+// ST2 register
+bool ak8963GetOverflowStatus();
+bool ak8963GetDataError();
+
+// CNTL register
+uint8_t ak8963GetMode();
+void ak8963SetMode(uint8_t mode);
+void ak8963Reset();
+
+// ASTC register
+void ak8963SetSelfTest(bool enabled);
+
+// I2CDIS
+void ak8963DisableI2C(); // um, why...?
+
+// ASA* registers
+void ak8963GetAdjustment(int8_t *x, int8_t *y, int8_t *z);
+void ak8963SetAdjustment(int8_t x, int8_t y, int8_t z);
+uint8_t ak8963GetAdjustmentX();
+void ak8963SetAdjustmentX(uint8_t x);
+uint8_t ak8963GetAdjustmentY();
+void ak8963SetAdjustmentY(uint8_t y);
+uint8_t ak8963GetAdjustmentZ();
+void ak8963SetAdjustmentZ(uint8_t z);
+
+#endif /* _AK8963_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/cppm.h b/crazyflie-firmware-src/src/drivers/interface/cppm.h
new file mode 100644
index 0000000000000000000000000000000000000000..0971d6b888dccbd38bc17da68058971465549d5c
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/cppm.h
@@ -0,0 +1,41 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2013 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * cppm.h - Combined PPM / PPM-Sum driver header file
+ */
+
+#include <stdint.h>
+
+void cppmInit(void);
+
+bool cppmIsAvailible(void);
+
+void cppmClearQueue(void);
+
+int cppmGetTimestamp(uint16_t *timestamp);
+
+float cppmConvert2Float(uint16_t timestamp, float min, float max);
+
+uint16_t cppmConvert2uint16(uint16_t timestamp);
+
diff --git a/crazyflie-firmware-src/src/drivers/interface/diskio.h b/crazyflie-firmware-src/src/drivers/interface/diskio.h
new file mode 100644
index 0000000000000000000000000000000000000000..0785b082482aa315eeede38cde4e083526fb69ed
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/diskio.h
@@ -0,0 +1,100 @@
+/*-----------------------------------------------------------------------/
+/  Low level disk interface modlue include file   (C)ChaN, 2013          /
+/-----------------------------------------------------------------------*/
+
+#ifndef _DISKIO_DEFINED
+#define _DISKIO_DEFINED
+
+#include <stdint.h>
+#include "integer.h"
+
+/* Status of Disk Functions */
+typedef BYTE DSTATUS;
+
+/* Results of Disk Functions */
+typedef enum {
+	RES_OK = 0,		/* 0: Successful */
+	RES_ERROR,		/* 1: R/W Error */
+	RES_WRPRT,		/* 2: Write Protected */
+	RES_NOTRDY,		/* 3: Not Ready */
+	RES_PARERR		/* 4: Invalid Parameter */
+} DRESULT;
+
+//#define FATFS_DEBUG_SEND_USART(x)	TM_USART_Puts(USART6, x); TM_USART_Puts(USART6, "\n");
+#define FATFS_DEBUG_SEND_USART(x)
+
+/*---------------------------------------*/
+/* Prototypes for disk control functions */
+
+/* FATFS related */
+DSTATUS disk_initialize(BYTE pdrv);
+DSTATUS disk_status(BYTE pdrv);
+DRESULT disk_read(BYTE pdrv, BYTE* buff, DWORD sector, UINT count);
+DRESULT disk_write(BYTE pdrv, const BYTE* buff, DWORD sector, UINT count);
+DRESULT disk_ioctl(BYTE pdrv, BYTE cmd, void* buff);
+
+/* Driver related functions */
+typedef struct {
+	DSTATUS (*disk_initialize)(void *);
+	DSTATUS (*disk_status)(void *);
+	DRESULT (*disk_ioctl)(BYTE, void *, void *);
+	DRESULT (*disk_write)(const BYTE *, DWORD, UINT, void *);
+	DRESULT (*disk_read)(BYTE *, DWORD, UINT, void *);
+	void * usrOps;
+} DISKIO_LowLevelDriver_t;
+
+/* Disk Status Bits (DSTATUS) */
+#define STA_NOINIT		0x01	/* Drive not initialized */
+#define STA_NODISK		0x02	/* No medium in the drive */
+#define STA_PROTECT		0x04	/* Write protected */
+
+/* Command code for disk_ioctrl function */
+/* Generic command (used by FatFs) */
+#define CTRL_SYNC			0	/* Flush disk cache (for write functions) */
+#define GET_SECTOR_COUNT	1	/* Get media size (for only f_mkfs()) */
+#define GET_SECTOR_SIZE		2	/* Get sector size (for multiple sector size (_MAX_SS >= 1024)) */
+#define GET_BLOCK_SIZE		3	/* Get erase block size (for only f_mkfs()) */
+#define CTRL_ERASE_SECTOR	4	/* Force erased a block of sectors (for only _USE_ERASE) */
+
+/* Generic command (not used by FatFs) */
+#define CTRL_POWER			5	/* Get/Set power status */
+#define CTRL_LOCK			6	/* Lock/Unlock media removal */
+#define CTRL_EJECT			7	/* Eject media */
+#define CTRL_FORMAT			8	/* Create physical format on the media */
+
+/* MMC/SDC specific ioctl command */
+#define MMC_GET_TYPE		10	/* Get card type */
+#define MMC_GET_CSD			11	/* Get CSD */
+#define MMC_GET_CID			12	/* Get CID */
+#define MMC_GET_OCR			13	/* Get OCR */
+#define MMC_GET_SDSTAT		14	/* Get SD status */
+
+/* ATA/CF specific ioctl command */
+#define ATA_GET_REV			20	/* Get F/W revision */
+#define ATA_GET_MODEL		21	/* Get model name */
+#define ATA_GET_SN			22	/* Get serial number */
+
+/* MMC card type flags (MMC_GET_TYPE) */
+#define CT_MMC		0x01		/* MMC ver 3 */
+#define CT_SD1		0x02		/* SD ver 1 */
+#define CT_SD2		0x04		/* SD ver 2 */
+#define CT_SDC		(CT_SD1|CT_SD2)	/* SD */
+#define CT_BLOCK	0x08		/* Block addressing */
+
+/**
+ * @brief  Adds new driver for DISKIO fatfs structure
+ * @param  *Driver: Pointer to @ref DISKIO_LowLevelDriver_t with filled structure
+ * @param  DriverName: User can use 2 custom drivers. This parameter can be a value of @ref Driver_t enumeration
+ * @retval None
+ */
+void FATFS_AddDriver(DISKIO_LowLevelDriver_t* Driver, uint8_t driverVolume);
+
+/* Drivers function declarations */
+DSTATUS SD_disk_initialize(void *);
+DSTATUS SD_disk_status(void *);
+DRESULT SD_disk_ioctl(BYTE cmd, void *buff, void *);
+DRESULT SD_disk_read(BYTE *buff, DWORD sector, UINT count, void *);
+DRESULT SD_disk_write(const BYTE *buff, DWORD sector, UINT count, void *);
+void SD_disk_timerproc (void*);
+
+#endif
diff --git a/crazyflie-firmware-src/src/drivers/interface/eeprom.h b/crazyflie-firmware-src/src/drivers/interface/eeprom.h
new file mode 100644
index 0000000000000000000000000000000000000000..7e58fa847a46341101f26f45fc34204dbb93ab35
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/eeprom.h
@@ -0,0 +1,83 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file eeprom.h
+ * Driver for the 24AA64F eeprom.
+ *
+ */
+#ifndef EERROM_H
+#define EERROM_H
+
+#include <stdbool.h>
+#include "i2cdev.h"
+
+#define EEPROM_I2C_ADDR     0x50
+#define EEPROM_SIZE         0x1FFF
+
+/**
+ * Initialize the i2c eeprom module
+ * @param i2cPort  I2C port ( a CPAL_InitTypeDef) the eeprom is connected to.
+ *
+ * @return True on success, else false.
+ */
+bool eepromInit(I2C_Dev *i2cPort);
+
+/**
+ * Test that the eeprom is there
+ *
+ * @return True on success, else false.
+ */
+bool eepromTest(void);
+
+/**
+ * Test that the eeprom is there
+ *
+ * @return True on success, else false.
+ */
+bool eepromTestConnection(void);
+
+/**
+ * Read data from the eeprom into a supplied buffer
+ * @param buffer  The buffer to write the data in
+ * @param readAddr  The start address to read from
+ * @param len  Number of bytes to read
+ *
+ * @return True on success, else false.
+ */
+bool eepromReadBuffer(uint8_t* buffer, uint16_t readAddr, uint16_t len);
+
+/**
+ * Write data to the eeprom from a supplied buffer.
+ * Currently very slow as id does single byte write.
+ * @param buffer  The buffer to read the data from
+ * @param writeAddr  The start address to write to
+ * @param len  Number of bytes to write
+ *
+ * @return True on success, else false.
+ */
+bool eepromWriteBuffer(uint8_t* buffer, uint16_t writeAddr, uint16_t len);
+
+// TODO
+bool eepromWritePage(uint8_t* buffer, uint16_t writeAddr);
+
+#endif // EERROM_H
diff --git a/crazyflie-firmware-src/src/drivers/interface/exti.h b/crazyflie-firmware-src/src/drivers/interface/exti.h
new file mode 100644
index 0000000000000000000000000000000000000000..420b4e27a52c54050b5435fe3cbbc6c8c951d15a
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/exti.h
@@ -0,0 +1,52 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * exti.h - Unified implementation of the exti interrupts
+ */
+
+#ifndef __EXTI_H__
+#define __EXTI_H__
+#include <stdbool.h>
+
+void extiInit();
+bool extiTest();
+
+void EXTI0_Callback(void);
+void EXTI1_Callback(void);
+void EXTI2_Callback(void);
+void EXTI3_Callback(void);
+void EXTI4_Callback(void);
+void EXTI5_Callback(void);
+void EXTI6_Callback(void);
+void EXTI7_Callback(void);
+void EXTI8_Callback(void);
+void EXTI9_Callback(void);
+void EXTI10_Callback(void);
+void EXTI11_Callback(void);
+void EXTI12_Callback(void);
+void EXTI13_Callback(void);
+void EXTI14_Callback(void);
+void EXTI15_Callback(void);
+
+#endif /* __EXTI_H__ */
+
diff --git a/crazyflie-firmware-src/src/drivers/interface/fatfs_sd.h b/crazyflie-firmware-src/src/drivers/interface/fatfs_sd.h
new file mode 100644
index 0000000000000000000000000000000000000000..9bedb163a1b283f343059ad1da705655eb376d74
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/fatfs_sd.h
@@ -0,0 +1,32 @@
+/*-----------------------------------------------------------------------/
+/  Low level disk interface modlue include file   (C)ChaN, 2013          /
+/-----------------------------------------------------------------------*/
+
+#ifndef __FATFS_SD_H__
+#define __FATFS_SD_H__
+
+#define SD_DISK_TIMER_PERIOD_MS 1
+
+#include "diskio.h"
+#include "integer.h"
+
+typedef struct {
+  void (*initSpi) (void);
+  void (*setSlowSpiMode) (void);
+  void (*setFastSpiMode) (void);
+  BYTE (*xchgSpi) (BYTE dat);
+  void (*rcvrSpiMulti) (BYTE *buff, UINT btr);
+  void (*xmitSpiMulti) (const BYTE *buff, UINT btx);
+  void (*csHigh) (void);
+  void (*csLow) (void);
+
+  volatile DSTATUS stat;
+  BYTE cardType;
+
+  // 1kHz decrement timers stopped at zero (disk_timerproc())
+  volatile UINT timer1;
+  volatile UINT timer2;
+} sdSpiContext_t;
+
+#endif // __FATFS_SD_H__
+
diff --git a/crazyflie-firmware-src/src/drivers/interface/hmc5883l.h b/crazyflie-firmware-src/src/drivers/interface/hmc5883l.h
new file mode 100644
index 0000000000000000000000000000000000000000..04620930b19dd067e39df003a2bccd882536d1af
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/hmc5883l.h
@@ -0,0 +1,149 @@
+// I2Cdev library collection - HMC5883L I2C device class header file
+// Based on Honeywell HMC5883L datasheet, 10/2010 (Form #900405 Rev B)
+// 6/12/2012 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2011 Jeff Rowberg
+Adapted to Crazyflie FW by Bitcraze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef HMC5883L_H_
+#define HMC5883L_H_
+#include <stdbool.h>
+#include "i2cdev.h"
+
+#define HMC5883L_ADDRESS            0x1E // this device only has one address
+#define HMC5883L_DEFAULT_ADDRESS    0x1E
+
+#define HMC5883L_RA_CONFIG_A        0x00
+#define HMC5883L_RA_CONFIG_B        0x01
+#define HMC5883L_RA_MODE            0x02
+#define HMC5883L_RA_DATAX_H         0x03
+#define HMC5883L_RA_DATAX_L         0x04
+#define HMC5883L_RA_DATAZ_H         0x05
+#define HMC5883L_RA_DATAZ_L         0x06
+#define HMC5883L_RA_DATAY_H         0x07
+#define HMC5883L_RA_DATAY_L         0x08
+#define HMC5883L_RA_STATUS          0x09
+#define HMC5883L_RA_ID_A            0x0A
+#define HMC5883L_RA_ID_B            0x0B
+#define HMC5883L_RA_ID_C            0x0C
+
+#define HMC5883L_CRA_AVERAGE_BIT    6
+#define HMC5883L_CRA_AVERAGE_LENGTH 2
+#define HMC5883L_CRA_RATE_BIT       4
+#define HMC5883L_CRA_RATE_LENGTH    3
+#define HMC5883L_CRA_BIAS_BIT       1
+#define HMC5883L_CRA_BIAS_LENGTH    2
+
+#define HMC5883L_AVERAGING_1        0x00
+#define HMC5883L_AVERAGING_2        0x01
+#define HMC5883L_AVERAGING_4        0x02
+#define HMC5883L_AVERAGING_8        0x03
+
+#define HMC5883L_RATE_0P75          0x00
+#define HMC5883L_RATE_1P5           0x01
+#define HMC5883L_RATE_3             0x02
+#define HMC5883L_RATE_7P5           0x03
+#define HMC5883L_RATE_15            0x04
+#define HMC5883L_RATE_30            0x05
+#define HMC5883L_RATE_75            0x06
+
+#define HMC5883L_BIAS_NORMAL        0x00
+#define HMC5883L_BIAS_POSITIVE      0x01
+#define HMC5883L_BIAS_NEGATIVE      0x02
+
+#define HMC5883L_CRB_GAIN_BIT       7
+#define HMC5883L_CRB_GAIN_LENGTH    3
+
+#define HMC5883L_GAIN_1370          0x00
+#define HMC5883L_GAIN_1090          0x01
+#define HMC5883L_GAIN_820           0x02
+#define HMC5883L_GAIN_660           0x03
+#define HMC5883L_GAIN_440           0x04
+#define HMC5883L_GAIN_390           0x05
+#define HMC5883L_GAIN_330           0x06
+#define HMC5883L_GAIN_220           0x07
+
+#define HMC5883L_MODEREG_BIT        1
+#define HMC5883L_MODEREG_LENGTH     2
+
+#define HMC5883L_MODE_CONTINUOUS    0x00
+#define HMC5883L_MODE_SINGLE        0x01
+#define HMC5883L_MODE_IDLE          0x02
+
+#define HMC5883L_STATUS_LOCK_BIT    1
+#define HMC5883L_STATUS_READY_BIT   0
+
+#define HMC5883L_ST_GAIN            HMC5883L_GAIN_440  // Gain value during self-test
+#define HMC5883L_ST_GAIN_NBR        440
+#define HMC5883L_ST_ERROR           0.2                // Max error
+#define HMC5883L_ST_DELAY_MS        250                // delay in millisec during self test */
+#define HMC5883L_ST_X_NORM          (int32_t)(1.16 * HMC5883L_ST_GAIN_NBR)
+#define HMC5883L_ST_X_MIN           (int32_t)(HMC5883L_ST_X_NORM - (HMC5883L_ST_X_NORM * HMC5883L_ST_ERROR))
+#define HMC5883L_ST_X_MAX           (int32_t)(HMC5883L_ST_X_NORM + (HMC5883L_ST_X_NORM * HMC5883L_ST_ERROR))
+#define HMC5883L_ST_Y_NORM          (int32_t)(1.16 * HMC5883L_ST_GAIN_NBR)
+#define HMC5883L_ST_Y_MIN           (int32_t)(HMC5883L_ST_Y_NORM - (HMC5883L_ST_Y_NORM * HMC5883L_ST_ERROR))
+#define HMC5883L_ST_Y_MAX           (int32_t)(HMC5883L_ST_Y_NORM + (HMC5883L_ST_Y_NORM * HMC5883L_ST_ERROR))
+#define HMC5883L_ST_Z_NORM          (int32_t)(1.08 * HMC5883L_ST_GAIN_NBR)
+#define HMC5883L_ST_Z_MIN           (int32_t)(HMC5883L_ST_Z_NORM - (HMC5883L_ST_Z_NORM * HMC5883L_ST_ERROR))
+#define HMC5883L_ST_Z_MAX           (int32_t)(HMC5883L_ST_Z_NORM + (HMC5883L_ST_Z_NORM * HMC5883L_ST_ERROR))
+
+void hmc5883lInit(I2C_TypeDef *i2cPort);
+bool hmc5883lTestConnection();
+bool hmc5883lSelfTest();
+bool hmc5883lEvaluateSelfTest(int16_t min, int16_t max, int16_t value, char* string);
+
+// CONFIG_A register
+uint8_t hmc5883lGetSampleAveraging();
+void hmc5883lSetSampleAveraging(uint8_t averaging);
+uint8_t hmc5883lGetDataRate();
+void hmc5883lSetDataRate(uint8_t rate);
+uint8_t hmc5883lGetMeasurementBias();
+void hmc5883lSetMeasurementBias(uint8_t bias);
+
+// CONFIG_B register
+uint8_t hmc5883lGetGain();
+void hmc5883lSetGain(uint8_t gain);
+
+// MODE register
+uint8_t hmc5883lGetMode();
+void hmc5883lSetMode(uint8_t mode);
+
+// DATA* registers
+void hmc5883lGetHeading(int16_t *x, int16_t *y, int16_t *z);
+int16_t hmc5883lGetHeadingX();
+int16_t hmc5883lGetHeadingY();
+int16_t hmc5883lGetHeadingZ();
+
+// STATUS register
+bool hmc5883lGetLockStatus();
+bool hmc5883lGetReadyStatus();
+
+// ID_* registers
+uint8_t hmc5883lGetIDA();
+uint8_t hmc5883lGetIDB();
+uint8_t hmc5883lGetIDC();
+
+#endif /* HMC5883L_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/i2c_drv.h b/crazyflie-firmware-src/src/drivers/interface/i2c_drv.h
new file mode 100644
index 0000000000000000000000000000000000000000..60a838aaa1588aa5d6b5098c04c9e61f4015b8d9
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/i2c_drv.h
@@ -0,0 +1,134 @@
+#ifndef I2C_H
+#define I2C_H
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+#include "queue.h"
+/* ST includes */
+#include "stm32fxxx.h"
+
+#define I2C_NO_INTERNAL_ADDRESS   0xFFFF
+
+typedef enum
+{
+  i2cAck,
+  i2cNack
+} I2cStatus;
+
+typedef enum
+{
+  i2cWrite,
+  i2cRead
+} I2cDirection;
+
+/**
+ * Structure used to capture the I2C message details.  The structure is then
+ * queued for processing by the I2C ISR.
+ */
+typedef struct _I2cMessage
+{
+	uint32_t         messageLength;		  //< How many bytes of data to send or received.
+	uint8_t          slaveAddress;		  //< The slave address of the device on the I2C bus.
+  uint8_t          nbrOfRetries;      //< The slave address of the device on the I2C bus.
+	I2cDirection     direction;         //< Direction of message
+  I2cStatus        status;            //< i2c status
+  xQueueHandle     clientQueue;       //< Queue to send received messages to.
+  bool             isInternal16bit;   //< Is internal address 16 bit. If false 8 bit.
+  uint16_t         internalAddress;   //< Internal address of device.
+  uint8_t          *buffer;           //< Pointer to the buffer from where data will be read for transmission, or into which received data will be placed.
+} I2cMessage;
+
+typedef struct
+{
+  I2C_TypeDef*        i2cPort;
+  uint32_t            i2cPerif;
+  uint32_t            i2cEVIRQn;
+  uint32_t            i2cERIRQn;
+  uint32_t            i2cClockSpeed;
+  uint32_t            gpioSCLPerif;
+  GPIO_TypeDef*       gpioSCLPort;
+  uint32_t            gpioSCLPin;
+  uint32_t            gpioSCLPinSource;
+  uint32_t            gpioSDAPerif;
+  GPIO_TypeDef*       gpioSDAPort;
+  uint32_t            gpioSDAPin;
+  uint32_t            gpioSDAPinSource;
+  uint32_t            gpioAF;
+  uint32_t            dmaPerif;
+  uint32_t            dmaChannel;
+  DMA_Stream_TypeDef* dmaRxStream;
+  uint32_t            dmaRxIRQ;
+  uint32_t            dmaRxTCFlag;
+  uint32_t            dmaRxTEFlag;
+
+} I2cDef;
+
+typedef struct
+{
+  const I2cDef *def;                    //< Definition of the i2c
+  I2cMessage txMessage;                 //< The I2C send message
+  uint32_t messageIndex;                //< Index of bytes sent/received
+  uint32_t nbrOfretries;                //< Retries done
+  SemaphoreHandle_t isBusFreeSemaphore; //< Semaphore to block during transaction.
+  SemaphoreHandle_t isBusFreeMutex;     //< Mutex to protect buss
+  DMA_InitTypeDef DMAStruct;            //< DMA configuration structure used during transfer setup.
+} I2cDrv;
+
+// Definitions of i2c busses found in c file.
+extern I2cDrv deckBus;
+extern I2cDrv sensorsBus;
+
+/**
+ * Initialize i2c peripheral as defined by static I2cDef structs.
+ */
+void i2cdrvInit(I2cDrv* i2c);
+
+/**
+ * Send or receive a message over the I2C bus.
+ *
+ * The message is synchrony by semapthore and uses interrupts to transfer the message.
+ *
+ * @param i2c      i2c bus to use.
+ * @param message	 An I2cMessage struct containing all the i2c message
+ *                 Information. Message status will be altered if nack.
+ * @return         true if successful, false otherwise.
+ */
+bool i2cdrvMessageTransfer(I2cDrv* i2c, I2cMessage* message);
+
+
+/**
+ * Create a message to transfer
+ *
+ * @param message       pointer to message struct that will be filled in.
+ * @param slaveAddress  i2c slave address
+ * @param direction     i2cWrite or i2cRead
+ * @param length        Length of message
+ * @param buffer        pointer to buffer of send/receive data
+ */
+void i2cdrvCreateMessage(I2cMessage *message,
+                      uint8_t  slaveAddress,
+                      I2cDirection  direction,
+                      uint32_t length,
+                      uint8_t  *buffer);
+
+/**
+ * Create a message to transfer with internal "reg" address. Will first do a write
+ * of one or two bytes depending of IsInternal16 and then write/read the data.
+ *
+ * @param message       pointer to message struct that will be filled in.
+ * @param slaveAddress  i2c slave address
+ * @param IsInternal16  It true 16bit reg address else 8bit.
+ * @param direction     i2cWrite or i2cRead
+ * @param length        Length of message
+ * @param buffer        pointer to buffer of send/receive data
+ */
+void i2cdrvCreateMessageIntAddr(I2cMessage *message,
+                             uint8_t  slaveAddress,
+                             bool IsInternal16,
+                             uint16_t intAddress,
+                             I2cDirection  direction,
+                             uint32_t length,
+                             uint8_t  *buffer);
+
+#endif
+
diff --git a/crazyflie-firmware-src/src/drivers/interface/i2cdev.h b/crazyflie-firmware-src/src/drivers/interface/i2cdev.h
new file mode 100644
index 0000000000000000000000000000000000000000..0df9580d71188e70edf98d7981065acbce950a48
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/i2cdev.h
@@ -0,0 +1,196 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * i2cdev.h - Functions to write to I2C devices
+ */
+
+#ifndef __I2CDEV_H__
+#define __I2CDEV_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#ifdef PLATFORM_CF2
+#include "i2c_drv.h"
+#endif
+
+#ifdef PLATFORM_CF1
+// Delay is approx 0.2us per loop @64Mhz
+#define I2CDEV_LOOPS_PER_US  5
+#define I2CDEV_LOOPS_PER_MS  (1000 * I2CDEV_LOOPS_PER_US)
+#endif
+
+#define I2CDEV_I2C1_PIN_SDA GPIO_Pin_7
+#define I2CDEV_I2C1_PIN_SCL GPIO_Pin_6
+
+#define I2CDEV_NO_MEM_ADDR  0xFF
+
+
+#ifdef PLATFORM_CF1
+typedef I2C_TypeDef      I2C_Dev;
+#else
+typedef I2cDrv    I2C_Dev;
+#define I2C1_DEV  &deckBus
+#define I2C3_DEV  &sensorsBus
+#endif
+
+
+/**
+ * Read bytes from an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to read from
+ * @param devAddress  The device address to read from
+ * @param memAddress  The internal address to read from, I2CDEV_NO_MEM_ADDR if none.
+ * @param len  Number of bytes to read.
+ * @param data  Pointer to a buffer to read the data to.
+ *
+ * @return TRUE if read was successful, otherwise FALSE.
+ */
+bool i2cdevRead(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+               uint16_t len, uint8_t *data);
+
+/**
+ * Read bytes from an I2C peripheral with a 16bit internal reg/mem address
+ * @param I2Cx  Pointer to I2C peripheral to read from
+ * @param devAddress  The device address to read from
+ * @param memAddress  The internal address to read from, I2CDEV_NO_MEM_ADDR if none.
+ * @param len  Number of bytes to read.
+ * @param data  Pointer to a buffer to read the data to.
+ *
+ * @return TRUE if read was successful, otherwise FALSE.
+ */
+bool i2cdevRead16(I2C_Dev *dev, uint8_t devAddress, uint16_t memAddress,
+               uint16_t len, uint8_t *data);
+
+/**
+ * I2C device init function.
+ * @param I2Cx  Pointer to I2C peripheral to initialize.
+ *
+ * @return TRUE if initialization went OK otherwise FALSE.
+ */
+int i2cdevInit(I2C_Dev *dev);
+
+/**
+ * Read a byte from an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to read from
+ * @param devAddress  The device address to read from
+ * @param memAddress  The internal address to read from, I2CDEV_NO_MEM_ADDR if none.
+ * @param data  Pointer to a buffer to read the data to.
+ *
+ * @return TRUE if read was successful, otherwise FALSE.
+ */
+bool i2cdevReadByte(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t *data);
+
+/**
+ * Read a bit from an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to read from
+ * @param devAddress  The device address to read from
+ * @param memAddress  The internal address to read from, I2CDEV_NO_MEM_ADDR if none.
+ * @param bitNum  The bit number 0 - 7 to read.
+ * @param data  Pointer to a buffer to read the data to.
+ *
+ * @return TRUE if read was successful, otherwise FALSE.
+ */
+bool i2cdevReadBit(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                     uint8_t bitNum, uint8_t *data);
+/**
+ * Read up to 8 bits from an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to read from
+ * @param devAddress  The device address to read from
+ * @param memAddress  The internal address to read from, I2CDEV_NO_MEM_ADDR if none.
+ * @param bitStart The bit to start from, 0 - 7.
+ * @param length  The number of bits to read, 1 - 8.
+ * @param data  Pointer to a buffer to read the data to.
+ *
+ * @return TRUE if read was successful, otherwise FALSE.
+ */
+bool i2cdevReadBits(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t bitStart, uint8_t length, uint8_t *data);
+
+/**
+ * Write bytes to an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to write to
+ * @param devAddress  The device address to write to
+ * @param memAddress  The internal address to write to, I2CDEV_NO_MEM_ADDR if none.
+ * @param len  Number of bytes to read.
+ * @param data  Pointer to a buffer to read the data from that will be written.
+ *
+ * @return TRUE if write was successful, otherwise FALSE.
+ */
+bool i2cdevWrite(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                 uint16_t len, uint8_t *data);
+
+/**
+ * Write bytes to an I2C peripheral with 16bit internal reg/mem address.
+ * @param I2Cx  Pointer to I2C peripheral to write to
+ * @param devAddress  The device address to write to
+ * @param memAddress  The internal address to write to, I2CDEV_NO_MEM_ADDR if none.
+ * @param len  Number of bytes to read.
+ * @param data  Pointer to a buffer to read the data from that will be written.
+ *
+ * @return TRUE if write was successful, otherwise FALSE.
+ */
+bool i2cdevWrite16(I2C_Dev *dev, uint8_t devAddress, uint16_t memAddress,
+                   uint16_t len, uint8_t *data);
+
+/**
+ * Write a byte to an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to write to
+ * @param devAddress  The device address to write to
+ * @param memAddress  The internal address to write from, I2CDEV_NO_MEM_ADDR if none.
+ * @param data  The byte to write.
+ *
+ * @return TRUE if write was successful, otherwise FALSE.
+ */
+bool i2cdevWriteByte(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                     uint8_t data);
+
+/**
+ * Write a bit to an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to write to
+ * @param devAddress  The device address to write to
+ * @param memAddress  The internal address to write to, I2CDEV_NO_MEM_ADDR if none.
+ * @param bitNum  The bit number, 0 - 7, to write.
+ * @param data  The bit to write.
+ *
+ * @return TRUE if read was successful, otherwise FALSE.
+ */
+bool i2cdevWriteBit(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t bitNum, uint8_t data);
+
+/**
+ * Write up to 8 bits to an I2C peripheral
+ * @param I2Cx  Pointer to I2C peripheral to write to
+ * @param devAddress  The device address to write to
+ * @param memAddress  The internal address to write to, I2CDEV_NO_MEM_ADDR if none.
+ * @param bitStart The bit to start from, 0 - 7.
+ * @param length  The number of bits to write, 1 - 8.
+ * @param data  The byte containing the bits to write.
+ *
+ * @return TRUE if read was successful, otherwise FALSE.
+ */
+bool i2cdevWriteBits(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                     uint8_t bitStart, uint8_t length, uint8_t data);
+
+#endif //__I2CDEV_H__
diff --git a/crazyflie-firmware-src/src/drivers/interface/i2croutines.h b/crazyflie-firmware-src/src/drivers/interface/i2croutines.h
new file mode 100644
index 0000000000000000000000000000000000000000..748083c2bba962b2e443e36ec4281140a589498f
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/i2croutines.h
@@ -0,0 +1,139 @@
+/**
+  ******************************************************************************
+  * @file OptimizedI2Cexamples/inc/I2CRoutines.h
+  * @author  MCD Application Team
+  * @version  V4.0.0
+  * @date  06/18/2010
+  * @brief  Header for I2CRoutines.c
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>
+  */
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __I2CROUTINES_H
+#define __I2CROUTINES_H
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* I2C SPE mask */
+#define CR1_PE_Set              ((uint16_t)0x0001)
+#define CR1_PE_Reset            ((uint16_t)0xFFFE)
+
+/* I2C START mask */
+#define CR1_START_Set           ((uint16_t)0x0100)
+#define CR1_START_Reset         ((uint16_t)0xFEFF)
+
+#define CR1_POS_Set           ((uint16_t)0x0800)
+#define CR1_POS_Reset         ((uint16_t)0xF7FF)
+
+/* I2C STOP mask */
+#define CR1_STOP_Set            ((uint16_t)0x0200)
+#define CR1_STOP_Reset          ((uint16_t)0xFDFF)
+
+/* I2C ACK mask */
+#define CR1_ACK_Set             ((uint16_t)0x0400)
+#define CR1_ACK_Reset           ((uint16_t)0xFBFF)
+
+/* I2C ENARP mask */
+#define CR1_ENARP_Set           ((uint16_t)0x0010)
+#define CR1_ENARP_Reset         ((uint16_t)0xFFEF)
+
+/* I2C NOSTRETCH mask */
+#define CR1_NOSTRETCH_Set       ((uint16_t)0x0080)
+#define CR1_NOSTRETCH_Reset     ((uint16_t)0xFF7F)
+
+/* I2C registers Masks */
+#define CR1_CLEAR_Mask          ((uint16_t)0xFBF5)
+
+/* I2C DMAEN mask */
+#define CR2_DMAEN_Set           ((uint16_t)0x0800)
+#define CR2_DMAEN_Reset         ((uint16_t)0xF7FF)
+
+/* I2C LAST mask */
+#define CR2_LAST_Set            ((uint16_t)0x1000)
+#define CR2_LAST_Reset          ((uint16_t)0xEFFF)
+
+/* I2C FREQ mask */
+#define CR2_FREQ_Reset          ((uint16_t)0xFFC0)
+
+/* I2C ADD0 mask */
+#define OAR1_ADD0_Set           ((uint16_t)0x0001)
+#define OAR1_ADD0_Reset         ((uint16_t)0xFFFE)
+
+/* I2C ENDUAL mask */
+#define OAR2_ENDUAL_Set         ((uint16_t)0x0001)
+#define OAR2_ENDUAL_Reset       ((uint16_t)0xFFFE)
+
+/* I2C ADD2 mask */
+#define OAR2_ADD2_Reset         ((uint16_t)0xFF01)
+
+/* I2C F/S mask */
+#define CCR_FS_Set              ((uint16_t)0x8000)
+
+/* I2C CCR mask */
+#define CCR_CCR_Set             ((uint16_t)0x0FFF)
+
+/* I2C FLAG mask */
+#define FLAG_Mask               ((uint32_t)0x00FFFFFF)
+
+/* I2C Interrupt Enable mask */
+#define ITEN_Mask               ((uint32_t)0x07000000)
+
+
+#define I2C_IT_BUF                      ((uint16_t)0x0400)
+#define I2C_IT_EVT                      ((uint16_t)0x0200)
+#define I2C_IT_ERR                      ((uint16_t)0x0100)
+
+
+#define  ClockSpeed            400000
+
+#define I2C_DIRECTION_TX 0
+#define I2C_DIRECTION_RX 1
+
+#define OwnAddress1 0x28
+#define OwnAddress2 0x30
+
+
+#define I2C1_DMA_CHANNEL_TX           DMA1_Channel6
+#define I2C1_DMA_CHANNEL_RX           DMA1_Channel7
+
+#define I2C2_DMA_CHANNEL_TX           DMA1_Channel4
+#define I2C2_DMA_CHANNEL_RX           DMA1_Channel5
+
+#define I2C1_DR_Address              0x40005410
+#define I2C2_DR_Address              0x40005810
+
+typedef enum
+{
+  INTERRUPT,
+  DMA
+} I2C_ProgrammingModel;
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+ErrorStatus I2C_Master_BufferRead(I2C_TypeDef* I2Cx, uint8_t* pBuffer,  uint32_t NumByteToRead,
+                             I2C_ProgrammingModel Mode, uint8_t SlaveAddress, uint32_t timeoutMs);
+ErrorStatus I2C_Master_BufferWrite(I2C_TypeDef* I2Cx, uint8_t* pBuffer,  uint32_t NumByteToWrite,
+                              I2C_ProgrammingModel Mode, uint8_t SlaveAddress, uint32_t timeoutMs);
+void I2C_Slave_BufferReadWrite(I2C_TypeDef* I2Cx, I2C_ProgrammingModel Mode);
+void I2C_LowLevel_Init(I2C_TypeDef* I2Cx);
+void I2C_DMAConfig(I2C_TypeDef* I2Cx, uint8_t* pBuffer, uint32_t BufferSize, uint32_t Direction);
+
+void i2cInterruptHandlerI2c1(void);
+void i2cInterruptHandlerI2c2(void);
+void i2cErrorInterruptHandler(I2C_TypeDef* I2Cx);
+
+#endif
+
+/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/drivers/interface/led.h b/crazyflie-firmware-src/src/drivers/interface/led.h
new file mode 100644
index 0000000000000000000000000000000000000000..61c6c1b52ca9c8d8ac0bf0a7913fe49c8e385f4c
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/led.h
@@ -0,0 +1,103 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * led.h - LED functions header file
+ */
+#ifndef __LED_H__
+#define __LED_H__
+
+#include <stdbool.h>
+
+//Led polarity configuration constant
+#define LED_POL_POS 0
+#define LED_POL_NEG 1
+
+#ifdef PLATFORM_CF1
+//Hardware configuration
+#define LED_GPIO_PERIF   RCC_APB2Periph_GPIOB
+#define LED_GPIO_PORT    GPIOB
+#define LED_GPIO_GREEN   GPIO_Pin_5
+#define LED_POL_GREEN    LED_POL_NEG
+#define LED_GPIO_RED     GPIO_Pin_4
+#define LED_POL_RED      LED_POL_NEG
+
+#define LED_NUM 2
+
+typedef enum {LED_RED=0, LED_GREEN} led_t;
+
+#define LINK_LED         LED_GREEN
+#define CHG_LED          LED_GREEN
+#define LOWBAT_LED       LED_RED
+#define LINK_DOWN_LED    LED_GREEN
+#define SYS_LED          LED_RED
+#define ERR_LED1         LED_RED
+#define ERR_LED2         LED_GREEN
+
+#elif defined(PLATFORM_CF2)
+//Hardware configuration
+#define LED_GPIO_PERIF   (RCC_AHB1Periph_GPIOC | RCC_AHB1Periph_GPIOD)
+#define LED_GPIO_PORT_BLUE  GPIOD
+#define LED_GPIO_BLUE_L  GPIO_Pin_2
+#define LED_POL_BLUE_L   LED_POL_POS
+#define LED_GPIO_PORT    GPIOC
+#define LED_GPIO_GREEN_L GPIO_Pin_1
+#define LED_POL_GREEN_L  LED_POL_NEG
+#define LED_GPIO_RED_L   GPIO_Pin_0
+#define LED_POL_RED_L    LED_POL_NEG
+#define LED_GPIO_GREEN_R GPIO_Pin_2
+#define LED_POL_GREEN_R  LED_POL_NEG
+#define LED_GPIO_RED_R   GPIO_Pin_3
+#define LED_POL_RED_R    LED_POL_NEG
+
+#define LINK_LED         LED_GREEN_L
+#define CHG_LED          LED_BLUE_L
+#define LOWBAT_LED       LED_RED_R
+#define LINK_DOWN_LED    LED_RED_L
+#define SYS_LED          LED_RED_R
+#define ERR_LED1         LED_RED_L
+#define ERR_LED2         LED_RED_R
+
+#define LED_NUM 5
+
+typedef enum {LED_BLUE_L = 0, LED_GREEN_L, LED_RED_L, LED_GREEN_R, LED_RED_R} led_t;
+#endif
+
+void ledInit();
+bool ledTest();
+
+// Clear all configured LEDs
+void ledClearAll(void);
+
+// Set all configured LEDs
+void ledSetAll(void);
+
+// Procedures to set the status of the LEDs
+void ledSet(led_t led, bool value);
+
+void ledTask(void *param);
+
+//Legacy functions
+#define ledSetRed(VALUE) ledSet(LED_RED, VALUE)
+#define ledSetGreen(VALUE) ledSet(LED_GREEN, VALUE)
+
+#endif
diff --git a/crazyflie-firmware-src/src/drivers/interface/lps25h.h b/crazyflie-firmware-src/src/drivers/interface/lps25h.h
new file mode 100644
index 0000000000000000000000000000000000000000..76e9b960bec0fb740ee4af8e6fdb99c7dd3f28ce
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/lps25h.h
@@ -0,0 +1,157 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011 Fabio Varesano <fvaresano@yahoo.it>
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file ms5611.h
+ * Driver for the ms5611 pressure sensor from measurement specialties.
+ * Datasheet at http://www.meas-spec.com/downloads/MS5611-01BA03.pdf
+ *
+ */
+#ifndef LPS25H_H
+#define LPS25H_H
+
+#include <stdbool.h>
+#include "i2cdev.h"
+
+// addresses of the device
+#define LPS25H_I2C_ADDR 0x5D // 1011101b
+
+#define LPS25H_LSB_PER_MBAR      4096UL
+#define LPS25H_LSB_PER_CELSIUS   480UL
+#define LPS25H_ADDR_AUTO_INC     (1<<7)
+
+// register addresses
+
+// register addresses
+// Note: Some of the register names in the datasheet are inconsistent
+// between Table 14 in section 6 and the register descriptions in
+// section 7. Where they differ, the names from section 7 have been
+// used here.
+
+#define LPS25H_REF_P_XL       0x08
+#define LPS25H_REF_P_L        0x09
+#define LPS25H_REF_P_H        0x0A
+
+#define LPS25H_WHO_AM_I       0x0F
+
+#define LPS25H_RES_CONF       0x10
+
+#define LPS25H_CTRL_REG1      0x20
+#define LPS25H_CTRL_REG2      0x21
+#define LPS25H_CTRL_REG3      0x22
+#define LPS25H_CTRL_REG4      0x23
+#define LPS25H_INTERRUPT_CFG  0x24
+#define LPS25H_INT_SOURCE     0x25
+#define LPS25H_STATUS_REG     0x27
+
+#define LPS25H_PRESS_OUT_XL   0x28
+#define LPS25H_PRESS_OUT_L    0x29
+#define LPS25H_PRESS_OUT_H    0x2A
+
+#define LPS25H_TEMP_OUT_L     0x2B
+#define LPS25H_TEMP_OUT_H     0x2C
+
+#define LPS25H_FIFO_CTRL      0x2E
+#define LPS25H_FIFO_STATUS    0x2F
+#define LPS25H_THS_P_L        0x30
+#define LPS25H_THS_P_H        0x31
+#define LPS25H_RPDS_L         0x39
+#define LPS25H_RPDS_H         0x3A
+
+/* CUSTOM VALUES FOR LPS25H SENSOR */
+#define LPS25H_WAI_ID             0xBD
+#define LPS25H_ODR_ADDR           0x20
+#define LPS25H_ODR_MASK           0x70
+#define LPS25H_ODR_AVL_1HZ_VAL    0x01
+#define LPS25H_ODR_AVL_7HZ_VAL    0x02
+#define LPS25H_ODR_AVL_13HZ_VAL   0x03
+#define LPS25H_ODR_AVL_25HZ_VAL   0x04
+#define LPS25H_PW_ADDR            0x20
+#define LPS25H_PW_MASK            0x80
+#define LPS25H_FS_ADDR            0x00
+#define LPS25H_FS_MASK            0x00
+#define LPS25H_FS_AVL_1260_VAL    0x00
+#define LPS25H_FS_AVL_1260_GAIN   KPASCAL_NANO_SCALE
+#define LPS25H_FS_AVL_TEMP_GAIN   CELSIUS_NANO_SCALE
+#define LPS25H_BDU_ADDR           0x20
+#define LPS25H_BDU_MASK           0x04
+#define LPS25H_DRDY_IRQ_ADDR      0x23
+#define LPS25H_DRDY_IRQ_INT1_MASK 0x01
+#define LPS25H_DRDY_IRQ_INT2_MASK 0x10
+#define LPS25H_MULTIREAD_BIT      true
+#define LPS25H_TEMP_OFFSET        (42.5f)
+#define LPS25H_OUT_XL_ADDR        0x28
+#define LPS25H_TEMP_OUT_L_ADDR    0x2B
+
+// Self test parameters. Only checks that values are sane
+#define LPS25H_ST_PRESS_MAX   (1100.0f) //mbar
+#define LPS25H_ST_PRESS_MIN   (450.0f)  //mbar
+#define LPS25H_ST_TEMP_MAX    (80.0f)   //degree celcius
+#define LPS25H_ST_TEMP_MIN    (-20.0f)  //degree celcius
+
+/**
+ * Initialize the lps25h driver
+ * @param i2cPort  I2C port ( a CPAL_InitTypeDef) the lps25h is connected to.
+ *
+ * @return True on success, else false.
+ */
+bool lps25hInit(I2C_Dev *i2cPort);
+
+/**
+ * Do a self test of the lps25h. Currently it only tests for sane values.
+ *
+ * @return True on success, else false.
+ */
+bool lps25hSelfTest(void);
+
+/**
+ * Evaluate self test results.
+ *
+ * @return True on success, else false.
+ */
+bool lps25hEvaluateSelfTest(float min, float max, float value, char* string);
+
+/**
+ * Test the lps25h I2C connection.
+ *
+ * @return True on success, else false.
+ */
+bool lps25hTestConnection(void);
+
+/**
+ * Enable the lps25h and configure it.
+ *
+ * @return True on success, else false.
+ */
+bool lps25hSetEnabled(bool enable);
+
+/**
+ * Get measurement data.
+ *
+ * @return True on success, else false.
+ */
+bool lps25hGetData(float* pressure, float* temperature, float* asl);
+
+float lps25hPressureToAltitude(float* pressure);
+
+#endif // LPS25H_H
diff --git a/crazyflie-firmware-src/src/drivers/interface/maxsonar.h b/crazyflie-firmware-src/src/drivers/interface/maxsonar.h
new file mode 100644
index 0000000000000000000000000000000000000000..4751a92b166ed9c8be77a6fcb60eaacf7fdd12d4
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/maxsonar.h
@@ -0,0 +1,72 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * maxSonar.h - API for the MaxSonar MB1040 (LV-MaxSonar-EZ04)
+ */
+
+/**
+ * This driver assumes the ADC VREF is the same as the LV-MaxSonar-EZ4 VREF. This means
+ * that the MB1040 Sensor should have its VCC pin connected to the VCC pin on the deck
+ * port (instead of using the VCOM or VUSB pins).
+ *
+ * According to the datasheet for the MB1040, the sensor draws typically 2mA, so
+ * powering it with the VCC pin (50mA max) on the deck port should be safe.
+ *
+ * See also https://forum.bitcraze.io/viewtopic.php?f=6&t=1250
+ */
+
+#ifndef __MAXSONAR_H__
+#define __MAXSONAR_H__
+
+#include <stdint.h>
+
+/**
+ * \def MAXSONAR_ENABLED
+ * Enable the MaxSonar driver (used by the proximity measurement subsystem).
+ */
+//#define MAXSONAR_ENABLED
+
+/**
+ * \def MAXSONAR_DECK_GPIO
+ * The GPIO pin to use if reading via the analog interface of a MaxSonar sensor.
+ */
+#define MAXSONAR_DECK_GPIO DECK_GPIO_TX2
+
+/**
+ * \def MAXSONAR_LOG_ENABLED
+ * Uncomment to enable log variables for this driver.
+ */
+//#define MAXSONAR_LOG_ENABLED
+
+/**
+ * List of MaxBotix sensors with different interface types can be added here.
+ *
+ * Sensors should be listed once for each interface, for instance MB1040AN (Analog), MB1040I2C (I2C), MB1040PWM (PWM) etc.
+ */
+typedef enum {
+  MAXSONAR_MB1040_AN = 0, /* The MB1040 (LV-MaxSonar-EZ4) sensor read by analog conversion (GPIO pin read by ADC). */
+} maxSonarSensor_t;
+
+uint32_t maxSonarReadDistance(maxSonarSensor_t type, uint32_t *accuracy);
+
+#endif
diff --git a/crazyflie-firmware-src/src/drivers/interface/motors.h b/crazyflie-firmware-src/src/drivers/interface/motors.h
new file mode 100644
index 0000000000000000000000000000000000000000..710eeac45c9447ea0b5865ba1c633afbd14ba9b6
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/motors.h
@@ -0,0 +1,261 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * Motors.h - Motor driver header file
+ *
+ * The motors PWM ratio is a value on 16 bits (from 0 to 0xFFFF)
+ * the functions of the driver will make the conversions to the actual PWM
+ * precision (ie. if the precision is 8bits 0xFFFF and 0xFF00 are equivalents).
+ *
+ * The precision is set in number of bits by the define MOTORS_PWM_BITS
+ * The timer prescaler is set by MOTORS_PWM_PRESCALE
+ */
+#ifndef __MOTORS_H__
+#define __MOTORS_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "config.h"
+/* ST includes */
+#include "stm32fxxx.h"
+
+/******** Defines ********/
+
+#ifdef PLATFORM_CF1
+  // The following defines gives a PWM of 9 bits at ~140KHz for a sysclock of 72MHz
+  #define TIM_CLOCK_HZ 72000000
+  #define MOTORS_PWM_BITS           9
+  #define MOTORS_PWM_PERIOD         ((1<<MOTORS_PWM_BITS) - 1)
+  #define MOTORS_PWM_PRESCALE       0
+  #define MOTORS_TIM_BEEP_CLK_FREQ  (72000000L / 5)
+  #define MOTORS_POLARITY           TIM_OCPolarity_High
+
+// Abstraction of ST lib functions
+  #define MOTORS_GPIO_MODE          GPIO_Mode_AF_PP
+  #define MOTORS_RCC_GPIO_CMD       RCC_APB2PeriphClockCmd
+  #define MOTORS_RCC_TIM_CMD        RCC_APB1PeriphClockCmd
+  #define MOTORS_GPIO_AF_CFG(a,b,c) GPIO_PinRemapConfig(c, ENABLE)
+  #define MOTORS_TIM_DBG_CFG        DBGMCU_Config
+#else
+  // The following defines gives a PWM of 8 bits at ~328KHz for a sysclock of 168MHz
+  // CF2 PWM ripple is filtered better at 328kHz. At 168kHz the NCP702 regulator is affected.
+  #define TIM_CLOCK_HZ 84000000
+  #define MOTORS_PWM_BITS           8
+  #define MOTORS_PWM_PERIOD         ((1<<MOTORS_PWM_BITS) - 1)
+  #define MOTORS_PWM_PRESCALE       0
+  #define MOTORS_TIM_BEEP_CLK_FREQ  (84000000L / 5)
+  #define MOTORS_POLARITY           TIM_OCPolarity_High
+
+// Abstraction of ST lib functions
+  #define MOTORS_GPIO_MODE          GPIO_Mode_AF
+  #define MOTORS_RCC_GPIO_CMD       RCC_AHB1PeriphClockCmd
+  #define MOTORS_RCC_TIM_CMD        RCC_APB1PeriphClockCmd
+  #define MOTORS_TIM_DBG_CFG        DBGMCU_APB2PeriphConfig
+  #define MOTORS_GPIO_AF_CFG(a,b,c) GPIO_PinAFConfig(a,b,c)
+
+// Compensate thrust depending on battery voltage so it will produce about the same
+  // amount of thrust independent of the battery voltage. Based on thrust measurement.
+  #define ENABLE_THRUST_BAT_COMPENSATED
+#endif
+
+//#define ENABLE_ONESHOT125
+
+#ifdef ENABLE_ONESHOT125
+/**
+ * *VARNING* Make sure the brushless driver is configured correctly as on the Crazyflie with normal
+ * brushed motors connected they can turn on at full speed when it is powered on!
+ *
+ * Generates a PWM wave (50 - 400 Hz update rate with 1-2 ms high pulse) using the timer. That way we can use the same
+ * base as for the regular PWM driver. This means it will be a PWM with a period of the update rate configured to be high
+ * only in the 1-2 ms range.
+ */
+  #define BLMC_PERIOD 0.0005   // 0.5ms = 2000Hz
+  #define MOTORS_BL_PWM_PRESCALE_RAW   (uint32_t)((TIM_CLOCK_HZ/0xFFFF) * BLMC_PERIOD + 1) // +1 is to not end up above 0xFFFF in the end
+  #define MOTORS_BL_PWM_CNT_FOR_PERIOD (uint32_t)(TIM_CLOCK_HZ * BLMC_PERIOD / MOTORS_BL_PWM_PRESCALE_RAW)
+  #define MOTORS_BL_PWM_CNT_FOR_HIGH   (uint32_t)(TIM_CLOCK_HZ * 0.000125 / MOTORS_BL_PWM_PRESCALE_RAW)
+  #define MOTORS_BL_PWM_PERIOD         MOTORS_BL_PWM_CNT_FOR_PERIOD
+  #define MOTORS_BL_PWM_PRESCALE       (uint16_t)(MOTORS_BL_PWM_PRESCALE_RAW - 1)
+  #define MOTORS_BL_POLARITY           TIM_OCPolarity_Low
+#else
+/**
+ * *VARNING* Make sure the brushless driver is configured correctly as on the Crazyflie with normal
+ * brushed motors connected they can turn on at full speed when it is powered on!
+ *
+ * Generates a PWM wave (50 - 400 Hz update rate with 1-2 ms high pulse) using the timer. That way we can use the same
+ * base as for the regular PWM driver. This means it will be a PWM with a period of the update rate configured to be high
+ * only in the 1-2 ms range.
+ */
+  #define BLMC_PERIOD 0.0025   // 2.5ms = 400Hz
+  #define MOTORS_BL_PWM_PRESCALE_RAW   (uint32_t)((TIM_CLOCK_HZ/0xFFFF) * BLMC_PERIOD + 1) // +1 is to not end up above 0xFFFF in the end
+  #define MOTORS_BL_PWM_CNT_FOR_PERIOD (uint32_t)(TIM_CLOCK_HZ * BLMC_PERIOD / MOTORS_BL_PWM_PRESCALE_RAW)
+  #define MOTORS_BL_PWM_CNT_FOR_HIGH    (uint32_t)(TIM_CLOCK_HZ * 0.001 / MOTORS_BL_PWM_PRESCALE_RAW)
+  #define MOTORS_BL_PWM_PERIOD         MOTORS_BL_PWM_CNT_FOR_PERIOD
+  #define MOTORS_BL_PWM_PRESCALE       (uint16_t)(MOTORS_BL_PWM_PRESCALE_RAW - 1)
+  #define MOTORS_BL_POLARITY           TIM_OCPolarity_Low
+#endif
+
+#define NBR_OF_MOTORS 4
+// Motors IDs define
+#define MOTOR_M1  0
+#define MOTOR_M2  1
+#define MOTOR_M3  2
+#define MOTOR_M4  3
+
+// Test defines
+#define MOTORS_TEST_RATIO         (uint16_t)(0.2*(1<<16))
+#define MOTORS_TEST_ON_TIME_MS    50
+#define MOTORS_TEST_DELAY_TIME_MS 150
+
+// Sound defines
+#define C4    262
+#define DES4  277
+#define D4    294
+#define ES4   311
+#define E4    330
+#define F4    349
+#define GES4  370
+#define G4    392
+#define AS4   415
+#define A4    440
+#define B4    466
+#define H4    493
+#define C5    523
+#define DES5  554
+#define D5    587
+#define ES5   622
+#define E5    659
+#define F5    698
+#define GES5  740
+#define G5    783
+#define AS5   830
+#define A5    880
+#define B5    932
+#define H5    987
+#define C6    1046
+#define DES6  1108
+#define D6    1174
+#define ES6   1244
+#define E6    1318
+#define F6    1396
+#define GES6  1479
+#define G6    1567
+#define AS6   1661
+#define A6    1760
+#define B6    1864
+#define H6    1975
+#define C7    2093
+#define DES7  2217
+#define D7    2349
+#define ES7   2489
+#define E7    2637
+#define F7    2793
+#define GES7  2959
+#define G7    3135
+#define AS7   3322
+#define A7    3520
+#define H7    3729
+#define B7    3951
+
+// Sound duration defines
+#define EIGHTS 125
+#define QUAD 250
+#define HALF 500
+#define FULL 1000
+#define STOP 0
+
+typedef enum
+{
+  BRUSHED,
+  BRUSHLESS
+} motorsDrvType;
+
+typedef struct
+{
+  motorsDrvType drvType;
+  uint32_t      gpioPerif;
+  GPIO_TypeDef* gpioPort;
+  uint32_t      gpioPin;
+  uint32_t      gpioPinSource;
+  uint32_t      gpioOType;
+  uint32_t      gpioAF;
+  uint32_t      timPerif;
+  TIM_TypeDef*  tim;
+  uint16_t      timPolarity;
+  uint32_t      timDbgStop;
+  uint32_t      timPeriod;
+  uint16_t      timPrescaler;
+  /* Function pointers */
+#ifdef PLATFORM_CF1
+  void (*setCompare)(TIM_TypeDef* TIMx, uint16_t Compare);
+  uint16_t (*getCompare)(TIM_TypeDef* TIMx);
+#else
+  void (*setCompare)(TIM_TypeDef* TIMx, uint32_t Compare);
+  uint32_t (*getCompare)(TIM_TypeDef* TIMx);
+#endif
+  void (*ocInit)(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+  void (*preloadConfig)(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+} MotorPerifDef;
+
+/**
+ * Motor mapping configurations
+ */
+extern const MotorPerifDef* motorMapDefaultBrushed[NBR_OF_MOTORS];
+extern const MotorPerifDef* motorMapDefaltConBrushless[NBR_OF_MOTORS];
+extern const MotorPerifDef* motorMapBigQuadDeck[NBR_OF_MOTORS];
+extern const MotorPerifDef* motorMapRZRBrushless[NBR_OF_MOTORS];
+
+/*** Public interface ***/
+
+/**
+ * Initialisation. Will set all motors ratio to 0%
+ */
+void motorsInit(const MotorPerifDef** motorMapSelect);
+
+/**
+ * DeInitialisation. Reset to default
+ */
+void motorsDeInit(const MotorPerifDef** motorMapSelect);
+
+/**
+ * Test of the motor modules. The test will spin each motor very short in
+ * the sequence M1 to M4.
+ */
+bool motorsTest(void);
+
+/**
+ * Set the PWM ratio of the motor 'id'
+ */
+void motorsSetRatio(uint32_t id, uint16_t ratio);
+
+/**
+ * Get the PWM ratio of the motor 'id'. Return -1 if wrong ID.
+ */
+int motorsGetRatio(uint32_t id);
+
+/**
+ * FreeRTOS Task to test the Motors driver
+ */
+void motorsTestTask(void* params);
+
+#endif /* __MOTORS_H__ */
+
diff --git a/crazyflie-firmware-src/src/drivers/interface/mpu6050.h b/crazyflie-firmware-src/src/drivers/interface/mpu6050.h
new file mode 100644
index 0000000000000000000000000000000000000000..ad291d68f014d92bac873cc5c91b1edd564a700b
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/mpu6050.h
@@ -0,0 +1,1009 @@
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2011 Jeff Rowberg
+Adapted to Crazyflie FW by Bitcraze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6050_H_
+#define _MPU6050_H_
+
+#include "i2cdev.h"
+
+#define MPU6050_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU6050_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU6050_DEFAULT_ADDRESS     MPU6050_ADDRESS_AD0_LOW
+#define MPU6050_SELF_TEST_DELAY_MS  10
+
+//Product ID Description for MPU6050:  | High 4 bits  | Low 4 bits        |
+//                                     | Product Name | Product Revision  |
+#define MPU6050_REV_C4_ES     0x14  //        0001           0100
+#define MPU6050_REV_C5_ES     0x15  //        0001           0101
+#define MPU6050_REV_D6_ES     0x16  //        0001           0110
+#define MPU6050_REV_D7_ES     0x17  //        0001           0111
+#define MPU6050_REV_D8_ES     0x18  //        0001           1000
+#define MPU6050_REV_C4        0x54  //        0101           0100
+#define MPU6050_REV_C5        0x55  //        0101           0101
+#define MPU6050_REV_D6        0x56  //        0101           0110
+#define MPU6050_REV_D7        0x57  //        0101           0111
+#define MPU6050_REV_D8        0x58  //        0101           1000
+#define MPU6050_REV_D9        0x59  //        0101           1001
+
+#define MPU6050_RA_XG_OFFS_TC       0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_YG_OFFS_TC       0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_ZG_OFFS_TC       0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_X_FINE_GAIN      0x03 //[7:0] X_FINE_GAIN
+#define MPU6050_RA_Y_FINE_GAIN      0x04 //[7:0] Y_FINE_GAIN
+#define MPU6050_RA_Z_FINE_GAIN      0x05 //[7:0] Z_FINE_GAIN
+#define MPU6050_RA_XA_OFFS_H        0x06 //[15:0] XA_OFFS
+#define MPU6050_RA_XA_OFFS_L_TC     0x07
+#define MPU6050_RA_YA_OFFS_H        0x08 //[15:0] YA_OFFS
+#define MPU6050_RA_YA_OFFS_L_TC     0x09
+#define MPU6050_RA_ZA_OFFS_H        0x0A //[15:0] ZA_OFFS
+#define MPU6050_RA_ZA_OFFS_L_TC     0x0B
+#define MPU6050_RA_PRODUCT_ID       0x0C
+#define MPU6050_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
+#define MPU6050_RA_XG_OFFS_USRL     0x14
+#define MPU6050_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
+#define MPU6050_RA_YG_OFFS_USRL     0x16
+#define MPU6050_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
+#define MPU6050_RA_ZG_OFFS_USRL     0x18
+#define MPU6050_RA_SMPLRT_DIV       0x19
+#define MPU6050_RA_CONFIG           0x1A
+#define MPU6050_RA_GYRO_CONFIG      0x1B
+#define MPU6050_RA_ACCEL_CONFIG     0x1C
+#define MPU6050_RA_FF_THR           0x1D
+#define MPU6050_RA_FF_DUR           0x1E
+#define MPU6050_RA_MOT_THR          0x1F
+#define MPU6050_RA_MOT_DUR          0x20
+#define MPU6050_RA_ZRMOT_THR        0x21
+#define MPU6050_RA_ZRMOT_DUR        0x22
+#define MPU6050_RA_FIFO_EN          0x23
+#define MPU6050_RA_I2C_MST_CTRL     0x24
+#define MPU6050_RA_I2C_SLV0_ADDR    0x25
+#define MPU6050_RA_I2C_SLV0_REG     0x26
+#define MPU6050_RA_I2C_SLV0_CTRL    0x27
+#define MPU6050_RA_I2C_SLV1_ADDR    0x28
+#define MPU6050_RA_I2C_SLV1_REG     0x29
+#define MPU6050_RA_I2C_SLV1_CTRL    0x2A
+#define MPU6050_RA_I2C_SLV2_ADDR    0x2B
+#define MPU6050_RA_I2C_SLV2_REG     0x2C
+#define MPU6050_RA_I2C_SLV2_CTRL    0x2D
+#define MPU6050_RA_I2C_SLV3_ADDR    0x2E
+#define MPU6050_RA_I2C_SLV3_REG     0x2F
+#define MPU6050_RA_I2C_SLV3_CTRL    0x30
+#define MPU6050_RA_I2C_SLV4_ADDR    0x31
+#define MPU6050_RA_I2C_SLV4_REG     0x32
+#define MPU6050_RA_I2C_SLV4_DO      0x33
+#define MPU6050_RA_I2C_SLV4_CTRL    0x34
+#define MPU6050_RA_I2C_SLV4_DI      0x35
+#define MPU6050_RA_I2C_MST_STATUS   0x36
+#define MPU6050_RA_INT_PIN_CFG      0x37
+#define MPU6050_RA_INT_ENABLE       0x38
+#define MPU6050_RA_DMP_INT_STATUS   0x39
+#define MPU6050_RA_INT_STATUS       0x3A
+#define MPU6050_RA_ACCEL_XOUT_H     0x3B
+#define MPU6050_RA_ACCEL_XOUT_L     0x3C
+#define MPU6050_RA_ACCEL_YOUT_H     0x3D
+#define MPU6050_RA_ACCEL_YOUT_L     0x3E
+#define MPU6050_RA_ACCEL_ZOUT_H     0x3F
+#define MPU6050_RA_ACCEL_ZOUT_L     0x40
+#define MPU6050_RA_TEMP_OUT_H       0x41
+#define MPU6050_RA_TEMP_OUT_L       0x42
+#define MPU6050_RA_GYRO_XOUT_H      0x43
+#define MPU6050_RA_GYRO_XOUT_L      0x44
+#define MPU6050_RA_GYRO_YOUT_H      0x45
+#define MPU6050_RA_GYRO_YOUT_L      0x46
+#define MPU6050_RA_GYRO_ZOUT_H      0x47
+#define MPU6050_RA_GYRO_ZOUT_L      0x48
+#define MPU6050_RA_EXT_SENS_DATA_00 0x49
+#define MPU6050_RA_EXT_SENS_DATA_01 0x4A
+#define MPU6050_RA_EXT_SENS_DATA_02 0x4B
+#define MPU6050_RA_EXT_SENS_DATA_03 0x4C
+#define MPU6050_RA_EXT_SENS_DATA_04 0x4D
+#define MPU6050_RA_EXT_SENS_DATA_05 0x4E
+#define MPU6050_RA_EXT_SENS_DATA_06 0x4F
+#define MPU6050_RA_EXT_SENS_DATA_07 0x50
+#define MPU6050_RA_EXT_SENS_DATA_08 0x51
+#define MPU6050_RA_EXT_SENS_DATA_09 0x52
+#define MPU6050_RA_EXT_SENS_DATA_10 0x53
+#define MPU6050_RA_EXT_SENS_DATA_11 0x54
+#define MPU6050_RA_EXT_SENS_DATA_12 0x55
+#define MPU6050_RA_EXT_SENS_DATA_13 0x56
+#define MPU6050_RA_EXT_SENS_DATA_14 0x57
+#define MPU6050_RA_EXT_SENS_DATA_15 0x58
+#define MPU6050_RA_EXT_SENS_DATA_16 0x59
+#define MPU6050_RA_EXT_SENS_DATA_17 0x5A
+#define MPU6050_RA_EXT_SENS_DATA_18 0x5B
+#define MPU6050_RA_EXT_SENS_DATA_19 0x5C
+#define MPU6050_RA_EXT_SENS_DATA_20 0x5D
+#define MPU6050_RA_EXT_SENS_DATA_21 0x5E
+#define MPU6050_RA_EXT_SENS_DATA_22 0x5F
+#define MPU6050_RA_EXT_SENS_DATA_23 0x60
+#define MPU6050_RA_MOT_DETECT_STATUS    0x61
+#define MPU6050_RA_I2C_SLV0_DO      0x63
+#define MPU6050_RA_I2C_SLV1_DO      0x64
+#define MPU6050_RA_I2C_SLV2_DO      0x65
+#define MPU6050_RA_I2C_SLV3_DO      0x66
+#define MPU6050_RA_I2C_MST_DELAY_CTRL   0x67
+#define MPU6050_RA_SIGNAL_PATH_RESET    0x68
+#define MPU6050_RA_MOT_DETECT_CTRL      0x69
+#define MPU6050_RA_USER_CTRL        0x6A
+#define MPU6050_RA_PWR_MGMT_1       0x6B
+#define MPU6050_RA_PWR_MGMT_2       0x6C
+#define MPU6050_RA_BANK_SEL         0x6D
+#define MPU6050_RA_MEM_START_ADDR   0x6E
+#define MPU6050_RA_MEM_R_W          0x6F
+#define MPU6050_RA_DMP_CFG_1        0x70
+#define MPU6050_RA_DMP_CFG_2        0x71
+#define MPU6050_RA_FIFO_COUNTH      0x72
+#define MPU6050_RA_FIFO_COUNTL      0x73
+#define MPU6050_RA_FIFO_R_W         0x74
+#define MPU6050_RA_WHO_AM_I         0x75
+
+#define MPU6050_TC_PWR_MODE_BIT     7
+#define MPU6050_TC_OFFSET_BIT       6
+#define MPU6050_TC_OFFSET_LENGTH    6
+#define MPU6050_TC_OTP_BNK_VLD_BIT  0
+
+#define MPU6050_VDDIO_LEVEL_VLOGIC  0
+#define MPU6050_VDDIO_LEVEL_VDD     1
+
+#define MPU6050_CFG_EXT_SYNC_SET_BIT    5
+#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU6050_CFG_DLPF_CFG_BIT    2
+#define MPU6050_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU6050_EXT_SYNC_DISABLED       0x0
+#define MPU6050_EXT_SYNC_TEMP_OUT_L     0x1
+#define MPU6050_EXT_SYNC_GYRO_XOUT_L    0x2
+#define MPU6050_EXT_SYNC_GYRO_YOUT_L    0x3
+#define MPU6050_EXT_SYNC_GYRO_ZOUT_L    0x4
+#define MPU6050_EXT_SYNC_ACCEL_XOUT_L   0x5
+#define MPU6050_EXT_SYNC_ACCEL_YOUT_L   0x6
+#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L   0x7
+
+#define MPU6050_DLPF_BW_256         0x00
+#define MPU6050_DLPF_BW_188         0x01
+#define MPU6050_DLPF_BW_98          0x02
+#define MPU6050_DLPF_BW_42          0x03
+#define MPU6050_DLPF_BW_20          0x04
+#define MPU6050_DLPF_BW_10          0x05
+#define MPU6050_DLPF_BW_5           0x06
+
+#define MPU6050_GCONFIG_XG_ST_BIT       7
+#define MPU6050_GCONFIG_YG_ST_BIT       6
+#define MPU6050_GCONFIG_ZG_ST_BIT       5
+#define MPU6050_GCONFIG_FS_SEL_BIT      4
+#define MPU6050_GCONFIG_FS_SEL_LENGTH   2
+
+
+#define MPU6050_GYRO_FS_250         0x00
+#define MPU6050_GYRO_FS_500         0x01
+#define MPU6050_GYRO_FS_1000        0x02
+#define MPU6050_GYRO_FS_2000        0x03
+
+#define MPU6050_ACONFIG_XA_ST_BIT           7
+#define MPU6050_ACONFIG_YA_ST_BIT           6
+#define MPU6050_ACONFIG_ZA_ST_BIT           5
+#define MPU6050_ACONFIG_AFS_SEL_BIT         4
+#define MPU6050_ACONFIG_AFS_SEL_LENGTH      2
+#define MPU6050_ACONFIG_ACCEL_HPF_BIT       2
+#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH    3
+
+#define MPU6050_ACCEL_FS_2          0x00
+#define MPU6050_ACCEL_FS_4          0x01
+#define MPU6050_ACCEL_FS_8          0x02
+#define MPU6050_ACCEL_FS_16         0x03
+
+#define MPU6050_DHPF_RESET          0x00
+#define MPU6050_DHPF_5              0x01
+#define MPU6050_DHPF_2P5            0x02
+#define MPU6050_DHPF_1P25           0x03
+#define MPU6050_DHPF_0P63           0x04
+#define MPU6050_DHPF_HOLD           0x07
+
+#define MPU6050_TEMP_FIFO_EN_BIT    7
+#define MPU6050_XG_FIFO_EN_BIT      6
+#define MPU6050_YG_FIFO_EN_BIT      5
+#define MPU6050_ZG_FIFO_EN_BIT      4
+#define MPU6050_ACCEL_FIFO_EN_BIT   3
+#define MPU6050_SLV2_FIFO_EN_BIT    2
+#define MPU6050_SLV1_FIFO_EN_BIT    1
+#define MPU6050_SLV0_FIFO_EN_BIT    0
+
+#define MPU6050_MULT_MST_EN_BIT     7
+#define MPU6050_WAIT_FOR_ES_BIT     6
+#define MPU6050_SLV_3_FIFO_EN_BIT   5
+#define MPU6050_I2C_MST_P_NSR_BIT   4
+#define MPU6050_I2C_MST_CLK_BIT     3
+#define MPU6050_I2C_MST_CLK_LENGTH  4
+
+#define MPU6050_CLOCK_DIV_348       0x0
+#define MPU6050_CLOCK_DIV_333       0x1
+#define MPU6050_CLOCK_DIV_320       0x2
+#define MPU6050_CLOCK_DIV_308       0x3
+#define MPU6050_CLOCK_DIV_296       0x4
+#define MPU6050_CLOCK_DIV_286       0x5
+#define MPU6050_CLOCK_DIV_276       0x6
+#define MPU6050_CLOCK_DIV_267       0x7
+#define MPU6050_CLOCK_DIV_258       0x8
+#define MPU6050_CLOCK_DIV_500       0x9
+#define MPU6050_CLOCK_DIV_471       0xA
+#define MPU6050_CLOCK_DIV_444       0xB
+#define MPU6050_CLOCK_DIV_421       0xC
+#define MPU6050_CLOCK_DIV_400       0xD
+#define MPU6050_CLOCK_DIV_381       0xE
+#define MPU6050_CLOCK_DIV_364       0xF
+
+#define MPU6050_I2C_SLV_RW_BIT      7
+#define MPU6050_I2C_SLV_ADDR_BIT    6
+#define MPU6050_I2C_SLV_ADDR_LENGTH 7
+#define MPU6050_I2C_SLV_EN_BIT      7
+#define MPU6050_I2C_SLV_BYTE_SW_BIT 6
+#define MPU6050_I2C_SLV_REG_DIS_BIT 5
+#define MPU6050_I2C_SLV_GRP_BIT     4
+#define MPU6050_I2C_SLV_LEN_BIT     3
+#define MPU6050_I2C_SLV_LEN_LENGTH  4
+
+#define MPU6050_I2C_SLV4_RW_BIT         7
+#define MPU6050_I2C_SLV4_ADDR_BIT       6
+#define MPU6050_I2C_SLV4_ADDR_LENGTH    7
+#define MPU6050_I2C_SLV4_EN_BIT         7
+#define MPU6050_I2C_SLV4_INT_EN_BIT     6
+#define MPU6050_I2C_SLV4_REG_DIS_BIT    5
+#define MPU6050_I2C_SLV4_MST_DLY_BIT    4
+#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU6050_MST_PASS_THROUGH_BIT    7
+#define MPU6050_MST_I2C_SLV4_DONE_BIT   6
+#define MPU6050_MST_I2C_LOST_ARB_BIT    5
+#define MPU6050_MST_I2C_SLV4_NACK_BIT   4
+#define MPU6050_MST_I2C_SLV3_NACK_BIT   3
+#define MPU6050_MST_I2C_SLV2_NACK_BIT   2
+#define MPU6050_MST_I2C_SLV1_NACK_BIT   1
+#define MPU6050_MST_I2C_SLV0_NACK_BIT   0
+
+#define MPU6050_INTCFG_INT_LEVEL_BIT        7
+#define MPU6050_INTCFG_INT_OPEN_BIT         6
+#define MPU6050_INTCFG_LATCH_INT_EN_BIT     5
+#define MPU6050_INTCFG_INT_RD_CLEAR_BIT     4
+#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT  3
+#define MPU6050_INTCFG_FSYNC_INT_EN_BIT     2
+#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT    1
+#define MPU6050_INTCFG_CLKOUT_EN_BIT        0
+
+#define MPU6050_INTMODE_ACTIVEHIGH  0x00
+#define MPU6050_INTMODE_ACTIVELOW   0x01
+
+#define MPU6050_INTDRV_PUSHPULL     0x00
+#define MPU6050_INTDRV_OPENDRAIN    0x01
+
+#define MPU6050_INTLATCH_50USPULSE  0x00
+#define MPU6050_INTLATCH_WAITCLEAR  0x01
+
+#define MPU6050_INTCLEAR_STATUSREAD 0x00
+#define MPU6050_INTCLEAR_ANYREAD    0x01
+
+#define MPU6050_INTERRUPT_FF_BIT            7
+#define MPU6050_INTERRUPT_MOT_BIT           6
+#define MPU6050_INTERRUPT_ZMOT_BIT          5
+#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT    4
+#define MPU6050_INTERRUPT_I2C_MST_INT_BIT   3
+#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT   2
+#define MPU6050_INTERRUPT_DMP_INT_BIT       1
+#define MPU6050_INTERRUPT_DATA_RDY_BIT      0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU6050_DMPINT_5_BIT            5
+#define MPU6050_DMPINT_4_BIT            4
+#define MPU6050_DMPINT_3_BIT            3
+#define MPU6050_DMPINT_2_BIT            2
+#define MPU6050_DMPINT_1_BIT            1
+#define MPU6050_DMPINT_0_BIT            0
+
+#define MPU6050_MOTION_MOT_XNEG_BIT     7
+#define MPU6050_MOTION_MOT_XPOS_BIT     6
+#define MPU6050_MOTION_MOT_YNEG_BIT     5
+#define MPU6050_MOTION_MOT_YPOS_BIT     4
+#define MPU6050_MOTION_MOT_ZNEG_BIT     3
+#define MPU6050_MOTION_MOT_ZPOS_BIT     2
+#define MPU6050_MOTION_MOT_ZRMOT_BIT    0
+
+#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
+#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
+#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
+#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
+#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
+#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
+
+#define MPU6050_PATHRESET_GYRO_RESET_BIT    2
+#define MPU6050_PATHRESET_ACCEL_RESET_BIT   1
+#define MPU6050_PATHRESET_TEMP_RESET_BIT    0
+
+#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT       5
+#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH    2
+#define MPU6050_DETECT_FF_COUNT_BIT             3
+#define MPU6050_DETECT_FF_COUNT_LENGTH          2
+#define MPU6050_DETECT_MOT_COUNT_BIT            1
+#define MPU6050_DETECT_MOT_COUNT_LENGTH         2
+
+#define MPU6050_DETECT_DECREMENT_RESET  0x0
+#define MPU6050_DETECT_DECREMENT_1      0x1
+#define MPU6050_DETECT_DECREMENT_2      0x2
+#define MPU6050_DETECT_DECREMENT_4      0x3
+
+#define MPU6050_USERCTRL_DMP_EN_BIT             7
+#define MPU6050_USERCTRL_FIFO_EN_BIT            6
+#define MPU6050_USERCTRL_I2C_MST_EN_BIT         5
+#define MPU6050_USERCTRL_I2C_IF_DIS_BIT         4
+#define MPU6050_USERCTRL_DMP_RESET_BIT          3
+#define MPU6050_USERCTRL_FIFO_RESET_BIT         2
+#define MPU6050_USERCTRL_I2C_MST_RESET_BIT      1
+#define MPU6050_USERCTRL_SIG_COND_RESET_BIT     0
+
+#define MPU6050_PWR1_DEVICE_RESET_BIT   7
+#define MPU6050_PWR1_SLEEP_BIT          6
+#define MPU6050_PWR1_CYCLE_BIT          5
+#define MPU6050_PWR1_TEMP_DIS_BIT       3
+#define MPU6050_PWR1_CLKSEL_BIT         2
+#define MPU6050_PWR1_CLKSEL_LENGTH      3
+
+#define MPU6050_CLOCK_INTERNAL          0x00
+#define MPU6050_CLOCK_PLL_XGYRO         0x01
+#define MPU6050_CLOCK_PLL_YGYRO         0x02
+#define MPU6050_CLOCK_PLL_ZGYRO         0x03
+#define MPU6050_CLOCK_PLL_EXT32K        0x04
+#define MPU6050_CLOCK_PLL_EXT19M        0x05
+#define MPU6050_CLOCK_KEEP_RESET        0x07
+
+#define MPU6050_PWR2_LP_WAKE_CTRL_BIT       7
+#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH    2
+#define MPU6050_PWR2_STBY_XA_BIT            5
+#define MPU6050_PWR2_STBY_YA_BIT            4
+#define MPU6050_PWR2_STBY_ZA_BIT            3
+#define MPU6050_PWR2_STBY_XG_BIT            2
+#define MPU6050_PWR2_STBY_YG_BIT            1
+#define MPU6050_PWR2_STBY_ZG_BIT            0
+
+#define MPU6050_WAKE_FREQ_1P25      0x0
+#define MPU6050_WAKE_FREQ_2P5       0x1
+#define MPU6050_WAKE_FREQ_5         0x2
+#define MPU6050_WAKE_FREQ_10        0x3
+
+#define MPU6050_BANKSEL_PRFTCH_EN_BIT       6
+#define MPU6050_BANKSEL_CFG_USER_BANK_BIT   5
+#define MPU6050_BANKSEL_MEM_SEL_BIT         4
+#define MPU6050_BANKSEL_MEM_SEL_LENGTH      5
+
+#define MPU6050_WHO_AM_I_BIT        6
+#define MPU6050_WHO_AM_I_LENGTH     6
+
+#define MPU6050_DMP_MEMORY_BANKS        8
+#define MPU6050_DMP_MEMORY_BANK_SIZE    256
+#define MPU6050_DMP_MEMORY_CHUNK_SIZE   16
+
+#define MPU6050_DEG_PER_LSB_250  (float)((2 * 250.0) / 65536.0)
+#define MPU6050_DEG_PER_LSB_500  (float)((2 * 500.0) / 65536.0)
+#define MPU6050_DEG_PER_LSB_1000 (float)((2 * 1000.0) / 65536.0)
+#define MPU6050_DEG_PER_LSB_2000 (float)((2 * 2000.0) / 65536.0)
+
+#define MPU6050_G_PER_LSB_2      (float)((2 * 2) / 65536.0)
+#define MPU6050_G_PER_LSB_4      (float)((2 * 4) / 65536.0)
+#define MPU6050_G_PER_LSB_8      (float)((2 * 8) / 65536.0)
+#define MPU6050_G_PER_LSB_16     (float)((2 * 16) / 65536.0)
+
+#define MPU6050_ST_GYRO_LOW      10.0   // deg/s
+#define MPU6050_ST_GYRO_HIGH     105.0  // deg/s
+#define MPU6050_ST_ACCEL_LOW     0.300  // G
+#define MPU6050_ST_ACCEL_HIGH    0.950  // G
+
+// note: DMP code memory blocks defined at end of header file
+
+void mpu6050Init(I2C_Dev *i2cPort);
+bool mpu6050Test(void);
+
+bool mpu6050TestConnection();
+bool mpu6050EvaluateSelfTest(float low, float high, float value, char* string);
+bool mpu6050SelfTest();
+
+
+// AUX_VDDIO register
+uint8_t mpu6050GetAuxVDDIOLevel();
+void mpu6050SetAuxVDDIOLevel(uint8_t level);
+
+// SMPLRT_DIV register
+uint8_t mpu6050GetRate();
+void mpu6050SetRate(uint8_t rate);
+
+// CONFIG register
+uint8_t mpu6050GetExternalFrameSync();
+void mpu6050SetExternalFrameSync(uint8_t sync);
+uint8_t mpu6050GetDLPFMode();
+void mpu6050SetDLPFMode(uint8_t bandwidth);
+
+// GYRO_CONFIG register
+void mpu6050SetGyroXSelfTest(bool enabled);
+void mpu6050SetGyroYSelfTest(bool enabled);
+void mpu6050SetGyroZSelfTest(bool enabled);
+uint8_t mpu6050GetFullScaleGyroRangeId();
+float mpu6050GetFullScaleGyroDPL();
+void mpu6050SetFullScaleGyroRange(uint8_t range);
+
+// ACCEL_CONFIG register
+bool mpu6050GetAccelXSelfTest();
+void mpu6050SetAccelXSelfTest(bool enabled);
+bool mpu6050GetAccelYSelfTest();
+void mpu6050SetAccelYSelfTest(bool enabled);
+bool mpu6050GetAccelZSelfTest();
+void mpu6050SetAccelZSelfTest(bool enabled);
+uint8_t mpu6050GetFullScaleAccelRangeId();
+void mpu6050SetFullScaleAccelRange(uint8_t range);
+float mpu6050GetFullScaleAccelGPL();
+uint8_t mpu6050GetDHPFMode();
+void mpu6050SetDHPFMode(uint8_t mode);
+
+// FF_THR register
+uint8_t mpu6050GetFreefallDetectionThreshold();
+void mpu6050SetFreefallDetectionThreshold(uint8_t threshold);
+
+// FF_DUR register
+uint8_t mpu6050GetFreefallDetectionDuration();
+void mpu6050SetFreefallDetectionDuration(uint8_t duration);
+
+// MOT_THR register
+uint8_t mpu6050GetMotionDetectionThreshold();
+void mpu6050SetMotionDetectionThreshold(uint8_t threshold);
+
+// MOT_DUR register
+uint8_t mpu6050GetMotionDetectionDuration();
+void mpu6050SetMotionDetectionDuration(uint8_t duration);
+
+// ZRMOT_THR register
+uint8_t mpu6050GetZeroMotionDetectionThreshold();
+void mpu6050SetZeroMotionDetectionThreshold(uint8_t threshold);
+
+// ZRMOT_DUR register
+uint8_t mpu6050GetZeroMotionDetectionDuration();
+void mpu6050SetZeroMotionDetectionDuration(uint8_t duration);
+
+// FIFO_EN register
+bool mpu6050GetTempFIFOEnabled();
+void mpu6050SetTempFIFOEnabled(bool enabled);
+bool mpu6050GetXGyroFIFOEnabled();
+void mpu6050SetXGyroFIFOEnabled(bool enabled);
+bool mpu6050GetYGyroFIFOEnabled();
+void mpu6050SetYGyroFIFOEnabled(bool enabled);
+bool mpu6050GetZGyroFIFOEnabled();
+void mpu6050SetZGyroFIFOEnabled(bool enabled);
+bool mpu6050GetAccelFIFOEnabled();
+void mpu6050SetAccelFIFOEnabled(bool enabled);
+bool mpu6050GetSlave2FIFOEnabled();
+void mpu6050SetSlave2FIFOEnabled(bool enabled);
+bool mpu6050GetSlave1FIFOEnabled();
+void mpu6050SetSlave1FIFOEnabled(bool enabled);
+bool mpu6050GetSlave0FIFOEnabled();
+void mpu6050SetSlave0FIFOEnabled(bool enabled);
+
+// I2C_MST_CTRL register
+bool mpu6050GetMultiMasterEnabled();
+void mpu6050SetMultiMasterEnabled(bool enabled);
+bool mpu6050GetWaitForExternalSensorEnabled();
+void mpu6050SetWaitForExternalSensorEnabled(bool enabled);
+bool mpu6050GetSlave3FIFOEnabled();
+void mpu6050SetSlave3FIFOEnabled(bool enabled);
+bool mpu6050GetSlaveReadWriteTransitionEnabled();
+void mpu6050SetSlaveReadWriteTransitionEnabled(bool enabled);
+uint8_t mpu6050GetMasterClockSpeed();
+void mpu6050SetMasterClockSpeed(uint8_t speed);
+
+// I2C_SLV* registers (Slave 0-3)
+uint8_t mpu6050GetSlaveAddress(uint8_t num);
+void mpu6050SetSlaveAddress(uint8_t num, uint8_t address);
+uint8_t mpu6050GetSlaveRegister(uint8_t num);
+void mpu6050SetSlaveRegister(uint8_t num, uint8_t reg);
+bool mpu6050GetSlaveEnabled(uint8_t num);
+void mpu6050SetSlaveEnabled(uint8_t num, bool enabled);
+bool mpu6050GetSlaveWordByteSwap(uint8_t num);
+void mpu6050SetSlaveWordByteSwap(uint8_t num, bool enabled);
+bool mpu6050GetSlaveWriteMode(uint8_t num);
+void mpu6050SetSlaveWriteMode(uint8_t num, bool mode);
+bool mpu6050GetSlaveWordGroupOffmpu6050Set(uint8_t num);
+void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+uint8_t mpu6050GetSlaveDataLength(uint8_t num);
+void mpu6050SetSlaveDataLempu6050Seth(uint8_t num, uint8_t length);
+
+// I2C_SLV* registers (Slave 4)
+uint8_t mpu6050GetSlave4Address();
+void mpu6050SetSlave4Address(uint8_t address);
+uint8_t mpu6050GetSlave4Register();
+void mpu6050SetSlave4Register(uint8_t reg);
+void mpu6050SetSlave4OutputByte(uint8_t data);
+bool mpu6050GetSlave4Enabled();
+void mpu6050SetSlave4Enabled(bool enabled);
+bool mpu6050GetSlave4InterruptEnabled();
+void mpu6050SetSlave4InterruptEnabled(bool enabled);
+bool mpu6050GetSlave4WriteMode();
+void mpu6050SetSlave4WriteMode(bool mode);
+uint8_t mpu6050GetSlave4MasterDelay();
+void mpu6050SetSlave4MasterDelay(uint8_t delay);
+uint8_t mpu6050GetSlate4InputByte();
+
+// I2C_MST_STATUS register
+bool mpu6050GetPassthroughStatus();
+bool mpu6050GetSlave4IsDone();
+bool mpu6050GetLostArbitration();
+bool mpu6050GetSlave4Nack();
+bool mpu6050GetSlave3Nack();
+bool mpu6050GetSlave2Nack();
+bool mpu6050GetSlave1Nack();
+bool mpu6050GetSlave0Nack();
+
+// INT_PIN_CFG register
+bool mpu6050GetInterruptMode();
+void mpu6050SetInterruptMode(bool mode);
+bool mpu6050GetInterruptDrive();
+void mpu6050SetInterruptDrive(bool drive);
+bool mpu6050GetInterruptLatch();
+void mpu6050SetInterruptLatch(bool latch);
+bool mpu6050GetInterruptLatchClear();
+void mpu6050SetInterruptLatchClear(bool clear);
+bool mpu6050GetFSyncInterruptLevel();
+void mpu6050SetFSyncInterruptLevel(bool level);
+bool mpu6050GetFSyncInterruptEnabled();
+void mpu6050SetFSyncInterruptEnabled(bool enabled);
+bool mpu6050GetI2CBypassEnabled();
+void mpu6050SetI2CBypassEnabled(bool enabled);
+bool mpu6050GetClockOutputEnabled();
+void mpu6050SetClockOutputEnabled(bool enabled);
+
+// INT_ENABLE register
+uint8_t mpu6050GetIntEnabled();
+void mpu6050SetIntEnabled(uint8_t enabled);
+bool mpu6050GetIntFreefallEnabled();
+void mpu6050SetIntFreefallEnabled(bool enabled);
+bool mpu6050GetIntMotionEnabled();
+void mpu6050SetIntMotionEnabled(bool enabled);
+bool mpu6050GetIntZeroMotionEnabled();
+void mpu6050SetIntZeroMotionEnabled(bool enabled);
+bool mpu6050GetIntFIFOBufferOverflowEnabled();
+void mpu6050SetIntFIFOBufferOverflowEnabled(bool enabled);
+bool mpu6050GetIntI2CMasterEnabled();
+void mpu6050SetIntI2CMasterEnabled(bool enabled);
+bool mpu6050GetIntDataReadyEnabled();
+void mpu6050SetIntDataReadyEnabled(bool enabled);
+
+// INT_STATUS register
+uint8_t mpu6050GetIntStatus();
+bool mpu6050GetIntFreefallStatus();
+bool mpu6050GetIntMotionStatus();
+bool mpu6050GetIntZeroMotionStatus();
+bool mpu6050GetIntFIFOBufferOverflowStatus();
+bool mpu6050GetIntI2CMasterStatus();
+bool mpu6050GetIntDataReadyStatus();
+
+// ACCEL_*OUT_* registers
+void mpu6050GetMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+void mpu6050GetMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+void mpu6050GetAcceleration(int16_t* x, int16_t* y, int16_t* z);
+int16_t mpu6050GetAccelerationX();
+int16_t mpu6050GetAccelerationY();
+int16_t mpu6050GetAccelerationZ();
+
+// TEMP_OUT_* registers
+int16_t mpu6050GetTemperature();
+
+// GYRO_*OUT_* registers
+void mpu6050GetRotation(int16_t* x, int16_t* y, int16_t* z);
+int16_t mpu6050GetRotationX();
+int16_t mpu6050GetRotationY();
+int16_t mpu6050GetRotationZ();
+
+// EXT_SENS_DATA_* registers
+uint8_t mpu6050GetExternalSensorByte(int position);
+uint16_t mpu6050GetExternalSensorWord(int position);
+uint32_t mpu6050GetExternalSensorDWord(int position);
+
+// MOT_DETECT_STATUS register
+bool mpu6050GetXNegMotionDetected();
+bool mpu6050GetXPosMotionDetected();
+bool mpu6050GetYNegMotionDetected();
+bool mpu6050GetYPosMotionDetected();
+bool mpu6050GetZNegMotionDetected();
+bool mpu6050GetZPosMotionDetected();
+bool mpu6050GetZeroMotionDetected();
+
+// I2C_SLV*_DO register
+void mpu6050SetSlaveOutputByte(uint8_t num, uint8_t data);
+
+// I2C_MST_DELAY_CTRL register
+bool mpu6050GetExternalShadowDelayEnabled();
+void mpu6050SetExternalShadowDelayEnabled(bool enabled);
+bool mpu6050GetSlaveDelayEnabled(uint8_t num);
+void mpu6050SetSlaveDelayEnabled(uint8_t num, bool enabled);
+
+// SIGNAL_PATH_RESET register
+void rempu6050SetGyroscopePath();
+void rempu6050SetAccelerometerPath();
+void rempu6050SetTemperaturePath();
+
+// MOT_DETECT_CTRL register
+uint8_t mpu6050GetAccelerometerPowerOnDelay();
+void mpu6050SetAccelerometerPowerOnDelay(uint8_t delay);
+uint8_t mpu6050GetFreefallDetectionCounterDecrement();
+void mpu6050SetFreefallDetectionCounterDecrement(uint8_t decrement);
+uint8_t mpu6050GetMotionDetectionCounterDecrement();
+void mpu6050SetMotionDetectionCounterDecrement(uint8_t decrement);
+
+// USER_CTRL register
+bool mpu6050GetFIFOEnabled();
+void mpu6050SetFIFOEnabled(bool enabled);
+bool mpu6050GetI2CMasterModeEnabled();
+void mpu6050SetI2CMasterModeEnabled(bool enabled);
+void mpu6050SwitchSPIEnabled(bool enabled);
+void mpu6050ResetFIFO();
+void mpu6050ResetI2CMaster();
+void mpu6050ResetSensors();
+
+// PWR_MGMT_1 register
+void mpu6050Reset();
+bool mpu6050GetSleepEnabled();
+void mpu6050SetSleepEnabled(bool enabled);
+bool mpu6050GetWakeCycleEnabled();
+void mpu6050SetWakeCycleEnabled(bool enabled);
+bool mpu6050GetTempSensorEnabled();
+void mpu6050SetTempSensorEnabled(bool enabled);
+uint8_t mpu6050GetClockSource();
+void mpu6050SetClockSource(uint8_t source);
+
+// PWR_MGMT_2 register
+uint8_t mpu6050GetWakeFrequency();
+void mpu6050SetWakeFrequency(uint8_t frequency);
+bool mpu6050GetStandbyXAccelEnabled();
+void mpu6050SetStandbyXAccelEnabled(bool enabled);
+bool mpu6050GetStandbyYAccelEnabled();
+void mpu6050SetStandbyYAccelEnabled(bool enabled);
+bool mpu6050GetStandbyZAccelEnabled();
+void mpu6050SetStandbyZAccelEnabled(bool enabled);
+bool mpu6050GetStandbyXGyroEnabled();
+void mpu6050SetStandbyXGyroEnabled(bool enabled);
+bool mpu6050GetStandbyYGyroEnabled();
+void mpu6050SetStandbyYGyroEnabled(bool enabled);
+bool mpu6050GetStandbyZGyroEnabled();
+void mpu6050SetStandbyZGyroEnabled(bool enabled);
+
+// FIFO_COUNT_* registers
+uint16_t mpu6050GetFIFOCount();
+
+// FIFO_R_W register
+uint8_t mpu6050GetFIFOByte();
+void mpu6050SetFIFOByte(uint8_t data);
+void mpu6050GetFIFOBytes(uint8_t *data, uint8_t length);
+
+// WHO_AM_I register
+uint8_t mpu6050GetDeviceID();
+void mpu6050SetDeviceID(uint8_t id);
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+uint8_t mpu6050GetOTPBankValid();
+void mpu6050SetOTPBankValid(bool enabled);
+int8_t mpu6050GetXGyroOffset();
+void mpu6050SetXGyroOffset(int8_t offset);
+
+// YG_OFFS_TC register
+int8_t mpu6050GetYGyroOffset();
+void mpu6050SetYGyroOffset(int8_t offset);
+
+// ZG_OFFS_TC register
+int8_t mpu6050GetZGyroOffset();
+void  mpu6050SetGyroOffset(int8_t offset);
+
+// X_FINE_GAIN register
+int8_t mpu6050GetXFineGain();
+void mpu6050SetXFineGain(int8_t gain);
+
+// Y_FINE_GAIN register
+int8_t mpu6050GetYFineGain();
+void mpu6050SetYFineGain(int8_t gain);
+
+// Z_FINE_GAIN register
+int8_t mpu6050GetZFineGain();
+void mpu6050SetZFineGain(int8_t gain);
+
+// XA_OFFS_* registers
+int16_t mpu6050GetXAccelOffset();
+void mpu6050SetXAccelOffset(int16_t offset);
+
+// YA_OFFS_* register
+int16_t mpu6050GetYAccelOffset();
+void mpu6050SetYAccelOffset(int16_t offset);
+
+// ZA_OFFS_* register
+int16_t mpu6050GetZAccelOffset();
+void mpu6050SetZAccelOffset(int16_t offset);
+
+// XG_OFFS_USR* registers
+int16_t mpu6050GetXGyroOffsetUser();
+void mpu6050SetXGyroOffsetUser(int16_t offset);
+
+// YG_OFFS_USR* register
+int16_t mpu6050GetYGyroOffsetUser();
+void mpu6050SetYGyroOffsetUser(int16_t offset);
+
+// ZG_OFFS_USR* register
+int16_t mpu6050GetZGyroOffsetUser();
+void mpu6050SetZGyroOffsetUser(int16_t offset);
+
+// INT_ENABLE register (DMP functions)
+bool mpu6050GetIntPLLReadyEnabled();
+void mpu6050SetIntPLLReadyEnabled(bool enabled);
+bool mpu6050GetIntDMPEnabled();
+void mpu6050SetIntDMPEnabled(bool enabled);
+
+// DMP_INT_STATUS
+bool mpu6050GetDMPInt5Status();
+bool mpu6050GetDMPInt4Status();
+bool mpu6050GetDMPInt3Status();
+bool mpu6050GetDMPInt2Status();
+bool mpu6050GetDMPInt1Status();
+bool mpu6050GetDMPInt0Status();
+
+// INT_STATUS register (DMP functions)
+bool mpu6050GetIntPLLReadyStatus();
+bool mpu6050GetIntDMPStatus();
+
+// USER_CTRL register (DMP functions)
+bool mpu6050GetDMPEnabled();
+void mpu6050SetDMPEnabled(bool enabled);
+void mpu6050ResetDMP();
+
+// BANK_SEL register
+void mpu6050SetMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank);
+
+// MEM_START_ADDR register
+void mpu6050SetMemoryStartAddress(uint8_t address);
+
+// MEM_R_W register
+uint8_t mpu6050ReadMemoryByte();
+void mpu6050WriteMemoryByte(uint8_t data);
+void mpu6050ReadMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address);
+bool mpu6050WriteMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify);
+bool mpu6050WriteProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify);
+
+bool mpu6050WriteDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+bool mpu6050WiteProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+// DMP_CFG_1 register
+uint8_t mpu6050GetDMPConfig1();
+void mpu6050SetDMPConfig1(uint8_t config);
+
+// DMP_CFG_2 register
+uint8_t mpu6050GetDMPConfig2();
+void mpu6050SetDMPConfig2(uint8_t config);
+
+
+#ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS20
+    /* This is only included if you want it, since it eats about 2K of program
+     * memory, which is a waste if you aren't using the DMP (or if you aren't
+     * using this particular flavor of DMP).
+     *
+     * Source is from the InvenSense MotionApps v2 demo code. Original source is
+     * unavailable, unless you happen to be amazing as decompiling binary by
+     * hand (in which case, please contact me, and I'm totally serious).
+     *
+     * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the
+     * DMP reverse-engineering he did to help make this bit of wizardry
+     * possible.
+     */
+
+    #define MPU6050_DMP_CODE_SIZE 1929
+
+    // this block of memory gets written to the MPU on start-up, and it seems
+    // to be volatile memory, so it has to be done each time (it only takes ~1
+    // second though)
+    const prog_uchar dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+        // bank 0, 256 bytes
+        0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+        0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+        0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+        0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+        0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+        0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+        0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+        0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+        0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+        // bank 1, 256 bytes
+        0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+        0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+        0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+        0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+
+        // bank 2, 256 bytes
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+        0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+        // bank 3, 256 bytes
+        0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F,
+        0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2,
+        0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF,
+        0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C,
+        0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1,
+        0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01,
+        0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80,
+        0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C,
+        0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80,
+        0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E,
+        0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9,
+        0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24,
+        0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0,
+        0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86,
+        0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+        0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+
+        // bank 4, 256 bytes
+        0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+        0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+        0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+        0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+        0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+        0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+        0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+        0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+        0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+        0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+        0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+        0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+        0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+        0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+        0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+        0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+
+        // bank 5, 256 bytes
+        0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+        0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+        0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+        0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+        0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+        0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+        0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+        0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+        0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A,
+        0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60,
+        0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97,
+        0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04,
+        0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78,
+        0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79,
+        0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68,
+        0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68,
+
+        // bank 6, 256 bytes
+        0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04,
+        0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66,
+        0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31,
+        0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60,
+        0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76,
+        0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56,
+        0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD,
+        0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91,
+        0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8,
+        0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE,
+        0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9,
+        0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD,
+        0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E,
+        0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8,
+        0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89,
+        0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79,
+
+        // bank 7, 138 bytes (remainder)
+        0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8,
+        0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA,
+        0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB,
+        0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3,
+        0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3,
+        0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+        0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3,
+        0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC,
+        0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+    };
+
+    #define MPU6050_DMP_CONFIG_SIZE 192
+
+    // thanks to Noah Zerkin for piecing this stuff together!
+    const prog_uchar dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = {
+    //  BANK    OFFSET  LENGTH  [DATA]
+        0x03,   0x7B,   0x03,   0x4C, 0xCD, 0x6C,         // FCFG_1 inv_set_gyro_calibration
+        0x03,   0xAB,   0x03,   0x36, 0x56, 0x76,         // FCFG_3 inv_set_gyro_calibration
+        0x00,   0x68,   0x04,   0x02, 0xCB, 0x47, 0xA2,   // D_0_104 inv_set_gyro_calibration
+        0x02,   0x18,   0x04,   0x00, 0x05, 0x8B, 0xC1,   // D_0_24 inv_set_gyro_calibration
+        0x01,   0x0C,   0x04,   0x00, 0x00, 0x00, 0x00,   // D_1_152 inv_set_accel_calibration
+        0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_accel_calibration
+        0x03,   0x89,   0x03,   0x26, 0x46, 0x66,         // FCFG_7 inv_set_accel_calibration
+        0x00,   0x6C,   0x02,   0x20, 0x00,               // D_0_108 inv_set_accel_calibration
+        0x02,   0x40,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_00 inv_set_compass_calibration
+        0x02,   0x44,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_01
+        0x02,   0x48,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_02
+        0x02,   0x4C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_10
+        0x02,   0x50,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_11
+        0x02,   0x54,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_12
+        0x02,   0x58,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_20
+        0x02,   0x5C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_21
+        0x02,   0xBC,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_22
+        0x01,   0xEC,   0x04,   0x00, 0x00, 0x40, 0x00,   // D_1_236 inv_apply_endian_accel
+        0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+        0x04,   0x02,   0x03,   0x0D, 0x35, 0x5D,         // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+        0x04,   0x09,   0x04,   0x87, 0x2D, 0x35, 0x3D,   // FCFG_5 inv_set_bias_update
+        0x00,   0xA3,   0x01,   0x00,                     // D_0_163 inv_set_dead_zone
+                     // SPECIAL 0x01 = enable interrupts
+        0x00,   0x00,   0x00,   0x01, // SET INT_ENABLE at i=22, SPECIAL INSTRUCTION
+        0x07,   0x86,   0x01,   0xFE,                     // CFG_6 inv_set_fifo_interupt
+        0x07,   0x41,   0x05,   0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+        0x07,   0x7E,   0x01,   0x30,                     // CFG_16 inv_set_footer
+        0x07,   0x46,   0x01,   0x9A,                     // CFG_GYRO_SOURCE inv_send_gyro
+        0x07,   0x47,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_9 inv_send_gyro -> inv_construct3_fifo
+        0x07,   0x6C,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_12 inv_send_accel -> inv_construct3_fifo
+        0x02,   0x16,   0x02,   0x00, 0x0A                // D_0_22 inv_set_fifo_rate
+    };
+
+#endif
+
+#endif /* _MPU6050_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/mpu6500.h b/crazyflie-firmware-src/src/drivers/interface/mpu6500.h
new file mode 100644
index 0000000000000000000000000000000000000000..a2d5969db448df9bc48acbf39bfc7a9012fb04e6
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/mpu6500.h
@@ -0,0 +1,1023 @@
+// I2Cdev library collection - MPU6500 I2C device class
+// Based on InvenSense MPU-6500 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2011 Jeff Rowberg
+Adapted to Crazyflie FW by Bitcraze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6500_H_
+#define _MPU6500_H_
+
+#include "i2cdev.h"
+
+#define MPU6500_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU6500_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU6500_DEFAULT_ADDRESS     MPU6500_ADDRESS_AD0_HIGH
+
+//Product ID Description for MPU6500:  | High 4 bits  | Low 4 bits        |
+//                                     | Product Name | Product Revision  |
+#define MPU6500_REV_C4_ES     0x14  //        0001           0100
+#define MPU6500_REV_C5_ES     0x15  //        0001           0101
+#define MPU6500_REV_D6_ES     0x16  //        0001           0110
+#define MPU6500_REV_D7_ES     0x17  //        0001           0111
+#define MPU6500_REV_D8_ES     0x18  //        0001           1000
+#define MPU6500_REV_C4        0x54  //        0101           0100
+#define MPU6500_REV_C5        0x55  //        0101           0101
+#define MPU6500_REV_D6        0x56  //        0101           0110
+#define MPU6500_REV_D7        0x57  //        0101           0111
+#define MPU6500_REV_D8        0x58  //        0101           1000
+#define MPU6500_REV_D9        0x59  //        0101           1001
+
+#define MPU6500_RA_ST_X_GYRO        0x00
+#define MPU6500_RA_ST_Y_GYRO        0x01
+#define MPU6500_RA_ST_Z_GYRO        0x02
+#define MPU6500_RA_ST_X_ACCEL       0x0D
+#define MPU6500_RA_ST_Y_ACCEL       0x0E
+#define MPU6500_RA_ST_Z_ACCEL       0x0F
+#define MPU6500_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
+#define MPU6500_RA_XG_OFFS_USRL     0x14
+#define MPU6500_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
+#define MPU6500_RA_YG_OFFS_USRL     0x16
+#define MPU6500_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
+#define MPU6500_RA_ZG_OFFS_USRL     0x18
+#define MPU6500_RA_SMPLRT_DIV       0x19
+#define MPU6500_RA_CONFIG           0x1A
+#define MPU6500_RA_GYRO_CONFIG      0x1B
+#define MPU6500_RA_ACCEL_CONFIG     0x1C
+#define MPU6500_RA_ACCEL_CONFIG_2   0x1D
+#define MPU6500_RA_LP_ACCEL_ODR     0x1E
+#define MPU6500_RA_WOM_THR          0x1F
+
+#define MPU6500_RA_FIFO_EN          0x23
+#define MPU6500_RA_I2C_MST_CTRL     0x24
+#define MPU6500_RA_I2C_SLV0_ADDR    0x25
+#define MPU6500_RA_I2C_SLV0_REG     0x26
+#define MPU6500_RA_I2C_SLV0_CTRL    0x27
+#define MPU6500_RA_I2C_SLV1_ADDR    0x28
+#define MPU6500_RA_I2C_SLV1_REG     0x29
+#define MPU6500_RA_I2C_SLV1_CTRL    0x2A
+#define MPU6500_RA_I2C_SLV2_ADDR    0x2B
+#define MPU6500_RA_I2C_SLV2_REG     0x2C
+#define MPU6500_RA_I2C_SLV2_CTRL    0x2D
+#define MPU6500_RA_I2C_SLV3_ADDR    0x2E
+#define MPU6500_RA_I2C_SLV3_REG     0x2F
+#define MPU6500_RA_I2C_SLV3_CTRL    0x30
+#define MPU6500_RA_I2C_SLV4_ADDR    0x31
+#define MPU6500_RA_I2C_SLV4_REG     0x32
+#define MPU6500_RA_I2C_SLV4_DO      0x33
+#define MPU6500_RA_I2C_SLV4_CTRL    0x34
+#define MPU6500_RA_I2C_SLV4_DI      0x35
+#define MPU6500_RA_I2C_MST_STATUS   0x36
+#define MPU6500_RA_INT_PIN_CFG      0x37
+#define MPU6500_RA_INT_ENABLE       0x38
+#define MPU6500_RA_DMP_INT_STATUS   0x39
+#define MPU6500_RA_INT_STATUS       0x3A
+#define MPU6500_RA_ACCEL_XOUT_H     0x3B
+#define MPU6500_RA_ACCEL_XOUT_L     0x3C
+#define MPU6500_RA_ACCEL_YOUT_H     0x3D
+#define MPU6500_RA_ACCEL_YOUT_L     0x3E
+#define MPU6500_RA_ACCEL_ZOUT_H     0x3F
+#define MPU6500_RA_ACCEL_ZOUT_L     0x40
+#define MPU6500_RA_TEMP_OUT_H       0x41
+#define MPU6500_RA_TEMP_OUT_L       0x42
+#define MPU6500_RA_GYRO_XOUT_H      0x43
+#define MPU6500_RA_GYRO_XOUT_L      0x44
+#define MPU6500_RA_GYRO_YOUT_H      0x45
+#define MPU6500_RA_GYRO_YOUT_L      0x46
+#define MPU6500_RA_GYRO_ZOUT_H      0x47
+#define MPU6500_RA_GYRO_ZOUT_L      0x48
+#define MPU6500_RA_EXT_SENS_DATA_00 0x49
+#define MPU6500_RA_EXT_SENS_DATA_01 0x4A
+#define MPU6500_RA_EXT_SENS_DATA_02 0x4B
+#define MPU6500_RA_EXT_SENS_DATA_03 0x4C
+#define MPU6500_RA_EXT_SENS_DATA_04 0x4D
+#define MPU6500_RA_EXT_SENS_DATA_05 0x4E
+#define MPU6500_RA_EXT_SENS_DATA_06 0x4F
+#define MPU6500_RA_EXT_SENS_DATA_07 0x50
+#define MPU6500_RA_EXT_SENS_DATA_08 0x51
+#define MPU6500_RA_EXT_SENS_DATA_09 0x52
+#define MPU6500_RA_EXT_SENS_DATA_10 0x53
+#define MPU6500_RA_EXT_SENS_DATA_11 0x54
+#define MPU6500_RA_EXT_SENS_DATA_12 0x55
+#define MPU6500_RA_EXT_SENS_DATA_13 0x56
+#define MPU6500_RA_EXT_SENS_DATA_14 0x57
+#define MPU6500_RA_EXT_SENS_DATA_15 0x58
+#define MPU6500_RA_EXT_SENS_DATA_16 0x59
+#define MPU6500_RA_EXT_SENS_DATA_17 0x5A
+#define MPU6500_RA_EXT_SENS_DATA_18 0x5B
+#define MPU6500_RA_EXT_SENS_DATA_19 0x5C
+#define MPU6500_RA_EXT_SENS_DATA_20 0x5D
+#define MPU6500_RA_EXT_SENS_DATA_21 0x5E
+#define MPU6500_RA_EXT_SENS_DATA_22 0x5F
+#define MPU6500_RA_EXT_SENS_DATA_23 0x60
+#define MPU6500_RA_MOT_DETECT_STATUS    0x61
+#define MPU6500_RA_I2C_SLV0_DO      0x63
+#define MPU6500_RA_I2C_SLV1_DO      0x64
+#define MPU6500_RA_I2C_SLV2_DO      0x65
+#define MPU6500_RA_I2C_SLV3_DO      0x66
+#define MPU6500_RA_I2C_MST_DELAY_CTRL   0x67
+#define MPU6500_RA_SIGNAL_PATH_RESET    0x68
+#define MPU6500_RA_MOT_DETECT_CTRL      0x69
+#define MPU6500_RA_USER_CTRL        0x6A
+#define MPU6500_RA_PWR_MGMT_1       0x6B
+#define MPU6500_RA_PWR_MGMT_2       0x6C
+#define MPU6500_RA_BANK_SEL         0x6D
+#define MPU6500_RA_MEM_START_ADDR   0x6E
+#define MPU6500_RA_MEM_R_W          0x6F
+#define MPU6500_RA_DMP_CFG_1        0x70
+#define MPU6500_RA_DMP_CFG_2        0x71
+#define MPU6500_RA_FIFO_COUNTH      0x72
+#define MPU6500_RA_FIFO_COUNTL      0x73
+#define MPU6500_RA_FIFO_R_W         0x74
+#define MPU6500_RA_WHO_AM_I         0x75
+
+#define MPU6500_RA_XA_OFFSET_H      0x77
+#define MPU6500_RA_XA_OFFSET_L      0x78
+#define MPU6500_RA_YA_OFFSET_H      0x7A
+#define MPU6500_RA_YA_OFFSET_L      0x7B
+#define MPU6500_RA_ZA_OFFSET_H      0x7D
+#define MPU6500_RA_ZA_OFFSET_L      0x7E
+
+#define MPU6500_TC_PWR_MODE_BIT     7
+#define MPU6500_TC_OFFSET_BIT       6
+#define MPU6500_TC_OFFSET_LENGTH    6
+#define MPU6500_TC_OTP_BNK_VLD_BIT  0
+
+#define MPU6500_VDDIO_LEVEL_VLOGIC  0
+#define MPU6500_VDDIO_LEVEL_VDD     1
+
+#define MPU6500_CFG_EXT_SYNC_SET_BIT    5
+#define MPU6500_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU6500_CFG_DLPF_CFG_BIT    2
+#define MPU6500_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU6500_EXT_SYNC_DISABLED       0x0
+#define MPU6500_EXT_SYNC_TEMP_OUT_L     0x1
+#define MPU6500_EXT_SYNC_GYRO_XOUT_L    0x2
+#define MPU6500_EXT_SYNC_GYRO_YOUT_L    0x3
+#define MPU6500_EXT_SYNC_GYRO_ZOUT_L    0x4
+#define MPU6500_EXT_SYNC_ACCEL_XOUT_L   0x5
+#define MPU6500_EXT_SYNC_ACCEL_YOUT_L   0x6
+#define MPU6500_EXT_SYNC_ACCEL_ZOUT_L   0x7
+
+#define MPU6500_DLPF_BW_256         0x00
+#define MPU6500_DLPF_BW_188         0x01
+#define MPU6500_DLPF_BW_98          0x02
+#define MPU6500_DLPF_BW_42          0x03
+#define MPU6500_DLPF_BW_20          0x04
+#define MPU6500_DLPF_BW_10          0x05
+#define MPU6500_DLPF_BW_5           0x06
+
+#define MPU6500_GCONFIG_XG_ST_BIT       7
+#define MPU6500_GCONFIG_YG_ST_BIT       6
+#define MPU6500_GCONFIG_ZG_ST_BIT       5
+#define MPU6500_GCONFIG_FS_SEL_BIT      4
+#define MPU6500_GCONFIG_FS_SEL_LENGTH   2
+
+
+#define MPU6500_GYRO_FS_250         0x00
+#define MPU6500_GYRO_FS_500         0x01
+#define MPU6500_GYRO_FS_1000        0x02
+#define MPU6500_GYRO_FS_2000        0x03
+
+#define MPU6500_ACONFIG_XA_ST_BIT           7
+#define MPU6500_ACONFIG_YA_ST_BIT           6
+#define MPU6500_ACONFIG_ZA_ST_BIT           5
+#define MPU6500_ACONFIG_AFS_SEL_BIT         4
+#define MPU6500_ACONFIG_AFS_SEL_LENGTH      2
+#define MPU6500_ACONFIG_ACCEL_HPF_BIT       2
+#define MPU6500_ACONFIG_ACCEL_HPF_LENGTH    3
+
+#define MPU6500_ACONFIG2_FCHOICE_B_BIT      2
+#define MPU6500_ACONFIG2_FCHOICE_B_LENGTH   2
+#define MPU6500_ACONFIG2_DLPF_BIT           0
+#define MPU6500_ACONFIG2_DLPF_LENGTH        2
+
+#define MPU6500_ACCEL_DLPF_BW_460   0x00
+#define MPU6500_ACCEL_DLPF_BW_184   0x01
+#define MPU6500_ACCEL_DLPF_BW_92    0x02
+#define MPU6500_ACCEL_DLPF_BW_41    0x03
+#define MPU6500_ACCEL_DLPF_BW_20    0x04
+#define MPU6500_ACCEL_DLPF_BW_10    0x05
+#define MPU6500_ACCEL_DLPF_BW_5     0x06
+
+#define MPU6500_ACCEL_FS_2          0x00
+#define MPU6500_ACCEL_FS_4          0x01
+#define MPU6500_ACCEL_FS_8          0x02
+#define MPU6500_ACCEL_FS_16         0x03
+
+#define MPU6500_DHPF_RESET          0x00
+#define MPU6500_DHPF_5              0x01
+#define MPU6500_DHPF_2P5            0x02
+#define MPU6500_DHPF_1P25           0x03
+#define MPU6500_DHPF_0P63           0x04
+#define MPU6500_DHPF_HOLD           0x07
+
+#define MPU6500_TEMP_FIFO_EN_BIT    7
+#define MPU6500_XG_FIFO_EN_BIT      6
+#define MPU6500_YG_FIFO_EN_BIT      5
+#define MPU6500_ZG_FIFO_EN_BIT      4
+#define MPU6500_ACCEL_FIFO_EN_BIT   3
+#define MPU6500_SLV2_FIFO_EN_BIT    2
+#define MPU6500_SLV1_FIFO_EN_BIT    1
+#define MPU6500_SLV0_FIFO_EN_BIT    0
+
+#define MPU6500_MULT_MST_EN_BIT     7
+#define MPU6500_WAIT_FOR_ES_BIT     6
+#define MPU6500_SLV_3_FIFO_EN_BIT   5
+#define MPU6500_I2C_MST_P_NSR_BIT   4
+#define MPU6500_I2C_MST_CLK_BIT     3
+#define MPU6500_I2C_MST_CLK_LENGTH  4
+
+#define MPU6500_CLOCK_DIV_348       0x0
+#define MPU6500_CLOCK_DIV_333       0x1
+#define MPU6500_CLOCK_DIV_320       0x2
+#define MPU6500_CLOCK_DIV_308       0x3
+#define MPU6500_CLOCK_DIV_296       0x4
+#define MPU6500_CLOCK_DIV_286       0x5
+#define MPU6500_CLOCK_DIV_276       0x6
+#define MPU6500_CLOCK_DIV_267       0x7
+#define MPU6500_CLOCK_DIV_258       0x8
+#define MPU6500_CLOCK_DIV_500       0x9
+#define MPU6500_CLOCK_DIV_471       0xA
+#define MPU6500_CLOCK_DIV_444       0xB
+#define MPU6500_CLOCK_DIV_421       0xC
+#define MPU6500_CLOCK_DIV_400       0xD
+#define MPU6500_CLOCK_DIV_381       0xE
+#define MPU6500_CLOCK_DIV_364       0xF
+
+#define MPU6500_I2C_SLV_RW_BIT      7
+#define MPU6500_I2C_SLV_ADDR_BIT    6
+#define MPU6500_I2C_SLV_ADDR_LENGTH 7
+#define MPU6500_I2C_SLV_EN_BIT      7
+#define MPU6500_I2C_SLV_BYTE_SW_BIT 6
+#define MPU6500_I2C_SLV_REG_DIS_BIT 5
+#define MPU6500_I2C_SLV_GRP_BIT     4
+#define MPU6500_I2C_SLV_LEN_BIT     3
+#define MPU6500_I2C_SLV_LEN_LENGTH  4
+
+#define MPU6500_I2C_SLV4_RW_BIT         7
+#define MPU6500_I2C_SLV4_ADDR_BIT       6
+#define MPU6500_I2C_SLV4_ADDR_LENGTH    7
+#define MPU6500_I2C_SLV4_EN_BIT         7
+#define MPU6500_I2C_SLV4_INT_EN_BIT     6
+#define MPU6500_I2C_SLV4_REG_DIS_BIT    5
+#define MPU6500_I2C_SLV4_MST_DLY_BIT    4
+#define MPU6500_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU6500_MST_PASS_THROUGH_BIT    7
+#define MPU6500_MST_I2C_SLV4_DONE_BIT   6
+#define MPU6500_MST_I2C_LOST_ARB_BIT    5
+#define MPU6500_MST_I2C_SLV4_NACK_BIT   4
+#define MPU6500_MST_I2C_SLV3_NACK_BIT   3
+#define MPU6500_MST_I2C_SLV2_NACK_BIT   2
+#define MPU6500_MST_I2C_SLV1_NACK_BIT   1
+#define MPU6500_MST_I2C_SLV0_NACK_BIT   0
+
+#define MPU6500_INTCFG_INT_LEVEL_BIT        7
+#define MPU6500_INTCFG_INT_OPEN_BIT         6
+#define MPU6500_INTCFG_LATCH_INT_EN_BIT     5
+#define MPU6500_INTCFG_INT_RD_CLEAR_BIT     4
+#define MPU6500_INTCFG_FSYNC_INT_LEVEL_BIT  3
+#define MPU6500_INTCFG_FSYNC_INT_EN_BIT     2
+#define MPU6500_INTCFG_I2C_BYPASS_EN_BIT    1
+#define MPU6500_INTCFG_CLKOUT_EN_BIT        0
+
+#define MPU6500_INTMODE_ACTIVEHIGH  0x00
+#define MPU6500_INTMODE_ACTIVELOW   0x01
+
+#define MPU6500_INTDRV_PUSHPULL     0x00
+#define MPU6500_INTDRV_OPENDRAIN    0x01
+
+#define MPU6500_INTLATCH_50USPULSE  0x00
+#define MPU6500_INTLATCH_WAITCLEAR  0x01
+
+#define MPU6500_INTCLEAR_STATUSREAD 0x00
+#define MPU6500_INTCLEAR_ANYREAD    0x01
+
+#define MPU6500_INTERRUPT_FF_BIT            7
+#define MPU6500_INTERRUPT_MOT_BIT           6
+#define MPU6500_INTERRUPT_ZMOT_BIT          5
+#define MPU6500_INTERRUPT_FIFO_OFLOW_BIT    4
+#define MPU6500_INTERRUPT_I2C_MST_INT_BIT   3
+#define MPU6500_INTERRUPT_PLL_RDY_INT_BIT   2
+#define MPU6500_INTERRUPT_DMP_INT_BIT       1
+#define MPU6500_INTERRUPT_DATA_RDY_BIT      0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU6500_DMPINT_5_BIT            5
+#define MPU6500_DMPINT_4_BIT            4
+#define MPU6500_DMPINT_3_BIT            3
+#define MPU6500_DMPINT_2_BIT            2
+#define MPU6500_DMPINT_1_BIT            1
+#define MPU6500_DMPINT_0_BIT            0
+
+#define MPU6500_MOTION_MOT_XNEG_BIT     7
+#define MPU6500_MOTION_MOT_XPOS_BIT     6
+#define MPU6500_MOTION_MOT_YNEG_BIT     5
+#define MPU6500_MOTION_MOT_YPOS_BIT     4
+#define MPU6500_MOTION_MOT_ZNEG_BIT     3
+#define MPU6500_MOTION_MOT_ZPOS_BIT     2
+#define MPU6500_MOTION_MOT_ZRMOT_BIT    0
+
+#define MPU6500_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
+#define MPU6500_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
+#define MPU6500_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
+#define MPU6500_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
+#define MPU6500_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
+#define MPU6500_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
+
+#define MPU6500_PATHRESET_GYRO_RESET_BIT    2
+#define MPU6500_PATHRESET_ACCEL_RESET_BIT   1
+#define MPU6500_PATHRESET_TEMP_RESET_BIT    0
+
+#define MPU6500_DETECT_ACCEL_ON_DELAY_BIT       5
+#define MPU6500_DETECT_ACCEL_ON_DELAY_LENGTH    2
+#define MPU6500_DETECT_FF_COUNT_BIT             3
+#define MPU6500_DETECT_FF_COUNT_LENGTH          2
+#define MPU6500_DETECT_MOT_COUNT_BIT            1
+#define MPU6500_DETECT_MOT_COUNT_LENGTH         2
+
+#define MPU6500_DETECT_DECREMENT_RESET  0x0
+#define MPU6500_DETECT_DECREMENT_1      0x1
+#define MPU6500_DETECT_DECREMENT_2      0x2
+#define MPU6500_DETECT_DECREMENT_4      0x3
+
+#define MPU6500_USERCTRL_DMP_EN_BIT             7
+#define MPU6500_USERCTRL_FIFO_EN_BIT            6
+#define MPU6500_USERCTRL_I2C_MST_EN_BIT         5
+#define MPU6500_USERCTRL_I2C_IF_DIS_BIT         4
+#define MPU6500_USERCTRL_DMP_RESET_BIT          3
+#define MPU6500_USERCTRL_FIFO_RESET_BIT         2
+#define MPU6500_USERCTRL_I2C_MST_RESET_BIT      1
+#define MPU6500_USERCTRL_SIG_COND_RESET_BIT     0
+
+#define MPU6500_PWR1_DEVICE_RESET_BIT   7
+#define MPU6500_PWR1_SLEEP_BIT          6
+#define MPU6500_PWR1_CYCLE_BIT          5
+#define MPU6500_PWR1_TEMP_DIS_BIT       3
+#define MPU6500_PWR1_CLKSEL_BIT         2
+#define MPU6500_PWR1_CLKSEL_LENGTH      3
+
+#define MPU6500_CLOCK_INTERNAL          0x00
+#define MPU6500_CLOCK_PLL_XGYRO         0x01
+#define MPU6500_CLOCK_PLL_YGYRO         0x02
+#define MPU6500_CLOCK_PLL_ZGYRO         0x03
+#define MPU6500_CLOCK_PLL_EXT32K        0x04
+#define MPU6500_CLOCK_PLL_EXT19M        0x05
+#define MPU6500_CLOCK_KEEP_RESET        0x07
+
+#define MPU6500_PWR2_LP_WAKE_CTRL_BIT       7
+#define MPU6500_PWR2_LP_WAKE_CTRL_LENGTH    2
+#define MPU6500_PWR2_STBY_XA_BIT            5
+#define MPU6500_PWR2_STBY_YA_BIT            4
+#define MPU6500_PWR2_STBY_ZA_BIT            3
+#define MPU6500_PWR2_STBY_XG_BIT            2
+#define MPU6500_PWR2_STBY_YG_BIT            1
+#define MPU6500_PWR2_STBY_ZG_BIT            0
+
+#define MPU6500_WAKE_FREQ_1P25      0x0
+#define MPU6500_WAKE_FREQ_2P5       0x1
+#define MPU6500_WAKE_FREQ_5         0x2
+#define MPU6500_WAKE_FREQ_10        0x3
+
+#define MPU6500_BANKSEL_PRFTCH_EN_BIT       6
+#define MPU6500_BANKSEL_CFG_USER_BANK_BIT   5
+#define MPU6500_BANKSEL_MEM_SEL_BIT         4
+#define MPU6500_BANKSEL_MEM_SEL_LENGTH      5
+
+#define MPU6500_WHO_AM_I_BIT        6
+#define MPU6500_WHO_AM_I_LENGTH     6
+
+#define MPU6500_DMP_MEMORY_BANKS        8
+#define MPU6500_DMP_MEMORY_BANK_SIZE    256
+#define MPU6500_DMP_MEMORY_CHUNK_SIZE   16
+
+#define MPU6500_DEG_PER_LSB_250  (float)((2 * 250.0) / 65536.0)
+#define MPU6500_DEG_PER_LSB_500  (float)((2 * 500.0) / 65536.0)
+#define MPU6500_DEG_PER_LSB_1000 (float)((2 * 1000.0) / 65536.0)
+#define MPU6500_DEG_PER_LSB_2000 (float)((2 * 2000.0) / 65536.0)
+
+#define MPU6500_G_PER_LSB_2      (float)((2 * 2) / 65536.0)
+#define MPU6500_G_PER_LSB_4      (float)((2 * 4) / 65536.0)
+#define MPU6500_G_PER_LSB_8      (float)((2 * 8) / 65536.0)
+#define MPU6500_G_PER_LSB_16     (float)((2 * 16) / 65536.0)
+
+// Test limits
+#define MPU6500_ST_GYRO_LOW      (-14.0)  // %
+#define MPU6500_ST_GYRO_HIGH     14.0  // %
+#define MPU6500_ST_ACCEL_LOW     (-14.0)  // %
+#define MPU6500_ST_ACCEL_HIGH    14.0  // %
+
+// note: DMP code memory blocks defined at end of header file
+
+void mpu6500Init(I2C_Dev *i2cPort);
+bool mpu6500Test(void);
+
+bool mpu6500TestConnection();
+bool mpu6500EvaluateSelfTest(float low, float high, float value, char* string);
+bool mpu6500SelfTest();
+
+
+// AUX_VDDIO register
+uint8_t mpu6500GetAuxVDDIOLevel();
+void mpu6500SetAuxVDDIOLevel(uint8_t level);
+
+// SMPLRT_DIV register
+uint8_t mpu6500GetRate();
+void mpu6500SetRate(uint8_t rate);
+
+// CONFIG register
+uint8_t mpu6500GetExternalFrameSync();
+void mpu6500SetExternalFrameSync(uint8_t sync);
+uint8_t mpu6500GetDLPFMode();
+void mpu6500SetDLPFMode(uint8_t bandwidth);
+
+// GYRO_CONFIG register
+void mpu6500SetGyroXSelfTest(bool enabled);
+void mpu6500SetGyroYSelfTest(bool enabled);
+void mpu6500SetGyroZSelfTest(bool enabled);
+uint8_t mpu6500GetFullScaleGyroRangeId();
+float mpu6500GetFullScaleGyroDPL();
+void mpu6500SetFullScaleGyroRange(uint8_t range);
+
+// ACCEL_CONFIG register
+bool mpu6500GetAccelXSelfTest();
+void mpu6500SetAccelXSelfTest(bool enabled);
+bool mpu6500GetAccelYSelfTest();
+void mpu6500SetAccelYSelfTest(bool enabled);
+bool mpu6500GetAccelZSelfTest();
+void mpu6500SetAccelZSelfTest(bool enabled);
+uint8_t mpu6500GetFullScaleAccelRangeId();
+void mpu6500SetFullScaleAccelRange(uint8_t range);
+float mpu6500GetFullScaleAccelGPL();
+uint8_t mpu6500GetDHPFMode();
+void mpu6500SetDHPFMode(uint8_t mode);
+
+// ACCEL_CONFIG2 register
+void mpu6500SetAccelDLPF(uint8_t range);
+
+// FF_THR register
+uint8_t mpu6500GetFreefallDetectionThreshold();
+void mpu6500SetFreefallDetectionThreshold(uint8_t threshold);
+
+// FF_DUR register
+uint8_t mpu6500GetFreefallDetectionDuration();
+void mpu6500SetFreefallDetectionDuration(uint8_t duration);
+
+// MOT_THR register
+uint8_t mpu6500GetMotionDetectionThreshold();
+void mpu6500SetMotionDetectionThreshold(uint8_t threshold);
+
+// MOT_DUR register
+uint8_t mpu6500GetMotionDetectionDuration();
+void mpu6500SetMotionDetectionDuration(uint8_t duration);
+
+// ZRMOT_THR register
+uint8_t mpu6500GetZeroMotionDetectionThreshold();
+void mpu6500SetZeroMotionDetectionThreshold(uint8_t threshold);
+
+// ZRMOT_DUR register
+uint8_t mpu6500GetZeroMotionDetectionDuration();
+void mpu6500SetZeroMotionDetectionDuration(uint8_t duration);
+
+// FIFO_EN register
+bool mpu6500GetTempFIFOEnabled();
+void mpu6500SetTempFIFOEnabled(bool enabled);
+bool mpu6500GetXGyroFIFOEnabled();
+void mpu6500SetXGyroFIFOEnabled(bool enabled);
+bool mpu6500GetYGyroFIFOEnabled();
+void mpu6500SetYGyroFIFOEnabled(bool enabled);
+bool mpu6500GetZGyroFIFOEnabled();
+void mpu6500SetZGyroFIFOEnabled(bool enabled);
+bool mpu6500GetAccelFIFOEnabled();
+void mpu6500SetAccelFIFOEnabled(bool enabled);
+bool mpu6500GetSlave2FIFOEnabled();
+void mpu6500SetSlave2FIFOEnabled(bool enabled);
+bool mpu6500GetSlave1FIFOEnabled();
+void mpu6500SetSlave1FIFOEnabled(bool enabled);
+bool mpu6500GetSlave0FIFOEnabled();
+void mpu6500SetSlave0FIFOEnabled(bool enabled);
+
+// I2C_MST_CTRL register
+bool mpu6500GetMultiMasterEnabled();
+void mpu6500SetMultiMasterEnabled(bool enabled);
+bool mpu6500GetWaitForExternalSensorEnabled();
+void mpu6500SetWaitForExternalSensorEnabled(bool enabled);
+bool mpu6500GetSlave3FIFOEnabled();
+void mpu6500SetSlave3FIFOEnabled(bool enabled);
+bool mpu6500GetSlaveReadWriteTransitionEnabled();
+void mpu6500SetSlaveReadWriteTransitionEnabled(bool enabled);
+uint8_t mpu6500GetMasterClockSpeed();
+void mpu6500SetMasterClockSpeed(uint8_t speed);
+
+// I2C_SLV* registers (Slave 0-3)
+uint8_t mpu6500GetSlaveAddress(uint8_t num);
+void mpu6500SetSlaveAddress(uint8_t num, uint8_t address);
+uint8_t mpu6500GetSlaveRegister(uint8_t num);
+void mpu6500SetSlaveRegister(uint8_t num, uint8_t reg);
+bool mpu6500GetSlaveEnabled(uint8_t num);
+void mpu6500SetSlaveEnabled(uint8_t num, bool enabled);
+bool mpu6500GetSlaveWordByteSwap(uint8_t num);
+void mpu6500SetSlaveWordByteSwap(uint8_t num, bool enabled);
+bool mpu6500GetSlaveWriteMode(uint8_t num);
+void mpu6500SetSlaveWriteMode(uint8_t num, bool mode);
+bool mpu6500GetSlaveWordGroupOffset(uint8_t num);
+void mpu6500setSlaveWordGroupOffset(uint8_t num, bool enabled);
+uint8_t mpu6500GetSlaveDataLength(uint8_t num);
+void mpu6500SetSlaveDataLength(uint8_t num, uint8_t length);
+
+// I2C_SLV* registers (Slave 4)
+uint8_t mpu6500GetSlave4Address();
+void mpu6500SetSlave4Address(uint8_t address);
+uint8_t mpu6500GetSlave4Register();
+void mpu6500SetSlave4Register(uint8_t reg);
+void mpu6500SetSlave4OutputByte(uint8_t data);
+bool mpu6500GetSlave4Enabled();
+void mpu6500SetSlave4Enabled(bool enabled);
+bool mpu6500GetSlave4InterruptEnabled();
+void mpu6500SetSlave4InterruptEnabled(bool enabled);
+bool mpu6500GetSlave4WriteMode();
+void mpu6500SetSlave4WriteMode(bool mode);
+uint8_t mpu6500GetSlave4MasterDelay();
+void mpu6500SetSlave4MasterDelay(uint8_t delay);
+uint8_t mpu6500GetSlave4InputByte();
+
+// I2C_MST_STATUS register
+bool mpu6500GetPassthroughStatus();
+bool mpu6500GetSlave4IsDone();
+bool mpu6500GetLostArbitration();
+bool mpu6500GetSlave4Nack();
+bool mpu6500GetSlave3Nack();
+bool mpu6500GetSlave2Nack();
+bool mpu6500GetSlave1Nack();
+bool mpu6500GetSlave0Nack();
+
+// INT_PIN_CFG register
+bool mpu6500GetInterruptMode();
+void mpu6500SetInterruptMode(bool mode);
+bool mpu6500GetInterruptDrive();
+void mpu6500SetInterruptDrive(bool drive);
+bool mpu6500GetInterruptLatch();
+void mpu6500SetInterruptLatch(bool latch);
+bool mpu6500GetInterruptLatchClear();
+void mpu6500SetInterruptLatchClear(bool clear);
+bool mpu6500GetFSyncInterruptLevel();
+void mpu6500SetFSyncInterruptLevel(bool level);
+bool mpu6500GetFSyncInterruptEnabled();
+void mpu6500SetFSyncInterruptEnabled(bool enabled);
+bool mpu6500GetI2CBypassEnabled();
+void mpu6500SetI2CBypassEnabled(bool enabled);
+bool mpu6500GetClockOutputEnabled();
+void mpu6500SetClockOutputEnabled(bool enabled);
+
+// INT_ENABLE register
+uint8_t mpu6500GetIntEnabled();
+void mpu6500SetIntEnabled(uint8_t enabled);
+bool mpu6500GetIntFreefallEnabled();
+void mpu6500SetIntFreefallEnabled(bool enabled);
+bool mpu6500GetIntMotionEnabled();
+void mpu6500SetIntMotionEnabled(bool enabled);
+bool mpu6500GetIntZeroMotionEnabled();
+void mpu6500SetIntZeroMotionEnabled(bool enabled);
+bool mpu6500GetIntFIFOBufferOverflowEnabled();
+void mpu6500SetIntFIFOBufferOverflowEnabled(bool enabled);
+bool mpu6500GetIntI2CMasterEnabled();
+void mpu6500SetIntI2CMasterEnabled(bool enabled);
+bool mpu6500GetIntDataReadyEnabled();
+void mpu6500SetIntDataReadyEnabled(bool enabled);
+
+// INT_STATUS register
+uint8_t mpu6500GetIntStatus();
+bool mpu6500GetIntFreefallStatus();
+bool mpu6500GetIntMotionStatus();
+bool mpu6500GetIntZeroMotionStatus();
+bool mpu6500GetIntFIFOBufferOverflowStatus();
+bool mpu6500GetIntI2CMasterStatus();
+bool mpu6500GetIntDataReadyStatus();
+
+// ACCEL_*OUT_* registers
+void mpu6500GetMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+void mpu6500GetMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+void mpu6500GetAcceleration(int16_t* x, int16_t* y, int16_t* z);
+int16_t mpu6500GetAccelerationX();
+int16_t mpu6500GetAccelerationY();
+int16_t mpu6500GetAccelerationZ();
+
+// TEMP_OUT_* registers
+int16_t mpu6500GetTemperature();
+
+// GYRO_*OUT_* registers
+void mpu6500GetRotation(int16_t* x, int16_t* y, int16_t* z);
+int16_t mpu6500GetRotationX();
+int16_t mpu6500GetRotationY();
+int16_t mpu6500GetRotationZ();
+
+// EXT_SENS_DATA_* registers
+uint8_t mpu6500GetExternalSensorByte(int position);
+uint16_t mpu6500GetExternalSensorWord(int position);
+uint32_t mpu6500GetExternalSensorDWord(int position);
+
+// MOT_DETECT_STATUS register
+bool mpu6500GetXNegMotionDetected();
+bool mpu6500GetXPosMotionDetected();
+bool mpu6500GetYNegMotionDetected();
+bool mpu6500GetYPosMotionDetected();
+bool mpu6500GetZNegMotionDetected();
+bool mpu6500GetZPosMotionDetected();
+bool mpu6500GetZeroMotionDetected();
+
+// I2C_SLV*_DO register
+void mpu6500SetSlaveOutputByte(uint8_t num, uint8_t data);
+
+// I2C_MST_DELAY_CTRL register
+bool mpu6500GetExternalShadowDelayEnabled();
+void mpu6500SetExternalShadowDelayEnabled(bool enabled);
+bool mpu6500GetSlaveDelayEnabled(uint8_t num);
+void mpu6500SetSlaveDelayEnabled(uint8_t num, bool enabled);
+
+// SIGNAL_PATH_RESET register
+void rempu6500SetGyroscopePath();
+void rempu6500SetAccelerometerPath();
+void rempu6500SetTemperaturePath();
+
+// MOT_DETECT_CTRL register
+uint8_t mpu6500GetAccelerometerPowerOnDelay();
+void mpu6500SetAccelerometerPowerOnDelay(uint8_t delay);
+uint8_t mpu6500GetFreefallDetectionCounterDecrement();
+void mpu6500SetFreefallDetectionCounterDecrement(uint8_t decrement);
+uint8_t mpu6500GetMotionDetectionCounterDecrement();
+void mpu6500SetMotionDetectionCounterDecrement(uint8_t decrement);
+
+// USER_CTRL register
+bool mpu6500GetFIFOEnabled();
+void mpu6500SetFIFOEnabled(bool enabled);
+bool mpu6500GetI2CMasterModeEnabled();
+void mpu6500SetI2CMasterModeEnabled(bool enabled);
+void mpu6500SwitchSPIEnabled(bool enabled);
+void mpu6500ResetFIFO();
+void mpu6500ResetI2CMaster();
+void mpu6500ResetSensors();
+
+// PWR_MGMT_1 register
+void mpu6500Reset();
+bool mpu6500GetSleepEnabled();
+void mpu6500SetSleepEnabled(bool enabled);
+bool mpu6500GetWakeCycleEnabled();
+void mpu6500SetWakeCycleEnabled(bool enabled);
+bool mpu6500GetTempSensorEnabled();
+void mpu6500SetTempSensorEnabled(bool enabled);
+uint8_t mpu6500GetClockSource();
+void mpu6500SetClockSource(uint8_t source);
+
+// PWR_MGMT_2 register
+uint8_t mpu6500GetWakeFrequency();
+void mpu6500SetWakeFrequency(uint8_t frequency);
+bool mpu6500GetStandbyXAccelEnabled();
+void mpu6500SetStandbyXAccelEnabled(bool enabled);
+bool mpu6500GetStandbyYAccelEnabled();
+void mpu6500SetStandbyYAccelEnabled(bool enabled);
+bool mpu6500GetStandbyZAccelEnabled();
+void mpu6500SetStandbyZAccelEnabled(bool enabled);
+bool mpu6500GetStandbyXGyroEnabled();
+void mpu6500SetStandbyXGyroEnabled(bool enabled);
+bool mpu6500GetStandbyYGyroEnabled();
+void mpu6500SetStandbyYGyroEnabled(bool enabled);
+bool mpu6500GetStandbyZGyroEnabled();
+void mpu6500SetStandbyZGyroEnabled(bool enabled);
+
+// FIFO_COUNT_* registers
+uint16_t mpu6500GetFIFOCount();
+
+// FIFO_R_W register
+uint8_t mpu6500GetFIFOByte();
+void mpu6500SetFIFOByte(uint8_t data);
+void mpu6500GetFIFOBytes(uint8_t *data, uint8_t length);
+
+// WHO_AM_I register
+uint8_t mpu6500GetDeviceID();
+void mpu6500SetDeviceID(uint8_t id);
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+uint8_t mpu6500GetOTPBankValid();
+void mpu6500SetOTPBankValid(bool enabled);
+int8_t mpu6500GetXGyroOffset();
+void mpu6500SetXGyroOffset(int8_t offset);
+
+// YG_OFFS_TC register
+int8_t mpu6500GetYGyroOffset();
+void mpu6500SetYGyroOffset(int8_t offset);
+
+// ZG_OFFS_TC register
+int8_t mpu6500GetZGyroOffset();
+void  mpu6500SetGyroOffset(int8_t offset);
+
+// X_FINE_GAIN register
+int8_t mpu6500GetXFineGain();
+void mpu6500SetXFineGain(int8_t gain);
+
+// Y_FINE_GAIN register
+int8_t mpu6500GetYFineGain();
+void mpu6500SetYFineGain(int8_t gain);
+
+// Z_FINE_GAIN register
+int8_t mpu6500GetZFineGain();
+void mpu6500SetZFineGain(int8_t gain);
+
+// XA_OFFS_* registers
+int16_t mpu6500GetXAccelOffset();
+void mpu6500SetXAccelOffset(int16_t offset);
+
+// YA_OFFS_* register
+int16_t mpu6500GetYAccelOffset();
+void mpu6500SetYAccelOffset(int16_t offset);
+
+// ZA_OFFS_* register
+int16_t mpu6500GetZAccelOffset();
+void mpu6500SetZAccelOffset(int16_t offset);
+
+// XG_OFFS_USR* registers
+int16_t mpu6500GetXGyroOffsetUser();
+void mpu6500SetXGyroOffsetUser(int16_t offset);
+
+// YG_OFFS_USR* register
+int16_t mpu6500GetYGyroOffsetUser();
+void mpu6500SetYGyroOffsetUser(int16_t offset);
+
+// ZG_OFFS_USR* register
+int16_t mpu6500GetZGyroOffsetUser();
+void mpu6500SetZGyroOffsetUser(int16_t offset);
+
+// INT_ENABLE register (DMP functions)
+bool mpu6500GetIntPLLReadyEnabled();
+void mpu6500SetIntPLLReadyEnabled(bool enabled);
+bool mpu6500GetIntDMPEnabled();
+void mpu6500SetIntDMPEnabled(bool enabled);
+
+// DMP_INT_STATUS
+bool mpu6500GetDMPInt5Status();
+bool mpu6500GetDMPInt4Status();
+bool mpu6500GetDMPInt3Status();
+bool mpu6500GetDMPInt2Status();
+bool mpu6500GetDMPInt1Status();
+bool mpu6500GetDMPInt0Status();
+
+// INT_STATUS register (DMP functions)
+bool mpu6500GetIntPLLReadyStatus();
+bool mpu6500GetIntDMPStatus();
+
+// USER_CTRL register (DMP functions)
+bool mpu6500GetDMPEnabled();
+void mpu6500SetDMPEnabled(bool enabled);
+void mpu6500ResetDMP();
+
+// BANK_SEL register
+void mpu6500SetMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank);
+
+// MEM_START_ADDR register
+void mpu6500SetMemoryStartAddress(uint8_t address);
+
+// MEM_R_W register
+uint8_t mpu6500ReadMemoryByte();
+void mpu6500WriteMemoryByte(uint8_t data);
+void mpu6500ReadMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address);
+bool mpu6500WriteMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify);
+bool mpu6500WriteProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify);
+
+bool mpu6500WriteDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+bool mpu6500WiteProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+// DMP_CFG_1 register
+uint8_t mpu6500GetDMPConfig1();
+void mpu6500SetDMPConfig1(uint8_t config);
+
+// DMP_CFG_2 register
+uint8_t mpu6500GetDMPConfig2();
+void mpu6500SetDMPConfig2(uint8_t config);
+
+
+#ifdef MPU6500_INCLUDE_DMP_MOTIONAPPS20
+    /* This is only included if you want it, since it eats about 2K of program
+     * memory, which is a waste if you aren't using the DMP (or if you aren't
+     * using this particular flavor of DMP).
+     *
+     * Source is from the InvenSense MotionApps v2 demo code. Original source is
+     * unavailable, unless you happen to be amazing as decompiling binary by
+     * hand (in which case, please contact me, and I'm totally serious).
+     *
+     * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the
+     * DMP reverse-engineering he did to help make this bit of wizardry
+     * possible.
+     */
+
+    #define MPU6500_DMP_CODE_SIZE 1929
+
+    // this block of memory gets written to the MPU on start-up, and it seems
+    // to be volatile memory, so it has to be done each time (it only takes ~1
+    // second though)
+    const prog_uchar dmpMemory[MPU6500_DMP_CODE_SIZE] PROGMEM = {
+        // bank 0, 256 bytes
+        0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+        0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+        0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+        0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+        0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+        0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+        0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+        0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+        0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+        // bank 1, 256 bytes
+        0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+        0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+        0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+        0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+
+        // bank 2, 256 bytes
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+        0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+        0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+        // bank 3, 256 bytes
+        0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F,
+        0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2,
+        0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF,
+        0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C,
+        0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1,
+        0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01,
+        0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80,
+        0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C,
+        0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80,
+        0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E,
+        0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9,
+        0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24,
+        0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0,
+        0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86,
+        0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+        0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+
+        // bank 4, 256 bytes
+        0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+        0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+        0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+        0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+        0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+        0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+        0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+        0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+        0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+        0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+        0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+        0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+        0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+        0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+        0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+        0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+
+        // bank 5, 256 bytes
+        0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+        0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+        0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+        0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+        0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+        0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+        0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+        0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+        0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A,
+        0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60,
+        0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97,
+        0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04,
+        0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78,
+        0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79,
+        0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68,
+        0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68,
+
+        // bank 6, 256 bytes
+        0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04,
+        0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66,
+        0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31,
+        0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60,
+        0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76,
+        0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56,
+        0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD,
+        0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91,
+        0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8,
+        0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE,
+        0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9,
+        0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD,
+        0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E,
+        0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8,
+        0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89,
+        0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79,
+
+        // bank 7, 138 bytes (remainder)
+        0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8,
+        0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA,
+        0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB,
+        0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3,
+        0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3,
+        0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+        0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3,
+        0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC,
+        0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+    };
+
+    #define MPU6500_DMP_CONFIG_SIZE 192
+
+    // thanks to Noah Zerkin for piecing this stuff together!
+    const prog_uchar dmpConfig[MPU6500_DMP_CONFIG_SIZE] PROGMEM = {
+    //  BANK    OFFSET  LENGTH  [DATA]
+        0x03,   0x7B,   0x03,   0x4C, 0xCD, 0x6C,         // FCFG_1 inv_set_gyro_calibration
+        0x03,   0xAB,   0x03,   0x36, 0x56, 0x76,         // FCFG_3 inv_set_gyro_calibration
+        0x00,   0x68,   0x04,   0x02, 0xCB, 0x47, 0xA2,   // D_0_104 inv_set_gyro_calibration
+        0x02,   0x18,   0x04,   0x00, 0x05, 0x8B, 0xC1,   // D_0_24 inv_set_gyro_calibration
+        0x01,   0x0C,   0x04,   0x00, 0x00, 0x00, 0x00,   // D_1_152 inv_set_accel_calibration
+        0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_accel_calibration
+        0x03,   0x89,   0x03,   0x26, 0x46, 0x66,         // FCFG_7 inv_set_accel_calibration
+        0x00,   0x6C,   0x02,   0x20, 0x00,               // D_0_108 inv_set_accel_calibration
+        0x02,   0x40,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_00 inv_set_compass_calibration
+        0x02,   0x44,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_01
+        0x02,   0x48,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_02
+        0x02,   0x4C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_10
+        0x02,   0x50,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_11
+        0x02,   0x54,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_12
+        0x02,   0x58,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_20
+        0x02,   0x5C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_21
+        0x02,   0xBC,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_22
+        0x01,   0xEC,   0x04,   0x00, 0x00, 0x40, 0x00,   // D_1_236 inv_apply_endian_accel
+        0x03,   0x7F,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+        0x04,   0x02,   0x03,   0x0D, 0x35, 0x5D,         // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+        0x04,   0x09,   0x04,   0x87, 0x2D, 0x35, 0x3D,   // FCFG_5 inv_set_bias_update
+        0x00,   0xA3,   0x01,   0x00,                     // D_0_163 inv_set_dead_zone
+                     // SPECIAL 0x01 = enable interrupts
+        0x00,   0x00,   0x00,   0x01, // SET INT_ENABLE at i=22, SPECIAL INSTRUCTION
+        0x07,   0x86,   0x01,   0xFE,                     // CFG_6 inv_set_fifo_interupt
+        0x07,   0x41,   0x05,   0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+        0x07,   0x7E,   0x01,   0x30,                     // CFG_16 inv_set_footer
+        0x07,   0x46,   0x01,   0x9A,                     // CFG_GYRO_SOURCE inv_send_gyro
+        0x07,   0x47,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_9 inv_send_gyro -> inv_construct3_fifo
+        0x07,   0x6C,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_12 inv_send_accel -> inv_construct3_fifo
+        0x02,   0x16,   0x02,   0x00, 0x0A                // D_0_22 inv_set_fifo_rate
+    };
+
+#endif
+
+#endif /* _MPU6500_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/ms5611.h b/crazyflie-firmware-src/src/drivers/interface/ms5611.h
new file mode 100644
index 0000000000000000000000000000000000000000..1e9e20bf9d5b377bbcce432949584d6b13dae7ff
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/ms5611.h
@@ -0,0 +1,91 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011 Fabio Varesano <fvaresano@yahoo.it>
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file ms5611.h
+ * Driver for the ms5611 pressure sensor from measurement specialties.
+ * Datasheet at http://www.meas-spec.com/downloads/MS5611-01BA03.pdf
+ *
+ */
+#ifndef MS5611_H
+#define MS5611_H
+
+#include <stdbool.h>
+#include "i2cdev.h"
+
+// addresses of the device
+#define MS5611_ADDR_CSB_HIGH  0x76   //CBR=1 0x76 I2C address when CSB is connected to HIGH (VCC)
+#define MS5611_ADDR_CSB_LOW   0x77   //CBR=0 0x77 I2C address when CSB is connected to LOW (GND)
+
+// registers of the device
+#define MS5611_D1 0x40
+#define MS5611_D2 0x50
+#define MS5611_RESET 0x1E
+
+// D1 and D2 result size (bytes)
+#define MS5611_D1D2_SIZE 3
+
+// OSR (Over Sampling Ratio) constants
+#define MS5611_OSR_256 0x00
+#define MS5611_OSR_512 0x02
+#define MS5611_OSR_1024 0x04
+#define MS5611_OSR_2048 0x06
+#define MS5611_OSR_4096 0x08
+#define MS5611_OSR_DEFAULT MS5611_OSR_4096
+
+#define MS5611_PROM_BASE_ADDR 0xA2 // by adding ints from 0 to 6 we can read all the prom configuration values.
+// C1 will be at 0xA2 and all the subsequent are multiples of 2
+#define MS5611_PROM_REG_COUNT 6 // number of registers in the PROM
+#define MS5611_PROM_REG_SIZE 2 // size in bytes of a prom registry.
+
+// Self test parameters. Only checks that values are sane
+#define MS5611_ST_PRESS_MAX   (1100.0) //mbar
+#define MS5611_ST_PRESS_MIN   (450.0)  //mbar
+#define MS5611_ST_TEMP_MAX    (60.0)   //degree celcius
+#define MS5611_ST_TEMP_MIN    (-20.0)  //degree celcius
+
+// Constants used to determine altitude from pressure
+#define CONST_SEA_PRESSURE 102610.f //1026.1f //http://www.meteo.physik.uni-muenchen.de/dokuwiki/doku.php?id=wetter:stadt:messung
+#define CONST_PF 0.1902630958 //(1/5.25588f) Pressure factor
+#define CONST_PF2 44330.0f
+
+
+bool ms5611Init(I2C_Dev *i2cPort);
+bool ms5611SelfTest(void);
+bool ms5611EvaluateSelfTest(float min, float max, float value, char* string);
+float ms5611GetPressure(uint8_t osr);
+float ms5611CalcPressure(int32_t rawPress, int32_t dT);
+float ms5611GetTemperature(uint8_t osr);
+float ms5611CalcTemp(int32_t deltaT);
+int32_t ms5611GetDeltaTemp(uint8_t osr);
+int32_t ms5611CalcDeltaTemp(int32_t rawTemp);
+int32_t ms5611RawPressure(uint8_t osr);
+int32_t ms5611RawTemperature(uint8_t osr);
+bool ms5611ReadPROM();
+void ms5611Reset();
+void ms5611StartConversion(uint8_t command);
+int32_t ms5611GetConversion(uint8_t command);
+
+void ms5611GetData(float* pressure, float* temperature, float* asl);
+float ms5611PressureToAltitude(float* pressure);
+#endif // MS5611_H
diff --git a/crazyflie-firmware-src/src/drivers/interface/nRF24L01reg.h b/crazyflie-firmware-src/src/drivers/interface/nRF24L01reg.h
new file mode 100644
index 0000000000000000000000000000000000000000..c1333302e81efbd1cd027d6d4559ef342ca09014
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/nRF24L01reg.h
@@ -0,0 +1,67 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nRF24L01.c - nRF24L01+ register definition
+ */
+#ifndef __NRF24L01REG_H__
+#define __NRF24L01REG_H__
+
+/* Registers address definition */
+#define REG_CONFIG 0x00
+#define REG_EN_AA 0x01
+#define REG_EN_RXADDR 0x02
+#define REG_SETUP_AW 0x03
+#define REG_SETUP_RETR 0x04
+#define REG_RF_CH 0x05
+#define REG_RF_SETUP 0x06
+#define REG_STATUS 0x07
+#define REG_OBSERVE_TX 0x08
+#define REG_RPD 0x09
+#define REG_RX_ADDR_P0 0x0A
+#define REG_RX_ADDR_P1 0x0B
+#define REG_RX_ADDR_P2 0x0C
+#define REG_RX_ADDR_P3 0x0D
+#define REG_RX_ADDR_P4 0x0E
+#define REG_RX_ADDR_P5 0x0F
+#define REG_TX_ADDR 0x10
+#define REG_RX_PW_P0 0x11
+#define REG_RX_PW_P1 0x12
+#define REG_RX_PW_P2 0x13
+#define REG_RX_PW_P3 0x14
+#define REG_RX_PW_P4 0x15
+#define REG_RX_PW_P5 0x16
+#define REG_FIFO_STATUS 0x17
+#define REG_DYNPD 0x1C
+#define REG_FEATURE 0x1D
+
+#define VAL_RF_SETUP_250K 0x26
+#define VAL_RF_SETUP_1M   0x06
+#define VAL_RF_SETUP_2M   0x0E
+
+#define VAL_SETUP_AW_3B 1
+#define VAL_SETUP_AW_4B 2
+#define VAL_SETUP_AW_5B 3
+
+
+#endif /* __NRF24L01REG_H__ */
+
diff --git a/crazyflie-firmware-src/src/drivers/interface/nrf24l01.h b/crazyflie-firmware-src/src/drivers/interface/nrf24l01.h
new file mode 100644
index 0000000000000000000000000000000000000000..f90dce00c165436146f84baf26ee6cb6d50b9ff4
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/nrf24l01.h
@@ -0,0 +1,74 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nrf24l01.h: nRF24L01(-p) PRX mode low level driver
+ */
+
+#ifndef __NRF24L01_H__
+#define __NRF24L01_H__
+
+#include <stdbool.h>
+
+#include "nRF24L01reg.h"
+
+// Init and test of the connection to the chip
+void nrfInit(void);
+bool nrfTest(void);
+
+// Interrupt routine
+void nrfIsr();
+
+/*** Defines ***/
+#define RADIO_RATE_250K 0
+#define RADIO_RATE_1M 1
+#define RADIO_RATE_2M 2
+
+/* Low level reg access
+ * FIXME: the user should not need to access raw registers...
+ */
+unsigned char nrfReadReg(unsigned char address, char *buffer, int len);
+unsigned char nrfRead1Reg(unsigned char address);
+unsigned char nrfWriteReg(unsigned char address, char *buffer, int len);
+unsigned char nrfWrite1Reg(unsigned char address, char byte);
+
+//Interrupt access
+void nrfSetInterruptCallback(void (*cb)(void));
+
+// Low level functionality of the nrf chip
+unsigned char nrfNop();
+unsigned char nrfFlushRx();
+unsigned char nrfFlushTx();
+unsigned char nrfRxLength(unsigned int pipe);
+unsigned char nrfActivate();
+unsigned char nrfWriteAck(unsigned int pipe, char *buffer, int len);
+unsigned char nrfReadRX(char *buffer, int len);
+void nrfSetChannel(unsigned int channel);
+void nrfSetDatarate(int datarate);
+void nrfSetAddress(unsigned int pipe, char* address);
+void nrfSetEnable(bool enable);
+unsigned char nrfGetStatus();
+bool nrfInterruptActive(void);
+
+
+
+#endif
diff --git a/crazyflie-firmware-src/src/drivers/interface/nvic.h b/crazyflie-firmware-src/src/drivers/interface/nvic.h
new file mode 100644
index 0000000000000000000000000000000000000000..e39676936f42b49b27c924cb000f504cf6f0ec8d
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/nvic.h
@@ -0,0 +1,34 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nvic.h - Interrupt vector header file
+ */
+#ifndef NVIC_H_
+#define NVIC_H_
+
+/**
+ * Setup and initialize the NVIC
+ */
+void nvicInit(void);
+
+#endif /* NVIC_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/piezo.h b/crazyflie-firmware-src/src/drivers/interface/piezo.h
new file mode 100644
index 0000000000000000000000000000000000000000..fa89cfd4c9ba1b5839ca5e06437bdc52ba975d35
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/piezo.h
@@ -0,0 +1,66 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * Motors.h - Motor driver header file
+ *
+ * The motors PWM ratio is a value on 16 bits (from 0 to 0xFFFF)
+ * the functions of the driver will make the conversions to the actual PWM
+ * precision (ie. if the precision is 8bits 0xFFFF and 0xFF00 are equivalents).
+ *
+ * The precision is set in number of bits by the define MOTORS_PWM_BITS
+ * The timer prescaler is set by MOTORS_PWM_PRESCALE
+ */
+#ifndef __PIEZO_H__
+#define __PIEZO_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "config.h"
+
+/******** Defines ********/
+
+/*** Public interface ***/
+
+/**
+ * Piezo Initialization. Configures two output compare channels in PWM mode
+ * with one of them inverted to increase power output.
+ */
+void piezoInit();
+
+/**
+ * Test of the motor modules. The test will spin each motor very short in
+ * the sequence M1 to M4.
+ */
+bool piezoTest(void);
+
+/**
+ * Set piezo ratio/power.
+ */
+void piezoSetRatio(uint8_t ratio);
+
+/**
+ * Set piezo frequency in hertz.
+ */
+void piezoSetFreq(uint16_t freq);
+
+#endif /* __MOTORS_H__ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/swd.h b/crazyflie-firmware-src/src/drivers/interface/swd.h
new file mode 100644
index 0000000000000000000000000000000000000000..f3871e05289e87878c40a230edef3c00134eac73
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/swd.h
@@ -0,0 +1,33 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * swd.h - Low level SWD functionality.
+ */
+#ifndef __SWD_H__
+#define __SWD_H__
+
+#include <stdbool.h>
+void swdInit();
+bool swdTest();
+
+#endif /* __SWD_H__ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/uart1.h b/crazyflie-firmware-src/src/drivers/interface/uart1.h
new file mode 100644
index 0000000000000000000000000000000000000000..1e96360233c0f771556bb1a55ff9fef6da2162bb
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/uart1.h
@@ -0,0 +1,101 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart1.h - uart1 driver for deck port
+ */
+#ifndef UART1_H_
+#define UART1_H_
+
+#include <stdbool.h>
+#include "eprintf.h"
+
+#define UART1_BAUDRATE           9600
+#define UART1_DATA_TIMEOUT_MS    1000
+#define UART1_DATA_TIMEOUT_TICKS (UART1_DATA_TIMEOUT_MS / portTICK_RATE_MS)
+
+#define UART1_TYPE             USART3
+#define UART1_PERIF            RCC_APB1Periph_USART3
+#define ENABLE_UART1_RCC       RCC_APB1PeriphClockCmd
+#define UART1_IRQ              USART3_IRQn
+
+#define UART1_DMA_IRQ          DMA1_Channel2_IRQn
+#define UART1_DMA_IT_TC        DMA1_IT_TC2
+#define UART1_DMA_CH           DMA1_Channel2
+
+#define UART1_GPIO_PERIF       RCC_AHB1Periph_GPIOC
+#define UART1_GPIO_PORT        GPIOC
+#define UART1_GPIO_TX_PIN      GPIO_Pin_10
+#define UART1_GPIO_RX_PIN      GPIO_Pin_11
+#define UART1_GPIO_AF_TX_PIN   GPIO_PinSource10
+#define UART1_GPIO_AF_RX_PIN   GPIO_PinSource11
+#define UART1_GPIO_AF_TX       GPIO_AF_USART3
+#define UART1_GPIO_AF_RX       GPIO_AF_USART3
+
+/**
+ * Initialize the UART.
+ */
+void uart1Init(const uint32_t baudrate);
+
+/**
+ * Test the UART status.
+ *
+ * @return true if the UART is initialized
+ */
+bool uart1Test(void);
+
+/**
+ * Read a byte of data from incoming queue with a timeout defined by UART1_DATA_TIMEOUT_MS
+ * @param[out] c  Read byte
+ * @return true if data, false if timeout was reached.
+ */
+bool uart1GetDataWithTimout(uint8_t *c);
+
+/**
+ * Sends raw data using a lock. Should be used from
+ * exception functions and for debugging when a lot of data
+ * should be transfered.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ */
+void uart1SendData(uint32_t size, uint8_t* data);
+
+/**
+ * Send a single character to the serial port using the uartSendData function.
+ * @param[in] ch Character to print. Only the 8 LSB are used.
+ *
+ * @return Character printed
+ */
+int uart1Putchar(int ch);
+
+void uart1Getchar(char * ch);
+
+/**
+ * Uart printf macro that uses eprintf
+ * @param[in] FMT String format
+ * @param[in] ... Parameters to print
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+#define uart1Printf(FMT, ...) eprintf(uart1Putchar, FMT, ## __VA_ARGS__)
+
+#endif /* UART1_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/uart2.h b/crazyflie-firmware-src/src/drivers/interface/uart2.h
new file mode 100644
index 0000000000000000000000000000000000000000..ebfb4b4a6005188af0193a8ed8d4a3320b9ae768
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/uart2.h
@@ -0,0 +1,88 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart2.h - uart2 driver for deck port
+ */
+#ifndef UART2_H_
+#define UART2_H_
+
+#include <stdbool.h>
+#include "eprintf.h"
+
+#define UART2_TYPE             USART2
+#define UART2_PERIF            RCC_APB1Periph_USART2
+#define ENABLE_UART2_RCC       RCC_APB1PeriphClockCmd
+#define UART2_IRQ              USART2_IRQn
+
+#define UART2_DMA_IRQ          DMA1_Channel2_IRQn
+#define UART2_DMA_IT_TC        DMA1_IT_TC2
+#define UART2_DMA_CH           DMA1_Channel2
+
+#define UART2_GPIO_PERIF       RCC_AHB1Periph_GPIOA
+#define UART2_GPIO_PORT        GPIOA
+#define UART2_GPIO_TX_PIN      GPIO_Pin_2
+#define UART2_GPIO_RX_PIN      GPIO_Pin_3
+#define UART2_GPIO_AF_TX_PIN   GPIO_PinSource2
+#define UART2_GPIO_AF_RX_PIN   GPIO_PinSource3
+#define UART2_GPIO_AF_TX       GPIO_AF_USART2
+#define UART2_GPIO_AF_RX       GPIO_AF_USART2
+
+/**
+ * Initialize the UART.
+ */
+void uart2Init(const uint32_t baudrate);
+
+/**
+ * Test the UART status.
+ *
+ * @return true if the UART is initialized
+ */
+bool uart2Test(void);
+
+/**
+ * Sends raw data using a lock. Should be used from
+ * exception functions and for debugging when a lot of data
+ * should be transfered.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ */
+void uart2SendData(uint32_t size, uint8_t* data);
+
+/**
+ * Send a single character to the serial port using the uartSendData function.
+ * @param[in] ch Character to print. Only the 8 LSB are used.
+ *
+ * @return Character printed
+ */
+int uart2Putchar(int ch);
+
+/**
+ * Uart printf macro that uses eprintf
+ * @param[in] FMT String format
+ * @param[in] ... Parameters to print
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+#define uart2Printf(FMT, ...) eprintf(uart2Putchar, FMT, ## __VA_ARGS__)
+
+#endif /* UART2_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/uart_syslink.h b/crazyflie-firmware-src/src/drivers/interface/uart_syslink.h
new file mode 100644
index 0000000000000000000000000000000000000000..e52fbcc8d9e51610b16198cde725602b9dff596a
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/uart_syslink.h
@@ -0,0 +1,138 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart_syslink.h - uart syslink to nRF51 and raw access functions
+ */
+#ifndef UART_SYSLINK_H_
+#define UART_SYSLINK_H_
+
+#include <stdbool.h>
+
+#include "crtp.h"
+#include "eprintf.h"
+
+#define UARTSLK_TYPE             USART6
+#define UARTSLK_PERIF            RCC_APB2Periph_USART6
+#define ENABLE_UARTSLK_RCC       RCC_APB2PeriphClockCmd
+#define UARTSLK_IRQ              USART6_IRQn
+
+#define UARTSLK_DMA_IRQ          DMA2_Stream7_IRQn
+#define UARTSLK_DMA_IT_TC        DMA_IT_TC
+#define UARTSLK_DMA_STREAM       DMA2_Stream7
+#define UARTSLK_DMA_CH           DMA_Channel_5
+#define UARTSLK_DMA_FLAG_TCIF    DMA_FLAG_TCIF7
+
+#define UARTSLK_GPIO_PERIF       RCC_AHB1Periph_GPIOC
+#define UARTSLK_GPIO_PORT        GPIOC
+#define UARTSLK_GPIO_TX_PIN      GPIO_Pin_6
+#define UARTSLK_GPIO_RX_PIN      GPIO_Pin_7
+#define UARTSLK_GPIO_AF_TX_PIN   GPIO_PinSource6
+#define UARTSLK_GPIO_AF_RX_PIN   GPIO_PinSource7
+#define UARTSLK_GPIO_AF_TX       GPIO_AF_USART6
+#define UARTSLK_GPIO_AF_RX       GPIO_AF_USART6
+
+#define UARTSLK_TXEN_PERIF       RCC_AHB1Periph_GPIOA
+#define UARTSLK_TXEN_PORT        GPIOA
+#define UARTSLK_TXEN_PIN         GPIO_Pin_4
+#define UARTSLK_TXEN_EXTI        EXTI_Line4
+
+/**
+ * Initialize the UART.
+ *
+ * @note Initialize CRTP link only if USE_CRTP_UART is defined
+ */
+void uartslkInit(void);
+
+/**
+ * Test the UART status.
+ *
+ * @return true if the UART is initialized
+ */
+bool uartslkTest(void);
+
+/**
+ * Get CRTP link data structure
+ *
+ * @return Address of the crtp link operations structure.
+ */
+struct crtpLinkOperations * uartslkGetLink();
+
+/**
+ * Get data from rx queue with timeout.
+ * @param[out] c  Byte of data
+ *
+ * @return true if byte received, false if timout reached.
+ */
+bool uartslkGetDataWithTimout(uint8_t *c);
+
+/**
+ * Sends raw data using a lock. Should be used from
+ * exception functions and for debugging when a lot of data
+ * should be transfered.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+void uartslkSendData(uint32_t size, uint8_t* data);
+
+/**
+ * Sends raw data using interrupts and blocking semaphore.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ */
+void uartslkSendDataIsrBlocking(uint32_t size, uint8_t* data);
+
+/**
+ * Send a single character to the serial port using the uartslkSendData function.
+ * @param[in] ch Character to print. Only the 8 LSB are used.
+ * @return Character printed
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+int uartslkPutchar(int ch);
+
+/**
+ * Sends raw data using DMA transfer. Should be used from
+ * exception functions and for debugging when a lot of data
+ * should be transfered.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+void uartslkSendDataDmaBlocking(uint32_t size, uint8_t* data);
+
+/**
+ * Interrupt service routine handling UART interrupts.
+ */
+void uartslkIsr(void);
+
+/**
+ * Interrupt service routine handling UART DMA interrupts.
+ */
+void uartslkDmaIsr(void);
+
+void uartslkTxenFlowctrlIsr();
+
+#endif /* UART_SYSLINK_H_ */
diff --git a/crazyflie-firmware-src/src/drivers/interface/watchdog.h b/crazyflie-firmware-src/src/drivers/interface/watchdog.h
new file mode 100644
index 0000000000000000000000000000000000000000..63bc7142a95aec8ced3b45bdd4c33ebc6d25d0bd
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/watchdog.h
@@ -0,0 +1,40 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file watchdog.h - Hardware watchdog
+ *
+ */
+#ifndef WATCHDOG_H_
+#define WATCHDOG_H_
+
+#include <stdbool.h>
+#include "stm32fxxx.h"
+
+#define WATCHDOG_RESET_PERIOD_MS 80
+
+void watchdogInit(void);
+bool watchdogNormalStartTest(void);
+#define watchdogReset() (IWDG_ReloadCounter())
+
+#endif // WATCHDOG_H_
+
diff --git a/crazyflie-firmware-src/src/drivers/interface/ws2812.h b/crazyflie-firmware-src/src/drivers/interface/ws2812.h
new file mode 100644
index 0000000000000000000000000000000000000000..657c6e5c32ca3e395449bed7e40bcd982ff878b1
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/interface/ws2812.h
@@ -0,0 +1,8 @@
+#ifndef __WS2812_H__
+#define __WS2812_H__
+
+void ws2812Init(void);
+void ws2812Send(uint8_t (*color)[3], uint16_t len);
+void ws2812DmaIsr(void);
+
+#endif
diff --git a/crazyflie-firmware-src/src/drivers/src/adc_f103.c b/crazyflie-firmware-src/src/drivers/src/adc_f103.c
new file mode 100644
index 0000000000000000000000000000000000000000..ed29759bf5681542d73a1f0fa8e75169133b5be5
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/adc_f103.c
@@ -0,0 +1,287 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * adc.c - Analog Digital Conversion
+ *
+ * TODO: Describe functionality.
+ *
+ * Sample time: According to the formula in the stm32 product manual
+ *              page 69, with a Ts of 28.5 samples, 12-bit, and ADC@12
+ *              the highest impedance to use is 25.2kOhm.
+ */
+#include "stm32fxxx.h"
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+#include "adc.h"
+#include "pm.h"
+#include "nvicconf.h"
+#include "imu.h"
+
+#ifdef ADC_OUTPUT_RAW_DATA
+#include "uart.h"
+#include "acc.h"
+#endif
+
+// PORT A
+#define GPIO_VBAT        GPIO_Pin_3
+
+// CHANNELS
+#define NBR_OF_ADC_CHANNELS   1
+#define CH_VBAT               ADC_Channel_3
+
+#define CH_VREF               ADC_Channel_17
+#define CH_TEMP               ADC_Channel_16
+
+static bool isInit;
+volatile AdcGroup adcValues[ADC_MEAN_SIZE * 2];
+
+xQueueHandle      adcQueue;
+
+static void adcDmaInit(void)
+{
+  DMA_InitTypeDef DMA_InitStructure;
+
+  RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+
+  // DMA channel1 configuration
+  DMA_DeInit(DMA1_Channel1);
+  DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
+  DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&adcValues;
+  DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+  DMA_InitStructure.DMA_BufferSize = NBR_OF_ADC_CHANNELS * (ADC_MEAN_SIZE * 2);
+  DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+  DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+  DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+  DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+  DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+  DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+  DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+  DMA_Init(DMA1_Channel1, &DMA_InitStructure);
+  // Enable DMA channel1
+  DMA_Cmd(DMA1_Channel1, ENABLE);
+}
+
+/**
+ * Decimates the adc samples after oversampling
+ */
+static void adcDecimate(AdcGroup* oversampled, AdcGroup* decimated)
+{
+  uint32_t i, j;
+  uint32_t sum;
+  uint32_t sumVref;
+  AdcGroup* adcIterator;
+  AdcPair *adcOversampledPair;
+  AdcPair *adcDecimatedPair;
+
+  // Compute sums and decimate each channel
+  adcDecimatedPair = (AdcPair*)decimated;
+  for (i = 0; i < NBR_OF_ADC_CHANNELS; i++)
+  {
+    adcIterator = oversampled;
+    sum = 0;
+    sumVref = 0;
+    for (j = 0; j < ADC_MEAN_SIZE; j++)
+    {
+      adcOversampledPair = &((AdcPair*)adcIterator)[i];
+      sum += adcOversampledPair->val;
+      sumVref += adcOversampledPair->vref;
+      adcIterator++;
+    }
+    // Decimate
+    adcDecimatedPair->val = sum / ADC_DECIMATE_DIVEDEND;
+    adcDecimatedPair->vref = sumVref / ADC_DECIMATE_DIVEDEND;
+    adcDecimatedPair++;
+  }
+}
+
+void adcInit(void)
+{
+
+  if(isInit)
+    return;
+
+  ADC_InitTypeDef ADC_InitStructure;
+  TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+  TIM_OCInitTypeDef TIM_OCInitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  // Enable TIM2, GPIOA and ADC1 clock
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2 |
+                         RCC_APB2Periph_GPIOA | RCC_APB2Periph_AFIO, ENABLE);
+
+  //Timer configuration
+  TIM_TimeBaseStructure.TIM_Period = ADC_TRIG_PERIOD;
+  TIM_TimeBaseStructure.TIM_Prescaler = ADC_TRIG_PRESCALE;
+  TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+  TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);
+
+  // TIM2 channel2 configuration in PWM mode
+  TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+  TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+  TIM_OCInitStructure.TIM_Pulse = 1;
+  TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+  TIM_OC2Init(TIM2, &TIM_OCInitStructure);
+  TIM_OC2PreloadConfig(TIM2, TIM_OCPreload_Enable);
+  // Halt timer 2 during debug halt.
+  DBGMCU_Config(DBGMCU_TIM2_STOP, ENABLE);
+
+  adcDmaInit();
+
+  // ADC1 configuration
+  ADC_DeInit(ADC1);
+  ADC_InitStructure.ADC_Mode = ADC_Mode_RegSimult;
+  ADC_InitStructure.ADC_ScanConvMode = ENABLE;
+  ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
+  ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T2_CC2;
+  ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+  ADC_InitStructure.ADC_NbrOfChannel = NBR_OF_ADC_CHANNELS;
+  ADC_Init(ADC1, &ADC_InitStructure);
+
+  // ADC1 channel sequence
+  ADC_RegularChannelConfig(ADC1, CH_VREF, 1, ADC_SampleTime_28Cycles5);
+
+  // ADC2 configuration
+  ADC_DeInit(ADC2);
+  ADC_InitStructure.ADC_Mode = ADC_Mode_RegSimult;
+  ADC_InitStructure.ADC_ScanConvMode = ENABLE;
+  ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
+  ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
+  ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+  ADC_InitStructure.ADC_NbrOfChannel = NBR_OF_ADC_CHANNELS;
+  ADC_Init(ADC2, &ADC_InitStructure);
+
+  // ADC2 channel sequence
+  ADC_RegularChannelConfig(ADC2, CH_VBAT, 1, ADC_SampleTime_28Cycles5);
+
+  // Enable ADC1
+  ADC_Cmd(ADC1, ENABLE);
+  // Calibrate ADC1
+  ADC_ResetCalibration(ADC1);
+  while(ADC_GetResetCalibrationStatus(ADC1));
+  ADC_StartCalibration(ADC1);
+  while(ADC_GetCalibrationStatus(ADC1));
+
+  // Enable ADC1 external trigger
+  ADC_ExternalTrigConvCmd(ADC1, ENABLE);
+  ADC_TempSensorVrefintCmd(ENABLE);
+
+  // Enable ADC2
+  ADC_Cmd(ADC2, ENABLE);
+  // Calibrate ADC2
+  ADC_ResetCalibration(ADC2);
+  while(ADC_GetResetCalibrationStatus(ADC2));
+  ADC_StartCalibration(ADC2);
+  while(ADC_GetCalibrationStatus(ADC2));
+
+  // Enable ADC2 external trigger
+  ADC_ExternalTrigConvCmd(ADC2, ENABLE);
+
+  // Enable the DMA1 channel1 Interrupt
+  NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel1_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_ADC_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  adcQueue = xQueueCreate(1, sizeof(AdcGroup*));
+
+  xTaskCreate(adcTask, ADC_TASK_NAME,
+              ADC_TASK_STACKSIZE, NULL, ADC_TASK_PRI, NULL);
+
+  isInit = true;
+}
+
+bool adcTest(void)
+{
+  return isInit;
+}
+
+float adcConvertToVoltageFloat(uint16_t v, uint16_t vref)
+{
+  return (v / (vref / ADC_INTERNAL_VREF));
+}
+
+void adcDmaStart(void)
+{
+  // Enable the Transfer Complete and Half Transfer Interrupt
+  DMA_ITConfig(DMA1_Channel1, DMA_IT_TC | DMA_IT_HT, ENABLE);
+  // Enable ADC1 DMA
+  ADC_DMACmd(ADC1, ENABLE);
+  // TIM2 counter enable
+  TIM_Cmd(TIM2, ENABLE);
+}
+
+void adcDmaStop(void)
+{
+//  TIM_Cmd(TIM2, DISABLE);
+}
+
+void adcInterruptHandler(void)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken;
+  AdcGroup* adcBuffer;
+
+  if(DMA_GetITStatus(DMA1_IT_HT1))
+  {
+    DMA_ClearITPendingBit(DMA1_IT_HT1);
+    adcBuffer = (AdcGroup*)&adcValues[0];
+    xQueueSendFromISR(adcQueue, &adcBuffer, &xHigherPriorityTaskWoken);
+  }
+  if(DMA_GetITStatus(DMA1_IT_TC1))
+  {
+    DMA_ClearITPendingBit(DMA1_IT_TC1);
+    adcBuffer = (AdcGroup*)&adcValues[ADC_MEAN_SIZE];
+    xQueueSendFromISR(adcQueue, &adcBuffer, &xHigherPriorityTaskWoken);
+  }
+}
+
+void adcTask(void *param)
+{
+  AdcGroup* adcRawValues;
+  AdcGroup adcValues;
+
+  vTaskSetApplicationTaskTag(0, (void*)TASK_ADC_ID_NBR);
+  vTaskDelay(1000);
+
+  adcDmaStart();
+
+  while(1)
+  {
+    xQueueReceive(adcQueue, &adcRawValues, portMAX_DELAY);
+    adcDecimate(adcRawValues, &adcValues);  // 10% CPU
+    pmBatteryUpdate(&adcValues);
+
+#ifdef ADC_OUTPUT_RAW_DATA
+    uartSendDataDma(sizeof(AdcGroup)*ADC_MEAN_SIZE, (uint8_t*)adcRawValues);
+#endif
+  }
+}
+
+void __attribute__((used)) DMA1_Channel1_IRQHandler(void)
+{
+  adcInterruptHandler();
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/ak8963.c b/crazyflie-firmware-src/src/drivers/src/ak8963.c
new file mode 100644
index 0000000000000000000000000000000000000000..62f99f6353d193f2a5efccdfc406d5be64a833d4
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/ak8963.c
@@ -0,0 +1,276 @@
+// I2Cdev library collection - AK8975 I2C device class header file
+// Based on AKM AK8975/B datasheet, 12/2009
+// 8/27/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     2011-08-27 - initial release
+
+/* ============================================
+ I2Cdev device library code is placed under the MIT license
+ Copyright (c) 2011 Jeff Rowberg
+ Adapted to Crazyflie FW by Bitcraze
+
+ Permission is hereby granted, free of charge, to any person obtaining a copy
+ of this software and associated documentation files (the "Software"), to deal
+ in the Software without restriction, including without limitation the rights
+ to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ copies of the Software, and to permit persons to whom the Software is
+ furnished to do so, subject to the following conditions:
+
+ The above copyright notice and this permission notice shall be included in
+ all copies or substantial portions of the Software.
+
+ THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ THE SOFTWARE.
+ ===============================================
+ */
+#define DEBUG_MODULE "AK8963"
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "ak8963.h"
+
+// TA: Maybe not so good to bring in these dependencies...
+#include "debug.h"
+#include "eprintf.h"
+
+static uint8_t devAddr;
+static uint8_t buffer[6];
+static I2C_Dev *I2Cx;
+static bool isInit;
+
+static bool ak8963EvaluateSelfTest(int16_t min, int16_t max, int16_t value, char* string);
+
+/** Power on and prepare for general usage.
+ * No specific pre-configuration is necessary for this device.
+ */
+void ak8963Init(I2C_Dev *i2cPort)
+{
+  if (isInit)
+    return;
+
+  I2Cx = i2cPort;
+  devAddr = AK8963_ADDRESS_00;
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool ak8963TestConnection()
+{
+  if (i2cdevReadByte(I2Cx, devAddr, AK8963_RA_WIA, buffer) == 1)
+  {
+    return (buffer[0] == 0x48);
+  }
+  return false;
+}
+
+bool ak8963SelfTest()
+{
+  bool testStatus = true;
+  int16_t mx, my, mz;  // positive magnetometer measurements
+  uint8_t confSave;
+  uint8_t timeout = 20;
+
+  // Save register values
+  if (i2cdevReadByte(I2Cx, devAddr, AK8963_RA_CNTL, &confSave) == false)
+  {
+    // TODO: error handling
+    return false;
+  }
+
+  // Power down
+  ak8963SetMode(AK8963_MODE_POWERDOWN);
+  ak8963SetSelfTest(true);
+  ak8963SetMode(AK8963_MODE_16BIT | AK8963_MODE_SELFTEST);
+  // Clear ST1 by reading ST2
+  ak8963GetOverflowStatus();
+  while (!ak8963GetDataReady() && timeout--)
+  {
+    vTaskDelay(M2T(1));
+  }
+  ak8963GetHeading(&mx, &my, &mz);
+  // Power down
+  ak8963SetMode(AK8963_MODE_POWERDOWN);
+
+  if (ak8963EvaluateSelfTest(AK8963_ST_X_MIN, AK8963_ST_X_MAX, mx, "X") &&
+      ak8963EvaluateSelfTest(AK8963_ST_Y_MIN, AK8963_ST_Y_MAX, my, "Y") &&
+      ak8963EvaluateSelfTest(AK8963_ST_Z_MIN, AK8963_ST_Z_MAX, mz, "Z"))
+   {
+    DEBUG_PRINT("Self test [OK].\n");
+  }
+  else
+  {
+    testStatus = false;
+  }
+
+  // Power up with saved config
+  ak8963SetMode(confSave);
+
+  return testStatus;
+}
+
+/** Evaluate the values from a HMC8335L self test.
+ * @param min The min limit of the self test
+ * @param max The max limit of the self test
+ * @param value The value to compare with.
+ * @param string A pointer to a string describing the value.
+ * @return True if self test within min - max limit, false otherwise
+ */
+static bool ak8963EvaluateSelfTest(int16_t min, int16_t max, int16_t value, char* string)
+{
+  if (value < min || value > max)
+  {
+    DEBUG_PRINT("Self test %s [FAIL]. low: %d, high: %d, measured: %d\n",
+                string, min, max, value);
+    return false;
+  }
+  return true;
+}
+
+// WIA register
+
+uint8_t ak8963GetDeviceID()
+{
+  i2cdevReadByte(I2Cx, devAddr, AK8963_RA_WIA, buffer);
+  return buffer[0];
+}
+
+// INFO register
+
+uint8_t ak8963GetInfo()
+{
+  i2cdevReadByte(I2Cx, devAddr, AK8963_RA_INFO, buffer);
+  return buffer[0];
+}
+
+// ST1 register
+
+bool ak8963GetDataReady()
+{
+  i2cdevReadBit(I2Cx, devAddr, AK8963_RA_ST1, AK8963_ST1_DRDY_BIT, buffer);
+  return buffer[0];
+}
+
+// H* registers
+void ak8963GetHeading(int16_t *x, int16_t *y, int16_t *z)
+{
+//  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_CNTL, AK8963_MODE_SINGLE);
+//  delay(10);
+  i2cdevRead(I2Cx, devAddr, AK8963_RA_HXL, 6, buffer);
+  *x = (((int16_t) buffer[1]) << 8) | buffer[0];
+  *y = (((int16_t) buffer[3]) << 8) | buffer[2];
+  *z = (((int16_t) buffer[5]) << 8) | buffer[4];
+}
+int16_t ak8963GetHeadingX()
+{
+  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_CNTL, AK8963_MODE_SINGLE);
+//  delay(10);
+  i2cdevRead(I2Cx, devAddr, AK8963_RA_HXL, 2, buffer);
+  return (((int16_t) buffer[1]) << 8) | buffer[0];
+}
+int16_t ak8963GetHeadingY()
+{
+  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_CNTL, AK8963_MODE_SINGLE);
+//  delay(10);
+  i2cdevRead(I2Cx, devAddr, AK8963_RA_HYL, 2, buffer);
+  return (((int16_t) buffer[1]) << 8) | buffer[0];
+}
+int16_t ak8963GetHeadingZ()
+{
+  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_CNTL, AK8963_MODE_SINGLE);
+//  delay(10);
+  i2cdevRead(I2Cx, devAddr, AK8963_RA_HZL, 2, buffer);
+  return (((int16_t) buffer[1]) << 8) | buffer[0];
+}
+
+// ST2 register
+bool ak8963GetOverflowStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, AK8963_RA_ST2, AK8963_ST2_HOFL_BIT, buffer);
+  return buffer[0];
+}
+bool ak8963GetDataError()
+{
+  i2cdevReadBit(I2Cx, devAddr, AK8963_RA_ST2, AK8963_ST2_DERR_BIT, buffer);
+  return buffer[0];
+}
+
+// CNTL register
+uint8_t ak8963GetMode()
+{
+  i2cdevReadByte(I2Cx, devAddr, AK8963_RA_CNTL, buffer);
+  return buffer[0];
+}
+void ak8963SetMode(uint8_t mode)
+{
+  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_CNTL, mode);
+}
+void ak8963Reset()
+{
+  i2cdevWriteBits(I2Cx, devAddr, AK8963_RA_CNTL, AK8963_CNTL_MODE_BIT,
+      AK8963_CNTL_MODE_LENGTH, AK8963_MODE_POWERDOWN);
+}
+
+// ASTC register
+void ak8963SetSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, AK8963_RA_ASTC, AK8963_ASTC_SELF_BIT, enabled);
+}
+
+// I2CDIS
+void ak8963DisableI2C()
+{
+  i2cdevWriteBit(I2Cx, devAddr, AK8963_RA_I2CDIS, AK8963_I2CDIS_BIT, true);
+}
+
+// ASA* registers
+void ak8963GetAdjustment(int8_t *x, int8_t *y, int8_t *z)
+{
+  i2cdevRead(I2Cx, devAddr, AK8963_RA_ASAX, 3, buffer);
+  *x = buffer[0];
+  *y = buffer[1];
+  *z = buffer[2];
+}
+void ak8963SetAdjustment(int8_t x, int8_t y, int8_t z)
+{
+  buffer[0] = x;
+  buffer[1] = y;
+  buffer[2] = z;
+  i2cdevWrite(I2Cx, devAddr, AK8963_RA_ASAX, 3, buffer);
+}
+uint8_t ak8963GetAdjustmentX()
+{
+  i2cdevReadByte(I2Cx, devAddr, AK8963_RA_ASAX, buffer);
+  return buffer[0];
+}
+void ak8963SetAdjustmentX(uint8_t x)
+{
+  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_ASAX, x);
+}
+uint8_t ak8963GetAdjustmentY()
+{
+  i2cdevReadByte(I2Cx, devAddr, AK8963_RA_ASAY, buffer);
+  return buffer[0];
+}
+void ak8963SetAdjustmentY(uint8_t y)
+{
+  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_ASAY, y);
+}
+uint8_t ak8963GetAdjustmentZ()
+{
+  i2cdevReadByte(I2Cx, devAddr, AK8963_RA_ASAZ, buffer);
+  return buffer[0];
+}
+void ak8963SetAdjustmentZ(uint8_t z)
+{
+  i2cdevWriteByte(I2Cx, devAddr, AK8963_RA_ASAZ, z);
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/cppm.c b/crazyflie-firmware-src/src/drivers/src/cppm.c
new file mode 100644
index 0000000000000000000000000000000000000000..b577e4d274a99b27b0f5c9deba7c8b127e17dfd9
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/cppm.c
@@ -0,0 +1,183 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2013 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * cppm.c - Combined PPM / PPM-Sum driver
+ */
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+
+#include "stm32fxxx.h"
+#include "cppm.h"
+#include "nvicconf.h"
+#include "commander.h"
+
+#define DEBUG_MODULE  "CPPM"
+#include "debug.h"
+#include "log.h"
+
+
+#define CPPM_TIMER                   TIM14
+#define CPPM_TIMER_RCC               RCC_APB1Periph_TIM14
+#define CPPM_TIMER_CH_Init           TIM_OC1Init
+#define CPPM_TIMER_CH_PreloadConfig  TIM_OC1PreloadConfig
+#define CPPM_TIMER_CH_SetCompare     TIM_SetCompare1
+#define CPPM_GPIO_RCC                RCC_AHB1Periph_GPIOA
+#define CPPM_GPIO_PORT               GPIOA
+#define CPPM_GPIO_PIN                GPIO_Pin_7
+#define CPPM_GPIO_SOURCE             GPIO_PinSource7
+#define CPPM_GPIO_AF                 GPIO_AF_TIM14
+
+#define CPPM_TIM_PRESCALER           (84 - 1) // TIM14 clock running at sysclk/2. Will give 1us tick.
+
+#define CPPM_MIN_PPM_USEC            1150
+#define CPPM_MAX_PPM_USEC            1900
+
+static xQueueHandle captureQueue;
+static uint16_t prevCapureVal;
+static bool captureFlag;
+static bool isAvailible;
+
+void cppmInit(void)
+{
+  TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+  TIM_ICInitTypeDef  TIM_ICInitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  RCC_AHB1PeriphClockCmd(CPPM_GPIO_RCC, ENABLE);
+  RCC_APB1PeriphClockCmd(CPPM_TIMER_RCC, ENABLE);
+
+  // Configure the GPIO for the timer input
+  GPIO_StructInit(&GPIO_InitStructure);
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_Pin = CPPM_GPIO_PIN;
+  GPIO_Init(CPPM_GPIO_PORT, &GPIO_InitStructure);
+
+  GPIO_PinAFConfig(CPPM_GPIO_PORT, CPPM_GPIO_SOURCE, CPPM_GPIO_AF);
+
+  // Time base configuration. 1us tick.
+  TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
+  TIM_TimeBaseStructure.TIM_Prescaler = CPPM_TIM_PRESCALER;
+  TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseInit(CPPM_TIMER, &TIM_TimeBaseStructure);
+
+  // Setup input capture using default config.
+  TIM_ICStructInit(&TIM_ICInitStructure);
+  TIM_ICInit(CPPM_TIMER, &TIM_ICInitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannel = TIM8_TRG_COM_TIM14_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_CPPM_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  captureQueue = xQueueCreate(64, sizeof(uint16_t));
+
+  TIM_ITConfig(CPPM_TIMER, TIM_IT_Update | TIM_IT_CC1, ENABLE);
+  TIM_Cmd(CPPM_TIMER, ENABLE);
+}
+
+bool cppmIsAvailible(void)
+{
+  return isAvailible;
+}
+
+int cppmGetTimestamp(uint16_t *timestamp)
+{
+  ASSERT(timestamp);
+
+  return xQueueReceive(captureQueue, timestamp, portMAX_DELAY);
+}
+
+void cppmClearQueue(void)
+{
+  xQueueReset(captureQueue);
+}
+
+float cppmConvert2Float(uint16_t timestamp, float min, float max)
+{
+  if (timestamp < CPPM_MIN_PPM_USEC)
+  {
+    timestamp = CPPM_MIN_PPM_USEC;
+  }
+  if (timestamp > CPPM_MAX_PPM_USEC)
+  {
+    timestamp = CPPM_MAX_PPM_USEC;
+  }
+
+  float scale = (float)(timestamp - CPPM_MIN_PPM_USEC) / (float)(CPPM_MAX_PPM_USEC - CPPM_MIN_PPM_USEC);
+
+  return min + ((max - min) * scale);
+}
+
+uint16_t cppmConvert2uint16(uint16_t timestamp)
+{
+  if (timestamp < CPPM_MIN_PPM_USEC)
+  {
+    timestamp = CPPM_MIN_PPM_USEC;
+  }
+  if (timestamp > CPPM_MAX_PPM_USEC)
+  {
+    timestamp = CPPM_MAX_PPM_USEC;
+  }
+
+  uint16_t base = (timestamp - CPPM_MIN_PPM_USEC);
+
+  return base * (65535 / (CPPM_MAX_PPM_USEC - CPPM_MIN_PPM_USEC));
+}
+
+void __attribute__((used)) TIM8_TRG_COM_TIM14_IRQHandler()
+{
+  uint16_t capureVal;
+  uint16_t capureValDiff;
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+
+  if (TIM_GetITStatus(CPPM_TIMER, TIM_IT_CC1) != RESET)
+  {
+    if (TIM_GetFlagStatus(CPPM_TIMER, TIM_FLAG_CC1OF) != RESET)
+    {
+      //TODO: Handle overflow error
+    }
+
+    capureVal = TIM_GetCapture1(CPPM_TIMER);
+    capureValDiff = capureVal - prevCapureVal;
+    prevCapureVal = capureVal;
+
+    xQueueSendFromISR(captureQueue, &capureValDiff, &xHigherPriorityTaskWoken);
+
+    captureFlag = true;
+    TIM_ClearITPendingBit(CPPM_TIMER, TIM_IT_CC1);
+  }
+
+  if (TIM_GetITStatus(CPPM_TIMER, TIM_IT_Update) != RESET)
+  {
+    // Update input status
+    isAvailible = (captureFlag == true);
+    captureFlag = false;
+    TIM_ClearITPendingBit(CPPM_TIMER, TIM_IT_Update);
+  }
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/diskio.c b/crazyflie-firmware-src/src/drivers/src/diskio.c
new file mode 100644
index 0000000000000000000000000000000000000000..02478b3dd998b6b3557e34c3d780096ea6862948
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/diskio.c
@@ -0,0 +1,145 @@
+/*-----------------------------------------------------------------------*/
+/* Low level disk I/O module skeleton for FatFs     (C)ChaN, 2013        */
+/*-----------------------------------------------------------------------*/
+/* If a working storage control module is available, it should be        */
+/* attached to the FatFs via a glue function rather than modifying it.   */
+/* This is an example of glue functions to attach various exsisting      */
+/* storage control module to the FatFs module with a defined API.        */
+/*-----------------------------------------------------------------------*/
+
+#include "diskio.h"		/* FatFs lower layer API */
+#include "ff.h"
+#include "fatfs_sd.h"
+#include "cfassert.h"
+
+///* Make driver structure */
+DISKIO_LowLevelDriver_t FATFS_LowLevelDrivers[_VOLUMES];
+
+void FATFS_AddDriver(DISKIO_LowLevelDriver_t* Driver, uint8_t driverVolume)
+{
+  ASSERT(driverVolume < _VOLUMES);
+  /* Add to structure */
+  FATFS_LowLevelDrivers[driverVolume].disk_initialize = Driver->disk_initialize;
+  FATFS_LowLevelDrivers[driverVolume].disk_status = Driver->disk_status;
+  FATFS_LowLevelDrivers[driverVolume].disk_ioctl = Driver->disk_ioctl;
+  FATFS_LowLevelDrivers[driverVolume].disk_read = Driver->disk_read;
+  FATFS_LowLevelDrivers[driverVolume].disk_write = Driver->disk_write;
+  FATFS_LowLevelDrivers[driverVolume].usrOps = Driver->usrOps;
+}
+
+/*-----------------------------------------------------------------------*/
+/* Inidialize a Drive                                                    */
+/*-----------------------------------------------------------------------*/
+DSTATUS disk_initialize (
+	BYTE pdrv				/* Physical drive nmuber (0..) */
+)
+{
+	/* Return low level status */
+	if (FATFS_LowLevelDrivers[pdrv].disk_initialize) {
+		return FATFS_LowLevelDrivers[pdrv].disk_initialize(FATFS_LowLevelDrivers[pdrv].usrOps);
+	}
+	
+	/* Return parameter error */
+	return RES_PARERR;
+}
+
+/*-----------------------------------------------------------------------*/
+/* Get Disk Status                                                       */
+/*-----------------------------------------------------------------------*/
+DSTATUS disk_status (
+	BYTE pdrv		/* Physical drive nmuber (0..) */
+)
+{
+	/* Return low level status */
+	if (FATFS_LowLevelDrivers[pdrv].disk_status) {
+		return FATFS_LowLevelDrivers[pdrv].disk_status(FATFS_LowLevelDrivers[pdrv].usrOps);
+	}
+	
+	/* Return parameter error */
+	return RES_PARERR;
+}
+
+/*-----------------------------------------------------------------------*/
+/* Read Sector(s)                                                        */
+/*-----------------------------------------------------------------------*/
+DRESULT disk_read (
+	BYTE pdrv,		/* Physical drive nmuber (0..) */
+	BYTE *buff,		/* Data buffer to store read data */
+	DWORD sector,	/* Sector address (LBA) */
+	UINT count		/* Number of sectors to read (1..128) */
+)
+{
+	/* Check count */
+	if (!count) {
+		return RES_PARERR;
+	}
+	
+	/* Return low level status */
+	if (FATFS_LowLevelDrivers[pdrv].disk_read) {
+		return FATFS_LowLevelDrivers[pdrv].disk_read(buff, sector, count,
+		                                             FATFS_LowLevelDrivers[pdrv].usrOps);
+	}
+	
+	/* Return parameter error */
+	return RES_PARERR;
+}
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Write Sector(s)                                                       */
+/*-----------------------------------------------------------------------*/
+DRESULT disk_write (
+	BYTE pdrv,			/* Physical drive nmuber (0..) */
+	const BYTE *buff,	/* Data to be written */
+	DWORD sector,		/* Sector address (LBA) */
+	UINT count			/* Number of sectors to write (1..128) */
+)
+{
+	/* Check count */
+	if (!count) {
+		return RES_PARERR;
+	}
+	
+	/* Return low level status */
+	if (FATFS_LowLevelDrivers[pdrv].disk_write) {
+		return FATFS_LowLevelDrivers[pdrv].disk_write(buff, sector, count,
+		                                              FATFS_LowLevelDrivers[pdrv].usrOps);
+	}
+	
+	/* Return parameter error */
+	return RES_PARERR;
+}
+
+
+/*-----------------------------------------------------------------------*/
+/* Miscellaneous Functions                                               */
+/*-----------------------------------------------------------------------*/
+DRESULT disk_ioctl (
+	BYTE pdrv,		/* Physical drive nmuber (0..) */
+	BYTE cmd,		/* Control code */
+	void *buff		/* Buffer to send/receive control data */
+)
+{
+	/* Return low level status */
+	if (FATFS_LowLevelDrivers[pdrv].disk_ioctl) {
+		return FATFS_LowLevelDrivers[pdrv].disk_ioctl(cmd, buff,
+		                                              FATFS_LowLevelDrivers[pdrv].usrOps);
+	}
+	
+	/* Return parameter error */
+	return RES_PARERR;
+}
+
+/*-----------------------------------------------------------------------*/
+/* Get time for fatfs for files                                          */
+/*-----------------------------------------------------------------------*/
+__attribute__((weak)) DWORD get_fattime(void) {
+	/* Returns current time packed into a DWORD variable */
+	return	  ((DWORD)(2016 - 1980) << 25)	/* Year 2016 */
+			| ((DWORD)1 << 21)				/* Month 1 */
+			| ((DWORD)1 << 16)				/* Mday 1 */
+			| ((DWORD)0 << 11)				/* Hour 0 */
+			| ((DWORD)0 << 5)				/* Min 0 */
+			| ((DWORD)0 >> 1);				/* Sec 0 */
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/eeprom.c b/crazyflie-firmware-src/src/drivers/src/eeprom.c
new file mode 100644
index 0000000000000000000000000000000000000000..6b7ecb435ff6d627665c515f026a3b04e74ad50d
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/eeprom.c
@@ -0,0 +1,162 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011 Fabio Varesano <fvaresano@yahoo.it>
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file eeprom.c
+ * Driver for the 24AA64F eeprom.
+ *
+ */
+#define DEBUG_MODULE "EEPROM"
+
+#include <string.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "eeprom.h"
+#include "debug.h"
+#include "eprintf.h"
+
+#ifdef EEPROM_RUN_WRITE_READ_TEST
+static bool eepromTestWriteRead(void);
+#endif
+
+static uint8_t devAddr;
+static I2C_Dev *I2Cx;
+static bool isInit;
+
+bool eepromInit(I2C_Dev *i2cPort)
+{
+  if (isInit)
+    return true;
+
+  I2Cx = i2cPort;
+  devAddr = EEPROM_I2C_ADDR;
+
+  isInit = true;
+
+  return true;
+}
+
+bool eepromTest(void)
+{
+  bool status;
+
+  status = eepromTestConnection();
+  if (status)
+  {
+    DEBUG_PRINT("I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("I2C connection [FAIL].\n");
+  }
+
+#ifdef EEPROM_RUN_WRITE_READ_TEST
+  status = eepromTestWriteRead();
+#endif
+
+  return status;
+}
+
+#ifdef EEPROM_RUN_WRITE_READ_TEST
+static bool eepromTestWriteRead(void)
+{
+  bool status = true;
+  int i;
+  const uint8_t testData[20] = {0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19};
+  uint8_t readData[20];
+
+  for (i = 0; i < sizeof(testData) && status; i++)
+  {
+    // Write one byte with increasing addresses.
+    eepromWriteBuffer(&testData[i], i, 1);
+    // Read it all back and check
+    eepromReadBuffer(readData, 0, i+1);
+    status = (memcmp(testData, readData, i+1) == 0);
+  }
+
+  // Write it all.
+  eepromWriteBuffer(testData, 0, sizeof(testData));
+  for (i = 0; i < sizeof(testData) && status; i++)
+  {
+    // Read one byte with increasing addresses and check
+    eepromReadBuffer(&readData[i], i, 1);
+    status = (memcmp(testData, readData, i+1) == 0);
+  }
+
+  return status;
+}
+#endif
+
+bool eepromTestConnection(void)
+{
+  uint8_t tmp;
+  bool status;
+
+  if (!isInit)
+    return false;
+
+  status = i2cdevRead16(I2Cx, devAddr, 0, 1, &tmp);
+
+  return status;
+}
+
+bool eepromReadBuffer(uint8_t* buffer, uint16_t readAddr, uint16_t len)
+{
+  bool status;
+
+  if ((uint32_t)readAddr + len > EEPROM_SIZE)
+  {
+     return false;
+  }
+
+  status = i2cdevRead16(I2Cx, devAddr, readAddr, len, buffer);
+
+  return status;
+}
+
+bool eepromWriteBuffer(uint8_t* buffer, uint16_t writeAddr, uint16_t len)
+{
+  bool status = true;
+  uint16_t index;
+
+  if ((uint32_t)writeAddr + len > EEPROM_SIZE)
+  {
+     return false;
+  }
+
+  for (index = 0; index < len && status; index++)
+  {
+    status = i2cdevWrite16(I2Cx, devAddr, writeAddr + index, 1, &buffer[index]);
+    vTaskDelay(M2T(6));
+  }
+
+  return status;
+}
+
+bool eepromWritePage(uint8_t* buffer, uint16_t writeAddr)
+{
+ //TODO: implement
+  return false;
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/exti.c b/crazyflie-firmware-src/src/drivers/src/exti.c
new file mode 100644
index 0000000000000000000000000000000000000000..7f7a58d54caad6fde259d69b674e3d7986328dd3
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/exti.c
@@ -0,0 +1,205 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * exti.c - Unified implementation of the exti interrupts
+ */
+#include <stdbool.h>
+
+#include "stm32fxxx.h"
+
+#include "exti.h"
+#include "nvicconf.h"
+#include "nrf24l01.h"
+
+static bool isInit;
+
+/* Interruption initialisation */
+void extiInit()
+{
+  static NVIC_InitTypeDef NVIC_InitStructure;
+
+  if (isInit)
+    return;
+
+#ifdef PLATFORM_CF2 
+  // This is required for the EXTI interrupt configuration since EXTI
+  // lines are set via the SYSCFG peripheral; eg.
+  // SYSCFG_EXTILineConfig(EXTI_PortSourceGPIOC, EXTI_PinSource13);
+
+  // On the CF1, the equivalent command is:
+  // GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource9);
+  // which only requires the relevant GPIO clock to be enabled.
+
+  RCC_AHB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); 
+#endif
+
+  // Here we enable all EXTI interrupt handlers to save conflicting
+  // reinitialization code for the 9_5 and 15_10 handlers. Note that
+  // the individual EXTI interrupts still need to be enabled.
+
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = EXTI0_PRI;
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = EXTI1_PRI;
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI1_IRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = EXTI2_PRI;
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI2_IRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = EXTI3_PRI;
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI3_IRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = EXTI4_PRI;
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI4_IRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = EXTI9_5_PRI;
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI9_5_IRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = EXTI15_10_PRI;
+  NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  isInit = true;
+}
+
+bool extiTest(void)
+{
+  return isInit;
+}
+
+void __attribute__((used)) EXTI0_IRQHandler(void)
+{
+  EXTI_ClearITPendingBit(EXTI_Line0);
+  EXTI0_Callback();
+}
+
+void __attribute__((used)) EXTI1_IRQHandler(void)
+{
+  EXTI_ClearITPendingBit(EXTI_Line1);
+  EXTI1_Callback();
+}
+
+void __attribute__((used)) EXTI2_IRQHandler(void)
+{
+  EXTI_ClearITPendingBit(EXTI_Line2);
+  EXTI2_Callback();
+}
+
+void __attribute__((used)) EXTI3_IRQHandler(void)
+{
+  EXTI_ClearITPendingBit(EXTI_Line3);
+  EXTI3_Callback();
+}
+
+void __attribute__((used)) EXTI4_IRQHandler(void)
+{
+  EXTI_ClearITPendingBit(EXTI_Line4);
+  EXTI4_Callback();
+}
+
+void __attribute__((used)) EXTI9_5_IRQHandler(void)
+{
+  if (EXTI_GetITStatus(EXTI_Line5) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line5);
+    EXTI5_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line6) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line6);
+    EXTI6_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line7) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line7);
+    EXTI7_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line8) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line8);
+    EXTI8_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line9) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line9);
+    EXTI9_Callback();
+  }
+}
+
+void __attribute__((used)) EXTI15_10_IRQHandler(void)
+{
+  if (EXTI_GetITStatus(EXTI_Line10) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line10);
+    EXTI10_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line11) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line11);
+    EXTI11_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line12) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line12);
+    EXTI12_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line13) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line13);
+    EXTI13_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line14) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line14);
+    EXTI14_Callback();
+  }
+
+  if (EXTI_GetITStatus(EXTI_Line15) == SET) {
+    EXTI_ClearITPendingBit(EXTI_Line15);
+    EXTI15_Callback();
+  }
+}
+
+void __attribute__((weak)) EXTI0_Callback(void) { }
+void __attribute__((weak)) EXTI1_Callback(void) { }
+void __attribute__((weak)) EXTI2_Callback(void) { }
+void __attribute__((weak)) EXTI3_Callback(void) { }
+void __attribute__((weak)) EXTI4_Callback(void) { }
+void __attribute__((weak)) EXTI5_Callback(void) { }
+void __attribute__((weak)) EXTI6_Callback(void) { }
+void __attribute__((weak)) EXTI7_Callback(void) { }
+void __attribute__((weak)) EXTI8_Callback(void) { }
+void __attribute__((weak)) EXTI9_Callback(void) { }
+void __attribute__((weak)) EXTI10_Callback(void) { }
+void __attribute__((weak)) EXTI11_Callback(void) { }
+void __attribute__((weak)) EXTI12_Callback(void) { }
+void __attribute__((weak)) EXTI13_Callback(void) { }
+void __attribute__((weak)) EXTI14_Callback(void) { }
+void __attribute__((weak)) EXTI15_Callback(void) { }
diff --git a/crazyflie-firmware-src/src/drivers/src/fatfs_sd.c b/crazyflie-firmware-src/src/drivers/src/fatfs_sd.c
new file mode 100644
index 0000000000000000000000000000000000000000..6831b6e204e9ab319e47c5870d4d62e9f301759c
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/fatfs_sd.c
@@ -0,0 +1,547 @@
+/*------------------------------------------------------------------------*/
+/* STM32F100: MMCv3/SDv1/SDv2 (SPI mode) control module                   */
+/*------------------------------------------------------------------------*/
+/*
+/  Copyright (C) 2014, ChaN, all right reserved.
+/
+/ * This software is a free software and there is NO WARRANTY.
+/ * No restriction on use. You can use, modify and redistribute it for
+/   personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY.
+/ * Redistributions of source code must retain the above copyright notice.
+/
+/-------------------------------------------------------------------------*/
+
+#include "diskio.h"
+#include "fatfs_sd.h"
+
+// MMC/SD command
+#define CMD0    (0)       // GO_IDLE_STATE
+#define CMD1    (1)       // SEND_OP_COND (MMC)
+#define ACMD41  (0x80+41) // SEND_OP_COND (SDC)
+#define CMD8    (8)       // SEND_IF_COND
+#define CMD9    (9)       // SEND_CSD
+#define CMD10   (10)      // SEND_CID
+#define CMD12   (12)      // STOP_TRANSMISSION
+#define ACMD13  (0x80+13) // SD_STATUS (SDC)
+#define CMD16   (16)      // SET_BLOCKLEN
+#define CMD17   (17)      // READ_SINGLE_BLOCK
+#define CMD18   (18)      // READ_MULTIPLE_BLOCK
+#define CMD23   (23)      // SET_BLOCK_COUNT (MMC)
+#define ACMD23  (0x80+23) // SET_WR_BLK_ERASE_COUNT (SDC)
+#define CMD24   (24)      // WRITE_BLOCK
+#define CMD25   (25)      // WRITE_MULTIPLE_BLOCK
+#define CMD32   (32)      // ERASE_ER_BLK_START
+#define CMD33   (33)      // ERASE_ER_BLK_END
+#define CMD38   (38)      // ERASE
+#define CMD55   (55)      // APP_CMD
+#define CMD58   (58)      // READ_OCR
+
+static const int INT_TIMEOUT = 0;
+static const int INT_ERROR = 0;
+static const int INT_READY = 1;
+
+
+static int waitForCardReady(sdSpiContext_t *context, UINT timeoutMs) {
+  BYTE d;
+
+  context->timer2 = timeoutMs;
+  do {
+    d = context->xchgSpi(0xFF);
+  } while (d != 0xFF && context->timer2);
+
+  return (d == 0xFF) ? INT_READY : INT_TIMEOUT;
+}
+
+
+// Deselect card and release SPI
+static void deselect(sdSpiContext_t *context) {
+  context->csHigh();
+
+  // Dummy clock (force DO hi-z for multiple slave SPI)
+  context->xchgSpi(0xFF);
+}
+
+
+static int select(sdSpiContext_t *context) {
+  context->csLow();
+
+  // Dummy clock (force DO enabled)
+  context->xchgSpi(0xFF);
+
+  if (waitForCardReady(context, 500)) {
+    return INT_READY;
+  }
+
+  deselect(context);
+  return INT_TIMEOUT;
+}
+
+
+static int receiveDataBlock(sdSpiContext_t *context, BYTE *data, UINT length) {
+  BYTE token;
+
+  context->timer1 = 200;
+  do {
+    token = context->xchgSpi(0xFF);
+  } while ((token == 0xFF) && context->timer1);
+
+  if(token != 0xFE){
+    return INT_ERROR;
+  }
+
+  // Store trailing data to the buffer
+  context->rcvrSpiMulti(data, length);
+
+  // Discard CRC
+  context->xchgSpi(0xFF);
+  context->xchgSpi(0xFF);
+
+  return INT_READY;
+}
+
+
+static int transmitDataBlock(sdSpiContext_t *context, const BYTE *data, BYTE token) {
+  if (!waitForCardReady(context, 500)) {
+    return INT_TIMEOUT;
+  }
+  
+  context->xchgSpi(token);
+
+  // Send data if token is other than StopTran
+  if (token != 0xFD) {
+    context->xmitSpiMulti(data, 512);
+
+    // Dummy CRC
+    context->xchgSpi(0xFF);
+    context->xchgSpi(0xFF);
+
+    BYTE resp = context->xchgSpi(0xFF);
+
+    if ((resp & 0x1F) != 0x05) {
+      // Data packet was not accepted
+      return INT_ERROR;
+    }
+  }
+
+  return INT_READY;
+}
+
+
+static BYTE sendCommand(sdSpiContext_t *context, BYTE cmd, DWORD arg) {
+  // Send a CMD55 prior to ACMD<n>
+  if (cmd & 0x80) {
+    cmd &= 0x7F;
+    BYTE res = sendCommand(context, CMD55, 0);
+
+    if (res > 1) {
+      return res;
+    }
+  }
+
+  // Select the card and wait for ready except to stop multiple block read
+  if(cmd == CMD0) {
+    deselect(context);
+    context->csLow();
+  } else if (cmd != CMD12) {
+    deselect(context);
+    if (!select(context)) {
+      return 0xFF;
+    }
+  }
+
+  // Start + command index
+  context->xchgSpi(0x40 | cmd);
+
+  // Argument[31..24]
+  context->xchgSpi((BYTE)(arg >> 24));
+  // Argument[23..16]
+  context->xchgSpi((BYTE)(arg >> 16));
+  // Argument[15..8]
+  context->xchgSpi((BYTE)(arg >> 8));
+  // Argument[7..0]
+  context->xchgSpi((BYTE)arg);
+
+  // Dummy CRC + Stop
+  BYTE crc = 0x01;
+  if (cmd == CMD0) {
+    crc = 0x95;
+  }
+  if (cmd == CMD8) {
+    crc = 0x87;
+  }
+  context->xchgSpi(crc);
+
+  if (cmd == CMD12) {
+    // Discard one byte when CMD12
+    context->xchgSpi(0xFF);
+  }
+
+  // Receive command resp
+  {
+    BYTE maxTries = 10;
+    BYTE res;
+    do {
+      res = context->xchgSpi(0xFF);
+    } while ((res & 0x80) && --maxTries);
+
+    // Return value: R1 resp (bit7==1:Failed to send)
+    return res;
+  }
+}
+
+
+DSTATUS SD_disk_initialize(void* usrOps) {
+  sdSpiContext_t *context = (sdSpiContext_t *)usrOps;
+
+  if (!usrOps) {
+    return RES_PARERR;
+  }
+
+  context->initSpi();
+
+  // Check is card is inserted
+  if (context->stat & STA_NODISK) {
+    return context->stat;
+  }
+
+  context->setSlowSpiMode();
+
+  // Send 80 dummy clocks (10 * 8)
+  for (BYTE n = 10; n; n--) {
+    context->xchgSpi(0xFF);
+  }
+
+  // Try to configure SD card in SPI mode
+  BYTE res = 0;
+  for (BYTE n = 100; n && res != 1; n--) {
+    res = sendCommand(context, CMD0, 0);
+  }
+
+  BYTE cardType = 0;
+
+  // Put the card SPI/Idle state
+  if (res == 1) {
+    context->timer1 = 1000;
+
+    // SDv2?
+    if (sendCommand(context, CMD8, 0x1AA) == 1) {
+      BYTE ocr[4];
+
+      // Get 32 bit return value of R7 resp
+      for (BYTE n = 0; n < 4; n++) {
+        ocr[n] = context->xchgSpi(0xFF);
+      }
+
+      // Does the card support vcc of 2.7-3.6V?
+      if (ocr[2] == 0x01 && ocr[3] == 0xAA) {
+        // Wait for end of initialization with ACMD41(HCS)
+        while (context->timer1 && sendCommand(context, ACMD41, 1UL << 30)) { /* Do nothing */ }
+
+        // Check CCS bit in the OCR
+        if (context->timer1 && sendCommand(context, CMD58, 0) == 0) {
+          for (BYTE n = 0; n < 4; n++) {
+            ocr[n] = context->xchgSpi(0xFF);
+          }
+
+          // Card id SDv2
+          cardType = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2;
+        }
+      }
+    } else {
+      BYTE cmd;
+
+      // SDv1 or MMC?
+      if (sendCommand(context, ACMD41, 0) <= 1)  {
+        // SDv1
+        cardType = CT_SD1;
+        cmd = ACMD41;
+      } else {
+        // MMCv3
+        cardType = CT_MMC;
+        cmd = CMD1;
+      }
+
+      // Wait for end of initialization
+      while (context->timer1 && sendCommand(context, cmd, 0)) { /* Do nothing */ }
+
+      // Set block length to 512
+      if (!context->timer1 || sendCommand(context, CMD16, 512) != 0) {
+        cardType = 0;
+      }
+    }
+  }
+
+  context->cardType = cardType;
+  deselect(context);
+
+  if (cardType) {
+    // OK
+    context->setFastSpiMode();
+
+    // Clear STA_NOINIT flag
+    context->stat &= ~STA_NOINIT;
+  } else {   /* Failed */
+    context->stat = STA_NOINIT;
+  }
+
+  return context->stat;
+}
+
+
+DSTATUS SD_disk_status(void * usrOps) {
+ sdSpiContext_t *context = (sdSpiContext_t *)usrOps;
+
+ return context->stat;
+}
+
+
+DRESULT SD_disk_read(BYTE *buff, DWORD sector, UINT count, void * usrOps) {
+  sdSpiContext_t *context = (sdSpiContext_t *)usrOps;
+
+  if (!usrOps || !count) {
+    return RES_PARERR;
+  }
+
+  // Check if drive is ready
+  if (context->stat & STA_NOINIT) {
+    return RES_NOTRDY;
+  }
+
+  // LBA ot BA conversion (byte addressing cards)
+  if (!(context->cardType & CT_BLOCK)) {
+    sector *= 512;
+  }
+
+  if (count == 1) {
+    // Single sector read
+    // READ_SINGLE_BLOCK
+    if ((sendCommand(context, CMD17, sector) == 0) && receiveDataBlock(context, buff, 512)) {
+      count = 0;
+    }
+  } else {
+    // Multiple sector read
+    // READ_MULTIPLE_BLOCK
+    if (sendCommand(context, CMD18, sector) == 0) {
+      do {
+        if (!receiveDataBlock(context, buff, 512)) {
+          break;
+        }
+        buff += 512;
+      } while (--count);
+
+      // STOP_TRANSMISSION
+      sendCommand(context, CMD12, 0);
+    }
+  }
+
+  deselect(context);
+
+  return count ? RES_ERROR : RES_OK;
+}
+
+
+DRESULT SD_disk_write(const BYTE *buff, DWORD sector, UINT count, void * usrOps) {
+  sdSpiContext_t *context = (sdSpiContext_t *)usrOps;
+
+  if (!usrOps || !count) {
+    return RES_PARERR;
+  }
+
+  // Check drive status
+  if (context->stat & STA_NOINIT) {
+    return RES_NOTRDY;
+  }
+
+  // Check write protect
+  if (context->stat & STA_PROTECT) {
+    return RES_WRPRT;
+  }
+
+  // LBA ==> BA conversion (byte addressing cards)
+  if (!(context->cardType & CT_BLOCK)) {
+    sector *= 512;
+  }
+
+  if (count == 1) {
+    // Single sector write
+    // WRITE_BLOCK
+    if ((sendCommand(context, CMD24, sector) == 0) && transmitDataBlock(context, buff, 0xFE)) {
+      count = 0;
+    }
+  } else {
+    // Multiple sector write
+    // Set number of sectors
+    if (context->cardType & CT_SDC) sendCommand(context, ACMD23, count);
+
+    // WRITE_MULTIPLE_BLOCK
+    if (sendCommand(context, CMD25, sector) == 0) {
+      do {
+        if (!transmitDataBlock(context, buff, 0xFC)) {
+          break;
+        }
+
+        buff += 512;
+      } while (--count);
+
+      // STOP_TRAN
+      if (!transmitDataBlock(context, 0, 0xFD)) {
+        count = 1;
+      }
+    }
+  }
+
+  deselect(context);
+
+  return count ? RES_ERROR : RES_OK;
+}
+
+
+DRESULT SD_disk_ioctl(BYTE cmd, void* buff, void* usrOps) {
+  sdSpiContext_t *context = (sdSpiContext_t *)usrOps;
+  BYTE csd[16];
+
+  if (!usrOps) {
+    return RES_PARERR;
+  }
+
+  // Check if drive is ready
+  if (context->stat & STA_NOINIT) {
+    return RES_NOTRDY;
+  }
+
+  DRESULT res = RES_ERROR;
+
+  switch (cmd) {
+    case CTRL_SYNC :
+      // Wait for end of internal write process of the drive
+      if (select(context)) {
+        res = RES_OK;
+      }
+      break;
+
+    case GET_SECTOR_COUNT :
+      // Get drive capacity in unit of sector (DWORD)
+      if ((sendCommand(context, CMD9, 0) == 0) && receiveDataBlock(context, csd, 16)) {
+        if ((csd[0] >> 6) == 1) {
+          // SDC ver 2.00
+          DWORD csize = csd[9] + ((WORD)csd[8] << 8) + ((DWORD)(csd[7] & 63) << 16) + 1;
+          *(DWORD*)buff = csize << 10;
+        } else {
+          // SDC ver 1.XX or MMC ver 3
+          BYTE n = (csd[5] & 15) + ((csd[10] & 128) >> 7) + ((csd[9] & 3) << 1) + 2;
+          DWORD csize = (csd[8] >> 6) + ((WORD)csd[7] << 2) + ((WORD)(csd[6] & 3) << 10) + 1;
+          *(DWORD*)buff = csize << (n - 9);
+        }
+        res = RES_OK;
+      }
+      break;
+
+    case GET_BLOCK_SIZE : /* Get erase block size in unit of sector (DWORD) */
+      if (context->cardType & CT_SD2) {
+        // SDC ver 2.00
+        if (sendCommand(context, ACMD13, 0) == 0) {
+          // Read SD status
+          context->xchgSpi(0xFF);
+          if (receiveDataBlock(context, csd, 16)) {
+            // Read partial block
+            for (BYTE n = 64 - 16; n; n--) {
+              // Purge trailing data
+              context->xchgSpi(0xFF);
+            }
+
+            *(DWORD*)buff = 16UL << (csd[10] >> 4);
+            res = RES_OK;
+          }
+        }
+      } else {
+        // SDC ver 1.XX or MMC
+        if ((sendCommand(context, CMD9, 0) == 0) && receiveDataBlock(context, csd, 16)) {
+          // Read CSD
+          if (context->cardType & CT_SD1) {
+            // SDC ver 1.XX
+            *(DWORD*)buff = (((csd[10] & 63) << 1) + ((WORD)(csd[11] & 128) >> 7) + 1) << ((csd[13] >> 6) - 1);
+          } else {
+            // MMC
+            *(DWORD*)buff = ((WORD)((csd[10] & 124) >> 2) + 1) * (((csd[11] & 3) << 3) + ((csd[11] & 224) >> 5) + 1);
+          }
+
+          res = RES_OK;
+        }
+      }
+      break;
+
+    case CTRL_ERASE_SECTOR :
+      // Erase a block of sectors (used when _USE_ERASE == 1)
+      // Check if the card is SDC
+      if (!(context->cardType & CT_SDC)) {
+        break;
+      }
+
+      // Get CSD
+      if (SD_disk_ioctl(MMC_GET_CSD, csd, context)) {
+        break;
+      }
+
+      // Check if sector erase can be applied to the card
+      if (!(csd[0] >> 6) && !(csd[10] & 0x40)) {
+        break;
+      }
+
+      // Load sector block
+      {
+        DWORD* dp = buff;
+        DWORD st = dp[0];
+        DWORD ed = dp[1];
+        if (!(context->cardType & CT_BLOCK)) {
+          st *= 512;
+          ed *= 512;
+        }
+
+        /* Erase sector block */
+        if (sendCommand(context, CMD32, st) == 0 && sendCommand(context, CMD33, ed) == 0 && sendCommand(context, CMD38, 0) == 0 && waitForCardReady(context, 30000)) {
+          // FatFs does not check result of this command
+          res = RES_OK;
+        }
+      }
+      break;
+
+    default:
+      res = RES_PARERR;
+  }
+
+  deselect(context);
+
+  return res;
+}
+
+
+// This function must be called from timer interrupt routine in period of 1 ms to generate card control timing.
+void SD_disk_timerproc (void* usrOps) {
+  sdSpiContext_t *context = (sdSpiContext_t *)usrOps;
+
+  {
+    WORD n = context->timer1;
+    if (n) {
+      context->timer1 = --n;
+    }
+  }
+
+  {
+    WORD n = context->timer2;
+    if (n) {
+      context->timer2 = --n;
+    }
+  }
+
+
+  BYTE s = context->stat;
+
+  // Write enabled
+  s &= ~STA_PROTECT;
+
+  // Card is in socket
+  s &= ~STA_NODISK;
+
+  context->stat = s;
+}
+
diff --git a/crazyflie-firmware-src/src/drivers/src/hmc5883l.c b/crazyflie-firmware-src/src/drivers/src/hmc5883l.c
new file mode 100644
index 0000000000000000000000000000000000000000..5d8d82384390a8968a58a2e1b1f7ca0f480bfabd
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/hmc5883l.c
@@ -0,0 +1,476 @@
+// I2Cdev library collection - HMC5883L I2C device class
+// Based on Honeywell HMC5883L datasheet, 10/2010 (Form #900405 Rev B)
+// 6/12/2012 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+
+/* ============================================
+ I2Cdev device library code is placed under the MIT license
+ Copyright (c) 2012 Jeff Rowberg
+ Adapted to Crazyflie FW by Bitcraze
+
+ Permission is hereby granted, free of charge, to any person obtaining a copy
+ of this software and associated documentation files (the "Software"), to deal
+ in the Software without restriction, including without limitation the rights
+ to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ copies of the Software, and to permit persons to whom the Software is
+ furnished to do so, subject to the following conditions:
+
+ The above copyright notice and this permission notice shall be included in
+ all copies or substantial portions of the Software.
+
+ THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ THE SOFTWARE.
+ ===============================================
+ */
+#define DEBUG_MODULE "HMC5883L"
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+// TA: Maybe not so good to bring in these dependencies...
+#include "debug.h"
+#include "eprintf.h"
+
+#include "hmc5883l.h"
+#include "i2cdev.h"
+
+static uint8_t devAddr;
+static uint8_t buffer[6];
+static uint8_t mode;
+static I2C_Dev *I2Cx;
+static bool isInit;
+
+/** Power on and prepare for general usage.
+ * This will prepare the magnetometer with default settings, ready for single-
+ * use mode (very low power requirements). Default settings include 8-sample
+ * averaging, 15 Hz data output rate, normal measurement bias, a,d 1090 gain (in
+ * terms of LSB/Gauss). Be sure to adjust any settings you need specifically
+ * after initialization, especially the gain settings if you happen to be seeing
+ * a lot of -4096 values (see the datasheet for mor information).
+ */
+void hmc5883lInit(I2C_Dev *i2cPort)
+{
+  if (isInit)
+    return;
+
+  I2Cx = i2cPort;
+  devAddr = HMC5883L_ADDRESS;
+
+  // write CONFIG_A register
+  i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_CONFIG_A,
+      (HMC5883L_AVERAGING_8 << (HMC5883L_CRA_AVERAGE_BIT - HMC5883L_CRA_AVERAGE_LENGTH + 1)) |
+      (HMC5883L_RATE_15 << (HMC5883L_CRA_RATE_BIT - HMC5883L_CRA_RATE_LENGTH + 1)) |
+      (HMC5883L_BIAS_NORMAL << (HMC5883L_CRA_BIAS_BIT - HMC5883L_CRA_BIAS_LENGTH + 1)));
+
+  // write CONFIG_B register
+  hmc5883lSetGain(HMC5883L_GAIN_660);
+
+  isInit = true;
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool hmc5883lTestConnection()
+{
+  if (i2cdevRead(I2Cx, devAddr, HMC5883L_RA_ID_A, 3, buffer))
+  {
+    return (buffer[0] == 'H' && buffer[1] == '4' && buffer[2] == '3');
+  }
+
+  return false;
+}
+
+/** Do a self test.
+ * @return True if self test passed, false otherwise
+ */
+bool hmc5883lSelfTest()
+{
+  bool testStatus = true;
+  int16_t mxp, myp, mzp;  // positive magnetometer measurements
+  int16_t mxn, myn, mzn;  // negative magnetometer measurements
+  struct
+  {
+    uint8_t configA;
+    uint8_t configB;
+    uint8_t mode;
+  } regSave;
+
+  // Save register values
+  if (i2cdevRead(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, sizeof(regSave), (uint8_t *)&regSave) == false)
+  {
+    // TODO: error handling
+    return false;
+  }
+  // Set gain (sensitivity)
+  hmc5883lSetGain(HMC5883L_ST_GAIN);
+
+  // Write CONFIG_A register and do positive test
+  i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_CONFIG_A,
+      (HMC5883L_AVERAGING_1 << (HMC5883L_CRA_AVERAGE_BIT - HMC5883L_CRA_AVERAGE_LENGTH + 1)) |
+      (HMC5883L_RATE_15 << (HMC5883L_CRA_RATE_BIT - HMC5883L_CRA_RATE_LENGTH + 1)) |
+      (HMC5883L_BIAS_POSITIVE << (HMC5883L_CRA_BIAS_BIT - HMC5883L_CRA_BIAS_LENGTH + 1)));
+
+  /* Perform test measurement & check results */
+  hmc5883lSetMode(HMC5883L_MODE_SINGLE);
+  vTaskDelay(M2T(HMC5883L_ST_DELAY_MS));
+  hmc5883lGetHeading(&mxp, &myp, &mzp);
+
+  // Write CONFIG_A register and do negative test
+  i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_CONFIG_A,
+      (HMC5883L_AVERAGING_1 << (HMC5883L_CRA_AVERAGE_BIT - HMC5883L_CRA_AVERAGE_LENGTH + 1)) |
+      (HMC5883L_RATE_15 << (HMC5883L_CRA_RATE_BIT - HMC5883L_CRA_RATE_LENGTH + 1)) |
+      (HMC5883L_BIAS_NEGATIVE << (HMC5883L_CRA_BIAS_BIT - HMC5883L_CRA_BIAS_LENGTH + 1)));
+
+  /* Perform test measurement & check results */
+  hmc5883lSetMode(HMC5883L_MODE_SINGLE);
+  vTaskDelay(M2T(HMC5883L_ST_DELAY_MS));
+  hmc5883lGetHeading(&mxn, &myn, &mzn);
+
+  if (hmc5883lEvaluateSelfTest(HMC5883L_ST_X_MIN, HMC5883L_ST_X_MAX, mxp, "pos X") &&
+      hmc5883lEvaluateSelfTest(HMC5883L_ST_Y_MIN, HMC5883L_ST_Y_MAX, myp, "pos Y") &&
+      hmc5883lEvaluateSelfTest(HMC5883L_ST_Z_MIN, HMC5883L_ST_Z_MAX, mzp, "pos Z") &&
+      hmc5883lEvaluateSelfTest(-HMC5883L_ST_X_MAX, -HMC5883L_ST_X_MIN, mxn, "neg X") &&
+      hmc5883lEvaluateSelfTest(-HMC5883L_ST_Y_MAX, -HMC5883L_ST_Y_MIN, myn, "neg Y") &&
+      hmc5883lEvaluateSelfTest(-HMC5883L_ST_Z_MAX, -HMC5883L_ST_Z_MIN, mzn, "neg Z"))
+  {
+    DEBUG_PRINT("Self test [OK].\n");
+  }
+  else
+  {
+    testStatus = false;
+  }
+
+  // Restore registers
+  if (i2cdevWrite(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, sizeof(regSave), (uint8_t *)&regSave) == false)
+  {
+    // TODO: error handling
+    return false;
+  }
+
+  return testStatus;
+}
+
+/** Evaluate the values from a HMC8335L self test.
+ * @param min The min limit of the self test
+ * @param max The max limit of the self test
+ * @param value The value to compare with.
+ * @param string A pointer to a string describing the value.
+ * @return True if self test within min - max limit, false otherwise
+ */
+bool hmc5883lEvaluateSelfTest(int16_t min, int16_t max, int16_t value, char* string)
+{
+  if (value < min || value > max)
+  {
+    DEBUG_PRINT("Self test %s [FAIL]. low: %d, high: %d, measured: %d\n",
+                string, min, max, value);
+    return false;
+  }
+  return true;
+}
+
+// CONFIG_A register
+
+/** Get number of samples averaged per measurement.
+ * @return Current samples averaged per measurement (0-3 for 1/2/4/8 respectively)
+ * @see HMC5883L_AVERAGING_8
+ * @see HMC5883L_RA_CONFIG_A
+ * @see HMC5883L_CRA_AVERAGE_BIT
+ * @see HMC5883L_CRA_AVERAGE_LENGTH
+ */
+uint8_t hmc5883lGetSampleAveraging()
+{
+  i2cdevReadBits(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_AVERAGE_BIT, HMC5883L_CRA_AVERAGE_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set number of samples averaged per measurement.
+ * @param averaging New samples averaged per measurement setting(0-3 for 1/2/4/8 respectively)
+ * @see HMC5883L_RA_CONFIG_A
+ * @see HMC5883L_CRA_AVERAGE_BIT
+ * @see HMC5883L_CRA_AVERAGE_LENGTH
+ */
+void hmc5883lSetSampleAveraging(uint8_t averaging)
+{
+  i2cdevWriteBits(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_AVERAGE_BIT, HMC5883L_CRA_AVERAGE_LENGTH, averaging);
+}
+/** Get data output rate value.
+ * The Table below shows all selectable output rates in continuous measurement
+ * mode. All three channels shall be measured within a given output rate. Other
+ * output rates with maximum rate of 160 Hz can be achieved by monitoring DRDY
+ * interrupt pin in single measurement mode.
+ *
+ * Value | Typical Data Output Rate (Hz)
+ * ------+------------------------------
+ * 0     | 0.75
+ * 1     | 1.5
+ * 2     | 3
+ * 3     | 7.5
+ * 4     | 15 (Default)
+ * 5     | 30
+ * 6     | 75
+ * 7     | Not used
+ *
+ * @return Current rate of data output to registers
+ * @see HMC5883L_RATE_15
+ * @see HMC5883L_RA_CONFIG_A
+ * @see HMC5883L_CRA_RATE_BIT
+ * @see HMC5883L_CRA_RATE_LENGTH
+ */
+uint8_t hmc5883lGetDataRate()
+{
+  i2cdevReadBits(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_RATE_BIT, HMC5883L_CRA_RATE_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set data output rate value.
+ * @param rate Rate of data output to registers
+ * @see getDataRate()
+ * @see HMC5883L_RATE_15
+ * @see HMC5883L_RA_CONFIG_A
+ * @see HMC5883L_CRA_RATE_BIT
+ * @see HMC5883L_CRA_RATE_LENGTH
+ */
+void hmc5883lSetDataRate(uint8_t rate)
+{
+  i2cdevWriteBits(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_RATE_BIT, HMC5883L_CRA_RATE_LENGTH, rate);
+}
+/** Get measurement bias value.
+ * @return Current bias value (0-2 for normal/positive/negative respectively)
+ * @see HMC5883L_BIAS_NORMAL
+ * @see HMC5883L_RA_CONFIG_A
+ * @see HMC5883L_CRA_BIAS_BIT
+ * @see HMC5883L_CRA_BIAS_LENGTH
+ */
+uint8_t hmc5883lGetMeasurementBias()
+{
+  i2cdevReadBits(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_BIAS_BIT, HMC5883L_CRA_BIAS_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set measurement bias value.
+ * @param bias New bias value (0-2 for normal/positive/negative respectively)
+ * @see HMC5883L_BIAS_NORMAL
+ * @see HMC5883L_RA_CONFIG_A
+ * @see HMC5883L_CRA_BIAS_BIT
+ * @see HMC5883L_CRA_BIAS_LENGTH
+ */
+void hmc5883lSetMeasurementBias(uint8_t bias)
+{
+  i2cdevWriteBits(I2Cx, devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_BIAS_BIT, HMC5883L_CRA_BIAS_LENGTH, bias);
+}
+
+// CONFIG_B register
+
+/** Get magnetic field gain value.
+ * The table below shows nominal gain settings. Use the "Gain" column to convert
+ * counts to Gauss. Choose a lower gain value (higher GN#) when total field
+ * strength causes overflow in one of the data output registers (saturation).
+ * The data output range for all settings is 0xF800-0x07FF (-2048 - 2047).
+ *
+ * Value | Field Range | Gain (LSB/Gauss)
+ * ------+-------------+-----------------
+ * 0     | +/- 0.88 Ga | 1370
+ * 1     | +/- 1.3 Ga  | 1090 (Default)
+ * 2     | +/- 1.9 Ga  | 820
+ * 3     | +/- 2.5 Ga  | 660
+ * 4     | +/- 4.0 Ga  | 440
+ * 5     | +/- 4.7 Ga  | 390
+ * 6     | +/- 5.6 Ga  | 330
+ * 7     | +/- 8.1 Ga  | 230
+ *
+ * @return Current magnetic field gain value
+ * @see HMC5883L_GAIN_1090
+ * @see HMC5883L_RA_CONFIG_B
+ * @see HMC5883L_CRB_GAIN_BIT
+ * @see HMC5883L_CRB_GAIN_LENGTH
+ */
+uint8_t hmc5883lGetGain()
+{
+  i2cdevReadBits(I2Cx, devAddr, HMC5883L_RA_CONFIG_B, HMC5883L_CRB_GAIN_BIT, HMC5883L_CRB_GAIN_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set magnetic field gain value.
+ * @param gain New magnetic field gain value
+ * @see getGain()
+ * @see HMC5883L_RA_CONFIG_B
+ * @see HMC5883L_CRB_GAIN_BIT
+ * @see HMC5883L_CRB_GAIN_LENGTH
+ */
+void hmc5883lSetGain(uint8_t gain)
+{
+  // use this method to guarantee that bits 4-0 are set to zero, which is a
+  // requirement specified in the datasheet; it's actually more efficient than
+  // using the I2Cdev.writeBits method
+  i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_CONFIG_B, gain << (HMC5883L_CRB_GAIN_BIT - HMC5883L_CRB_GAIN_LENGTH + 1));
+}
+
+// MODE register
+
+/** Get measurement mode.
+ * In continuous-measurement mode, the device continuously performs measurements
+ * and places the result in the data register. RDY goes high when new data is
+ * placed in all three registers. After a power-on or a write to the mode or
+ * configuration register, the first measurement set is available from all three
+ * data output registers after a period of 2/fDO and subsequent measurements are
+ * available at a frequency of fDO, where fDO is the frequency of data output.
+ *
+ * When single-measurement mode (default) is selected, device performs a single
+ * measurement, sets RDY high and returned to idle mode. Mode register returns
+ * to idle mode bit values. The measurement remains in the data output register
+ * and RDY remains high until the data output register is read or another
+ * measurement is performed.
+ *
+ * @return Current measurement mode
+ * @see HMC5883L_MODE_CONTINUOUS
+ * @see HMC5883L_MODE_SINGLE
+ * @see HMC5883L_MODE_IDLE
+ * @see HMC5883L_RA_MODE
+ * @see HMC5883L_MODEREG_BIT
+ * @see HMC5883L_MODEREG_LENGTH
+ */
+uint8_t hmc5883lGetMode()
+{
+  i2cdevReadBits(I2Cx, devAddr, HMC5883L_RA_MODE, HMC5883L_MODEREG_BIT, HMC5883L_MODEREG_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set measurement mode.
+ * @param newMode New measurement mode
+ * @see getMode()
+ * @see HMC5883L_MODE_CONTINUOUS
+ * @see HMC5883L_MODE_SINGLE
+ * @see HMC5883L_MODE_IDLE
+ * @see HMC5883L_RA_MODE
+ * @see HMC5883L_MODEREG_BIT
+ * @see HMC5883L_MODEREG_LENGTH
+ */
+void hmc5883lSetMode(uint8_t newMode)
+{
+  // use this method to guarantee that bits 7-2 are set to zero, which is a
+  // requirement specified in the datasheet; it's actually more efficient than
+  // using the I2Cdev.writeBits method
+  i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_MODE, mode << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1));
+  mode = newMode;// track to tell if we have to clear bit 7 after a read
+}
+
+// DATA* registers
+
+/** Get 3-axis heading measurements.
+ * In the event the ADC reading overflows or underflows for the given channel,
+ * or if there is a math overflow during the bias measurement, this data
+ * register will contain the value -4096. This register value will clear when
+ * after the next valid measurement is made. Note that this method automatically
+ * clears the appropriate bit in the MODE register if Single mode is active.
+ * @param x 16-bit signed integer container for X-axis heading
+ * @param y 16-bit signed integer container for Y-axis heading
+ * @param z 16-bit signed integer container for Z-axis heading
+ * @see HMC5883L_RA_DATAX_H
+ */
+void hmc5883lGetHeading(int16_t *x, int16_t *y, int16_t *z)
+{
+  i2cdevRead(I2Cx, devAddr, HMC5883L_RA_DATAX_H, 6, buffer);
+  if (mode == HMC5883L_MODE_SINGLE) i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1));
+  *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+  *y = (((int16_t)buffer[4]) << 8) | buffer[5];
+  *z = (((int16_t)buffer[2]) << 8) | buffer[3];
+}
+/** Get X-axis heading measurement.
+ * @return 16-bit signed integer with X-axis heading
+ * @see HMC5883L_RA_DATAX_H
+ */
+int16_t hmc5883lGetHeadingX()
+{
+  // each axis read requires that ALL axis registers be read, even if only
+  // one is used; this was not done ineffiently in the code by accident
+  i2cdevRead(I2Cx, devAddr, HMC5883L_RA_DATAX_H, 6, buffer);
+  if (mode == HMC5883L_MODE_SINGLE) i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1));
+  return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis heading measurement.
+ * @return 16-bit signed integer with Y-axis heading
+ * @see HMC5883L_RA_DATAY_H
+ */
+int16_t hmc5883lGetHeadingY()
+{
+  // each axis read requires that ALL axis registers be read, even if only
+  // one is used; this was not done ineffiently in the code by accident
+  i2cdevRead(I2Cx, devAddr, HMC5883L_RA_DATAX_H, 6, buffer);
+  if (mode == HMC5883L_MODE_SINGLE) i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1));
+  return (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get Z-axis heading measurement.
+ * @return 16-bit signed integer with Z-axis heading
+ * @see HMC5883L_RA_DATAZ_H
+ */
+int16_t hmc5883lGetHeadingZ()
+{
+  // each axis read requires that ALL axis registers be read, even if only
+  // one is used; this was not done ineffiently in the code by accident
+  i2cdevRead(I2Cx, devAddr, HMC5883L_RA_DATAX_H, 6, buffer);
+  if (mode == HMC5883L_MODE_SINGLE) i2cdevWriteByte(I2Cx, devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1));
+  return (((int16_t)buffer[2]) << 8) | buffer[3];
+}
+
+// STATUS register
+
+/** Get data output register lock status.
+ * This bit is set when this some but not all for of the six data output
+ * registers have been read. When this bit is set, the six data output registers
+ * are locked and any new data will not be placed in these register until one of
+ * three conditions are met: one, all six bytes have been read or the mode
+ * changed, two, the mode is changed, or three, the measurement configuration is
+ * changed.
+ * @return Data output register lock status
+ * @see HMC5883L_RA_STATUS
+ * @see HMC5883L_STATUS_LOCK_BIT
+ */
+bool hmc5883lGetLockStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, HMC5883L_RA_STATUS, HMC5883L_STATUS_LOCK_BIT, buffer);
+  return buffer[0];
+}
+/** Get data ready status.
+ * This bit is set when data is written to all six data registers, and cleared
+ * when the device initiates a write to the data output registers and after one
+ * or more of the data output registers are written to. When RDY bit is clear it
+ * shall remain cleared for 250 us. DRDY pin can be used as an alternative to
+ * the status register for monitoring the device for measurement data.
+ * @return Data ready status
+ * @see HMC5883L_RA_STATUS
+ * @see HMC5883L_STATUS_READY_BIT
+ */
+bool hmc5883lGetReadyStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, HMC5883L_RA_STATUS, HMC5883L_STATUS_READY_BIT, buffer);
+  return buffer[0];
+}
+
+// ID_* registers
+
+/** Get identification byte A
+ * @return ID_A byte (should be 01001000, ASCII value 'H')
+ */
+uint8_t hmc5883lGetIDA()
+{
+  i2cdevReadByte(I2Cx, devAddr, HMC5883L_RA_ID_A, buffer);
+  return buffer[0];
+}
+/** Get identification byte B
+ * @return ID_A byte (should be 00110100, ASCII value '4')
+ */
+uint8_t hmc5883lGetIDB()
+{
+  i2cdevReadByte(I2Cx, devAddr, HMC5883L_RA_ID_B, buffer);
+  return buffer[0];
+}
+/** Get identification byte C
+ * @return ID_A byte (should be 00110011, ASCII value '3')
+ */
+uint8_t hmc5883lGetIDC()
+{
+  i2cdevReadByte(I2Cx, devAddr, HMC5883L_RA_ID_C, buffer);
+  return buffer[0];
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/i2c_drv.c b/crazyflie-firmware-src/src/drivers/src/i2c_drv.c
new file mode 100644
index 0000000000000000000000000000000000000000..df2c94080d865730dfe490cb614c67291605da1f
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/i2c_drv.c
@@ -0,0 +1,667 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie 2.0 NRF Firmware
+ * Copyright (c) 2014, Bitcraze AB, All rights reserved.
+ *
+ * This library is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU Lesser General Public
+ * License as published by the Free Software Foundation; either
+ * version 3.0 of the License, or (at your option) any later version.
+ *
+ * This library is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+ * Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public
+ * License along with this library.
+ *
+ * i2c_drv.c - i2c driver implementation
+ *
+ * @note
+ * For some reason setting CR1 reg in sequence with
+ * I2C_AcknowledgeConfig(I2C_SENSORS, ENABLE) and after
+ * I2C_GenerateSTART(I2C_SENSORS, ENABLE) sometimes creates an
+ * instant start->stop condition (3.9us long) which I found out with an I2C
+ * analyzer. This fast start->stop is only possible to generate if both
+ * start and stop flag is set in CR1 at the same time. So i tried setting the CR1
+ * at once with I2C_SENSORS->CR1 = (I2C_CR1_START | I2C_CR1_ACK | I2C_CR1_PE) and the
+ * problem is gone. Go figure...
+ */
+
+// Standard includes.
+#include <string.h>
+// Scheduler include files.
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "semphr.h"
+
+#include "stm32fxxx.h"
+// Application includes.
+#include "i2c_drv.h"
+#include "config.h"
+#include "nvicconf.h"
+
+//DEBUG
+#ifdef I2CDRV_DEBUG_LOG_EVENTS
+#include "usec_time.h"
+#endif
+
+// Definitions of sensors I2C bus
+#define I2C_SENSORS_CLOCK_SPEED             400000
+
+// Definition of eeprom and deck I2C buss
+#define I2C_DECK_CLOCK_SPEED                400000
+
+// Misc constants.
+#define I2C_NO_BLOCK				    0
+#define I2C_SLAVE_ADDRESS7      0x30
+#define I2C_MAX_RETRIES         2
+#define I2C_MESSAGE_TIMEOUT     M2T(1000)
+
+// Delay is approx 0.06us per loop @168Mhz
+#define I2CDEV_LOOPS_PER_US  17
+#define I2CDEV_LOOPS_PER_MS  (16789) // measured
+
+// Defines to unlock bus
+#define I2CDEV_CLK_TS (10 * I2CDEV_LOOPS_PER_US)
+#define GPIO_WAIT_FOR_HIGH(gpio, pin, timeoutcycles)\
+  {\
+    int i = timeoutcycles;\
+    while(GPIO_ReadInputDataBit(gpio, pin) == Bit_RESET && i--);\
+  }
+
+#define GPIO_WAIT_FOR_LOW(gpio, pin, timeoutcycles) \
+  {\
+    int i = timeoutcycles;\
+    while(GPIO_ReadInputDataBit(gpio, pin) == Bit_SET && i--);\
+  }
+
+
+#ifdef I2CDRV_DEBUG_LOG_EVENTS
+// Debug variables
+uint32_t eventDebug[1024][2];
+uint32_t eventPos = 0;
+#endif
+
+/* Private functions */
+/**
+ * Low level i2c init funciton
+ */
+static void i2cdrvInitBus(I2cDrv* i2c);
+/**
+ * Low level dma init funciton
+ */
+static void i2cdrvDmaSetupBus(I2cDrv* i2c);
+/**
+ * Start the i2c transfer
+ */
+static void i2cdrvStartTransfer(I2cDrv *i2c);
+/**
+ * Try to restart a hanged buss
+ */
+static void i2cdrvTryToRestartBus(I2cDrv* i2c);
+/**
+ * Rough spin loop delay.
+ */
+static inline void i2cdrvRoughLoopDelay(uint32_t us) __attribute__((optimize("O2")));
+/**
+ * Unlocks the i2c bus if needed.
+ */
+static void i2cdrvdevUnlockBus(GPIO_TypeDef* portSCL, GPIO_TypeDef* portSDA, uint16_t pinSCL, uint16_t pinSDA);
+/**
+ * Clear DMA stream
+ */
+static void i2cdrvClearDMA(I2cDrv* i2c);
+/**
+ * Event interrupt service routine
+ */
+static void i2cdrvEventIsrHandler(I2cDrv* i2c);
+/**
+ * Error interrupt service routine
+ */
+static void i2cdrvErrorIsrHandler(I2cDrv* i2c);
+/**
+ * DMA interrupt service routine
+ */
+static void i2cdrvDmaIsrHandler(I2cDrv* i2c);
+
+// Cost definitions of busses
+static const I2cDef sensorBusDef =
+{
+  .i2cPort            = I2C3,
+  .i2cPerif           = RCC_APB1Periph_I2C3,
+  .i2cEVIRQn          = I2C3_EV_IRQn,
+  .i2cERIRQn          = I2C3_ER_IRQn,
+  .i2cClockSpeed      = I2C_SENSORS_CLOCK_SPEED,
+  .gpioSCLPerif       = RCC_AHB1Periph_GPIOA,
+  .gpioSCLPort        = GPIOA,
+  .gpioSCLPin         = GPIO_Pin_8,
+  .gpioSCLPinSource   = GPIO_PinSource8,
+  .gpioSDAPerif       = RCC_AHB1Periph_GPIOC,
+  .gpioSDAPort        = GPIOC,
+  .gpioSDAPin         = GPIO_Pin_9,
+  .gpioSDAPinSource   = GPIO_PinSource9,
+  .gpioAF             = GPIO_AF_I2C3,
+  .dmaPerif           = RCC_AHB1Periph_DMA1,
+  .dmaChannel         = DMA_Channel_3,
+  .dmaRxStream        = DMA1_Stream2,
+  .dmaRxIRQ           = DMA1_Stream2_IRQn,
+  .dmaRxTCFlag        = DMA_FLAG_TCIF2,
+  .dmaRxTEFlag        = DMA_FLAG_TEIF2,
+};
+
+I2cDrv sensorsBus =
+{
+  .def                = &sensorBusDef,
+};
+
+static const I2cDef deckBusDef =
+{
+  .i2cPort            = I2C1,
+  .i2cPerif           = RCC_APB1Periph_I2C1,
+  .i2cEVIRQn          = I2C1_EV_IRQn,
+  .i2cERIRQn          = I2C1_ER_IRQn,
+  .i2cClockSpeed      = I2C_DECK_CLOCK_SPEED,
+  .gpioSCLPerif       = RCC_AHB1Periph_GPIOB,
+  .gpioSCLPort        = GPIOB,
+  .gpioSCLPin         = GPIO_Pin_6,
+  .gpioSCLPinSource   = GPIO_PinSource6,
+  .gpioSDAPerif       = RCC_AHB1Periph_GPIOB,
+  .gpioSDAPort        = GPIOB,
+  .gpioSDAPin         = GPIO_Pin_7,
+  .gpioSDAPinSource   = GPIO_PinSource7,
+  .gpioAF             = GPIO_AF_I2C1,
+  .dmaPerif           = RCC_AHB1Periph_DMA1,
+  .dmaChannel         = DMA_Channel_1,
+  .dmaRxStream        = DMA1_Stream0,
+  .dmaRxIRQ           = DMA1_Stream0_IRQn,
+  .dmaRxTCFlag        = DMA_FLAG_TCIF0,
+  .dmaRxTEFlag        = DMA_FLAG_TEIF0,
+};
+
+I2cDrv deckBus =
+{
+  .def                = &deckBusDef,
+};
+
+
+static inline void i2cdrvRoughLoopDelay(uint32_t us)
+{
+  volatile uint32_t delay = 0;
+  for(delay = 0; delay < I2CDEV_LOOPS_PER_US * us; ++delay) { };
+}
+
+static void i2cdrvStartTransfer(I2cDrv *i2c)
+{
+  if (i2c->txMessage.direction == i2cRead)
+  {
+    i2c->DMAStruct.DMA_BufferSize = i2c->txMessage.messageLength;
+    i2c->DMAStruct.DMA_Memory0BaseAddr = (uint32_t)i2c->txMessage.buffer;
+    DMA_Init(i2c->def->dmaRxStream, &i2c->DMAStruct);
+    DMA_Cmd(i2c->def->dmaRxStream, ENABLE);
+  }
+
+  I2C_ITConfig(i2c->def->i2cPort, I2C_IT_BUF, DISABLE);
+  I2C_ITConfig(i2c->def->i2cPort, I2C_IT_EVT, ENABLE);
+  i2c->def->i2cPort->CR1 = (I2C_CR1_START | I2C_CR1_PE);
+}
+
+static void i2cTryNextMessage(I2cDrv* i2c)
+{
+  i2c->def->i2cPort->CR1 = (I2C_CR1_STOP | I2C_CR1_PE);
+  I2C_ITConfig(i2c->def->i2cPort, I2C_IT_EVT | I2C_IT_BUF, DISABLE);
+}
+
+static void i2cNotifyClient(I2cDrv* i2c)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+  xSemaphoreGiveFromISR(i2c->isBusFreeSemaphore, &xHigherPriorityTaskWoken);
+  portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
+}
+
+static void i2cdrvTryToRestartBus(I2cDrv* i2c)
+{
+  i2cdrvInitBus(i2c);
+}
+
+static void i2cdrvDmaSetupBus(I2cDrv* i2c)
+{
+
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  RCC_AHB1PeriphClockCmd(i2c->def->dmaPerif, ENABLE);
+
+  // RX DMA Channel Config
+  i2c->DMAStruct.DMA_Channel = i2c->def->dmaChannel;
+  i2c->DMAStruct.DMA_PeripheralBaseAddr = (uint32_t)&i2c->def->i2cPort->DR;
+  i2c->DMAStruct.DMA_Memory0BaseAddr = 0;
+  i2c->DMAStruct.DMA_DIR = DMA_DIR_PeripheralToMemory;
+  i2c->DMAStruct.DMA_BufferSize = 0;
+  i2c->DMAStruct.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+  i2c->DMAStruct.DMA_MemoryInc = DMA_MemoryInc_Enable;
+  i2c->DMAStruct.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+  i2c->DMAStruct.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+  i2c->DMAStruct.DMA_Mode = DMA_Mode_Normal;
+  i2c->DMAStruct.DMA_Priority = DMA_Priority_High;
+  i2c->DMAStruct.DMA_FIFOMode = DMA_FIFOMode_Disable;
+  i2c->DMAStruct.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
+  i2c->DMAStruct.DMA_MemoryBurst = DMA_MemoryBurst_Single;
+  i2c->DMAStruct.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+
+  NVIC_InitStructure.NVIC_IRQChannel = i2c->def->dmaRxIRQ;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+}
+
+static void i2cdrvInitBus(I2cDrv* i2c)
+{
+  I2C_InitTypeDef  I2C_InitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  // Enable GPIOA clock
+  RCC_AHB1PeriphClockCmd(i2c->def->gpioSDAPerif, ENABLE);
+  RCC_AHB1PeriphClockCmd(i2c->def->gpioSCLPerif, ENABLE);
+  // Enable I2C_SENSORS clock
+  RCC_APB1PeriphClockCmd(i2c->def->i2cPerif, ENABLE);
+
+  // Configure I2C_SENSORS pins to unlock bus.
+  GPIO_StructInit(&GPIO_InitStructure);
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
+  GPIO_InitStructure.GPIO_Pin = i2c->def->gpioSCLPin; // SCL
+  GPIO_Init(i2c->def->gpioSCLPort, &GPIO_InitStructure);
+  GPIO_InitStructure.GPIO_Pin =  i2c->def->gpioSDAPin; // SDA
+  GPIO_Init(i2c->def->gpioSDAPort, &GPIO_InitStructure);
+
+  i2cdrvdevUnlockBus(i2c->def->gpioSCLPort, i2c->def->gpioSDAPort, i2c->def->gpioSCLPin, i2c->def->gpioSDAPin);
+
+  // Configure I2C_SENSORS pins for AF.
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_Pin = i2c->def->gpioSCLPin; // SCL
+  GPIO_Init(i2c->def->gpioSCLPort, &GPIO_InitStructure);
+  GPIO_InitStructure.GPIO_Pin =  i2c->def->gpioSDAPin; // SDA
+  GPIO_Init(i2c->def->gpioSDAPort, &GPIO_InitStructure);
+
+  //Map gpios to alternate functions
+  GPIO_PinAFConfig(i2c->def->gpioSCLPort, i2c->def->gpioSCLPinSource, i2c->def->gpioAF);
+  GPIO_PinAFConfig(i2c->def->gpioSDAPort, i2c->def->gpioSDAPinSource, i2c->def->gpioAF);
+
+  // I2C_SENSORS configuration
+  I2C_DeInit(i2c->def->i2cPort);
+  I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+  I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+  I2C_InitStructure.I2C_OwnAddress1 = I2C_SLAVE_ADDRESS7;
+  I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+  I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+  I2C_InitStructure.I2C_ClockSpeed = i2c->def->i2cClockSpeed;
+  I2C_Init(i2c->def->i2cPort, &I2C_InitStructure);
+
+  // Enable I2C_SENSORS error interrupts
+  I2C_ITConfig(i2c->def->i2cPort, I2C_IT_ERR, ENABLE);
+
+  NVIC_InitStructure.NVIC_IRQChannel = i2c->def->i2cEVIRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+  NVIC_InitStructure.NVIC_IRQChannel = i2c->def->i2cERIRQn;
+  NVIC_Init(&NVIC_InitStructure);
+
+  i2cdrvDmaSetupBus(i2c);
+
+  i2c->isBusFreeSemaphore = xSemaphoreCreateBinary();
+  i2c->isBusFreeMutex = xSemaphoreCreateMutex();
+}
+
+static void i2cdrvdevUnlockBus(GPIO_TypeDef* portSCL, GPIO_TypeDef* portSDA, uint16_t pinSCL, uint16_t pinSDA)
+{
+  GPIO_SetBits(portSDA, pinSDA);
+  /* Check SDA line to determine if slave is asserting bus and clock out if so */
+  while(GPIO_ReadInputDataBit(portSDA, pinSDA) == Bit_RESET)
+  {
+    /* Set clock high */
+    GPIO_SetBits(portSCL, pinSCL);
+    /* Wait for any clock stretching to finish. */
+    GPIO_WAIT_FOR_HIGH(portSCL, pinSCL, 10 * I2CDEV_LOOPS_PER_MS);
+    i2cdrvRoughLoopDelay(I2CDEV_CLK_TS);
+
+    /* Generate a clock cycle */
+    GPIO_ResetBits(portSCL, pinSCL);
+    i2cdrvRoughLoopDelay(I2CDEV_CLK_TS);
+    GPIO_SetBits(portSCL, pinSCL);
+    i2cdrvRoughLoopDelay(I2CDEV_CLK_TS);
+  }
+
+  /* Generate a start then stop condition */
+  GPIO_SetBits(portSCL, pinSCL);
+  i2cdrvRoughLoopDelay(I2CDEV_CLK_TS);
+  GPIO_ResetBits(portSDA, pinSDA);
+  i2cdrvRoughLoopDelay(I2CDEV_CLK_TS);
+  GPIO_ResetBits(portSDA, pinSDA);
+  i2cdrvRoughLoopDelay(I2CDEV_CLK_TS);
+
+  /* Set data and clock high and wait for any clock stretching to finish. */
+  GPIO_SetBits(portSDA, pinSDA);
+  GPIO_SetBits(portSCL, pinSCL);
+  GPIO_WAIT_FOR_HIGH(portSCL, pinSCL, 10 * I2CDEV_LOOPS_PER_MS);
+  /* Wait for data to be high */
+  GPIO_WAIT_FOR_HIGH(portSDA, pinSDA, 10 * I2CDEV_LOOPS_PER_MS);
+}
+
+//-----------------------------------------------------------
+
+void i2cdrvInit(I2cDrv* i2c)
+{
+  i2cdrvInitBus(i2c);
+
+#ifdef I2CDRV_DEBUG_LOG_EVENTS
+  initUsecTimer();
+#endif
+}
+
+void i2cdrvCreateMessage(I2cMessage *message,
+                      uint8_t  slaveAddress,
+                      uint8_t  direction,
+                      uint32_t length,
+                      uint8_t  *buffer)
+{
+  message->slaveAddress = slaveAddress;
+  message->direction = direction;
+  message->isInternal16bit = false;
+  message->internalAddress = I2C_NO_INTERNAL_ADDRESS;
+  message->messageLength = length;
+  message->status = i2cAck;
+  message->buffer = buffer;
+  message->nbrOfRetries = I2C_MAX_RETRIES;
+}
+
+void i2cdrvCreateMessageIntAddr(I2cMessage *message,
+                             uint8_t  slaveAddress,
+                             bool IsInternal16,
+                             uint16_t intAddress,
+                             uint8_t  direction,
+                             uint32_t length,
+                             uint8_t  *buffer)
+{
+  message->slaveAddress = slaveAddress;
+  message->direction = direction;
+  message->isInternal16bit = IsInternal16;
+  message->internalAddress = intAddress;
+  message->messageLength = length;
+  message->status = i2cAck;
+  message->buffer = buffer;
+  message->nbrOfRetries = I2C_MAX_RETRIES;
+}
+
+bool i2cdrvMessageTransfer(I2cDrv* i2c, I2cMessage* message)
+{
+  bool status = false;
+
+  xSemaphoreTake(i2c->isBusFreeMutex, portMAX_DELAY); // Protect message data
+  // Copy message
+  memcpy((char*)&i2c->txMessage, (char*)message, sizeof(I2cMessage));
+  // We can now start the ISR sending this message.
+  i2cdrvStartTransfer(i2c);
+  // Wait for transaction to be done
+  if (xSemaphoreTake(i2c->isBusFreeSemaphore, I2C_MESSAGE_TIMEOUT) == pdTRUE)
+  {
+    if (i2c->txMessage.status == i2cAck)
+    {
+      status = true;
+    }
+  }
+  else
+  {
+    i2cdrvClearDMA(i2c);
+    i2cdrvTryToRestartBus(i2c);
+    //TODO: If bus is really hanged... fail safe
+  }
+  xSemaphoreGive(i2c->isBusFreeMutex);
+
+  return status;
+}
+
+
+static void i2cdrvEventIsrHandler(I2cDrv* i2c)
+{
+  uint16_t SR1;
+  uint16_t SR2;
+
+  // read the status register first
+  SR1 = i2c->def->i2cPort->SR1;
+
+#ifdef I2CDRV_DEBUG_LOG_EVENTS
+  // Debug code
+  eventDebug[eventPos][0] = usecTimestamp();
+  eventDebug[eventPos][1] = SR1;
+  if (++eventPos == 1024)
+  {
+    eventPos = 0;
+  }
+#endif
+
+  // Start bit event
+  if (SR1 & I2C_SR1_SB)
+  {
+    i2c->messageIndex = 0;
+
+    if(i2c->txMessage.direction == i2cWrite ||
+       i2c->txMessage.internalAddress != I2C_NO_INTERNAL_ADDRESS)
+    {
+      I2C_Send7bitAddress(i2c->def->i2cPort, i2c->txMessage.slaveAddress << 1, I2C_Direction_Transmitter);
+    }
+    else
+    {
+      I2C_AcknowledgeConfig(i2c->def->i2cPort, ENABLE);
+      I2C_Send7bitAddress(i2c->def->i2cPort, i2c->txMessage.slaveAddress << 1, I2C_Direction_Receiver);
+    }
+  }
+  // Address event
+  else if (SR1 & I2C_SR1_ADDR)
+  {
+    if(i2c->txMessage.direction == i2cWrite ||
+       i2c->txMessage.internalAddress != I2C_NO_INTERNAL_ADDRESS)
+    {
+      SR2 = i2c->def->i2cPort->SR2;                               // clear ADDR
+      // In write mode transmit is always empty so can send up to two bytes
+      if (i2c->txMessage.internalAddress != I2C_NO_INTERNAL_ADDRESS)
+      {
+        if (i2c->txMessage.isInternal16bit)
+        {
+          I2C_SendData(i2c->def->i2cPort, (i2c->txMessage.internalAddress & 0xFF00) >> 8);
+          I2C_SendData(i2c->def->i2cPort, (i2c->txMessage.internalAddress & 0x00FF));
+        }
+        else
+        {
+          I2C_SendData(i2c->def->i2cPort, (i2c->txMessage.internalAddress & 0x00FF));
+        }
+        i2c->txMessage.internalAddress = I2C_NO_INTERNAL_ADDRESS;
+      }
+      I2C_ITConfig(i2c->def->i2cPort, I2C_IT_BUF, ENABLE);        // allow us to have an EV7
+    }
+    else // Reading, start DMA transfer
+    {
+      if(i2c->txMessage.messageLength == 1)
+      {
+        I2C_AcknowledgeConfig(i2c->def->i2cPort, DISABLE);
+      }
+      else
+      {
+        I2C_DMALastTransferCmd(i2c->def->i2cPort, ENABLE); // No repetitive start
+      }
+      // Disable buffer I2C interrupts
+      I2C_ITConfig(i2c->def->i2cPort, I2C_IT_EVT | I2C_IT_BUF, DISABLE);
+      // Enable the Transfer Complete interrupt
+      DMA_ITConfig(i2c->def->dmaRxStream, DMA_IT_TC | DMA_IT_TE, ENABLE);
+      I2C_DMACmd(i2c->def->i2cPort, ENABLE); // Enable before ADDR clear
+
+      __DMB();                         // Make sure instructions (clear address) are in correct order
+      SR2 = i2c->def->i2cPort->SR2;    // clear ADDR
+    }
+  }
+  // Byte transfer finished
+  else if (SR1 & I2C_SR1_BTF)
+  {
+    SR2 = i2c->def->i2cPort->SR2;
+    if (SR2 & I2C_SR2_TRA) // In write mode?
+    {
+      if (i2c->txMessage.direction == i2cRead) // internal address read
+      {
+        /* Internal address written, switch to read */
+        i2c->def->i2cPort->CR1 = (I2C_CR1_START | I2C_CR1_PE); // Generate start
+      }
+      else
+      {
+        i2cNotifyClient(i2c);
+        // Are there any other messages to transact? If so stop else repeated start.
+        i2cTryNextMessage(i2c);
+      }
+    }
+    else // Reading. Shouldn't happen since we use DMA for reading.
+    {
+      ASSERT(1);
+      i2c->txMessage.buffer[i2c->messageIndex++] = I2C_ReceiveData(i2c->def->i2cPort);
+      if(i2c->messageIndex == i2c->txMessage.messageLength)
+      {
+        i2cNotifyClient(i2c);
+        // Are there any other messages to transact?
+        i2cTryNextMessage(i2c);
+      }
+    }
+    // A second BTF interrupt might occur if we don't wait for it to clear.
+    // TODO Implement better method.
+    while (i2c->def->i2cPort->CR1 & 0x0100) { ; }
+  }
+  // Byte received
+  else if (SR1 & I2C_SR1_RXNE) // Should not happen when we use DMA for reception.
+  {
+    i2c->txMessage.buffer[i2c->messageIndex++] = I2C_ReceiveData(i2c->def->i2cPort);
+    if(i2c->messageIndex == i2c->txMessage.messageLength)
+    {
+      I2C_ITConfig(i2c->def->i2cPort, I2C_IT_BUF, DISABLE);   // disable RXE to get BTF
+    }
+  }
+  // Byte ready to be transmitted
+  else if (SR1 & I2C_SR1_TXE)
+  {
+    if (i2c->txMessage.direction == i2cRead)
+    {
+      // Disable TXE to flush and get BTF to switch to read.
+      // Switch must be done in BTF or strange things happen.
+      I2C_ITConfig(i2c->def->i2cPort, I2C_IT_BUF, DISABLE);
+    }
+    else
+    {
+      I2C_SendData(i2c->def->i2cPort, i2c->txMessage.buffer[i2c->messageIndex++]);
+      if(i2c->messageIndex == i2c->txMessage.messageLength)
+      {
+        // Disable TXE to allow the buffer to flush and get BTF
+        I2C_ITConfig(i2c->def->i2cPort, I2C_IT_BUF, DISABLE);
+      }
+    }
+  }
+}
+
+
+static void i2cdrvErrorIsrHandler(I2cDrv* i2c)
+{
+  if (I2C_GetFlagStatus(i2c->def->i2cPort, I2C_FLAG_AF))
+  {
+    if(i2c->txMessage.nbrOfRetries-- > 0)
+    {
+      // Retry by generating start
+      i2c->def->i2cPort->CR1 = (I2C_CR1_START | I2C_CR1_PE);
+    }
+    else
+    {
+      // Failed so notify client and try next message if any.
+      i2c->txMessage.status = i2cNack;
+      i2cNotifyClient(i2c);
+      i2cTryNextMessage(i2c);
+    }
+    I2C_ClearFlag(i2c->def->i2cPort, I2C_FLAG_AF);
+  }
+  if (I2C_GetFlagStatus(i2c->def->i2cPort, I2C_FLAG_BERR))
+  {
+      I2C_ClearFlag(i2c->def->i2cPort, I2C_FLAG_BERR);
+  }
+  if (I2C_GetFlagStatus(i2c->def->i2cPort, I2C_FLAG_OVR))
+  {
+      I2C_ClearFlag(i2c->def->i2cPort, I2C_FLAG_OVR);
+  }
+  if (I2C_GetFlagStatus(i2c->def->i2cPort, I2C_FLAG_ARLO))
+  {
+      I2C_ClearFlag(i2c->def->i2cPort,I2C_FLAG_ARLO);
+  }
+}
+
+static void i2cdrvClearDMA(I2cDrv* i2c)
+{
+  DMA_Cmd(i2c->def->dmaRxStream, DISABLE);
+  DMA_ClearITPendingBit(i2c->def->dmaRxStream, i2c->def->dmaRxTCFlag);
+  I2C_DMACmd(i2c->def->i2cPort, DISABLE);
+  I2C_DMALastTransferCmd(i2c->def->i2cPort, DISABLE);
+  DMA_ITConfig(i2c->def->dmaRxStream, DMA_IT_TC | DMA_IT_TE, DISABLE);
+}
+
+static void i2cdrvDmaIsrHandler(I2cDrv* i2c)
+{
+  if (DMA_GetFlagStatus(i2c->def->dmaRxStream, i2c->def->dmaRxTCFlag)) // Tranasfer complete
+  {
+    i2cdrvClearDMA(i2c);
+    i2cNotifyClient(i2c);
+    // Are there any other messages to transact?
+    i2cTryNextMessage(i2c);
+  }
+  if (DMA_GetFlagStatus(i2c->def->dmaRxStream, i2c->def->dmaRxTEFlag)) // Transfer error
+  {
+    DMA_ClearITPendingBit(i2c->def->dmaRxStream, i2c->def->dmaRxTEFlag);
+    //TODO: Best thing we could do?
+    i2c->txMessage.status = i2cNack;
+    i2cNotifyClient(i2c);
+    i2cTryNextMessage(i2c);
+  }
+}
+
+
+void __attribute__((used)) I2C1_ER_IRQHandler(void)
+{
+  i2cdrvErrorIsrHandler(&deckBus);
+}
+
+void __attribute__((used)) I2C1_EV_IRQHandler(void)
+{
+  i2cdrvEventIsrHandler(&deckBus);
+}
+
+void __attribute__((used)) DMA1_Stream0_IRQHandler(void)
+{
+  i2cdrvDmaIsrHandler(&deckBus);
+}
+
+void __attribute__((used)) I2C3_ER_IRQHandler(void)
+{
+  i2cdrvErrorIsrHandler(&sensorsBus);
+}
+
+void __attribute__((used)) I2C3_EV_IRQHandler(void)
+{
+  i2cdrvEventIsrHandler(&sensorsBus);
+}
+
+void __attribute__((used)) DMA1_Stream2_IRQHandler(void)
+{
+  i2cdrvDmaIsrHandler(&sensorsBus);
+}
+
diff --git a/crazyflie-firmware-src/src/drivers/src/i2cdev_f103.c b/crazyflie-firmware-src/src/drivers/src/i2cdev_f103.c
new file mode 100644
index 0000000000000000000000000000000000000000..292ef06dda9c46d861f44754313ec9e177735a53
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/i2cdev_f103.c
@@ -0,0 +1,435 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * i2cdev.c - Functions to write to I2C devices
+ */
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "i2cdev.h"
+
+#include "nvicconf.h"
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+
+#include "stm32f10x.h"
+
+#include "i2croutines.h"
+
+#define I2C_TIMEOUT 5
+#define I2CDEV_CLK_TS (1000000 / 100000)
+
+#define I2CDEV_I2C1_PIN_SDA GPIO_Pin_7
+#define I2CDEV_I2C1_PIN_SCL GPIO_Pin_6
+
+#define I2CDEV_I2C2_PIN_SDA GPIO_Pin_11
+#define I2CDEV_I2C2_PIN_SCL GPIO_Pin_10
+
+#define GPIO_WAIT_LOW(gpio, pin, timeoutcycles)\
+  {\
+    int i = timeoutcycles;\
+    while(GPIO_ReadInputDataBit(gpio, pin) == Bit_RESET && i--);\
+  }
+
+#define GPIO_WAIT_HIGH(gpio, pin, timeoutcycles) \
+  {\
+    int i = timeoutcycles;\
+    while(GPIO_ReadInputDataBit(gpio, pin) == Bit_SET && i--);\
+  }
+
+xSemaphoreHandle i2cdevDmaEventI2c1;
+xSemaphoreHandle i2cdevDmaEventI2c2;
+/* Buffer of data to be received by I2C1 */
+uint8_t* Buffer_Rx1;
+/* Buffer of data to be transmitted by I2C1 */
+uint8_t* Buffer_Tx1;
+__IO uint32_t I2CDirection;
+
+static void i2cdevResetAndLowLevelInitBusI2c1(void);
+static void i2cdevResetAndLowLevelInitBusI2c2(void);
+static inline void i2cdevRoughLoopDelay(uint32_t us);
+
+
+int i2cdevInit(I2C_Dev *I2Cx)
+{
+  NVIC_InitTypeDef NVIC_InitStructure;
+  
+  if (I2Cx == I2C1)
+  {
+    i2cdevResetAndLowLevelInitBusI2c1();
+    // Enable the DMA1 channel6 Interrupt
+    NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel6_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_ADC_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+
+    // Enable the DMA1 channel7 Interrupt
+    NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel7_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_ADC_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+
+    // Enable the I2C error interrupt
+    NVIC_InitStructure.NVIC_IRQChannel = I2C1_ER_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_ADC_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+
+    DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE);
+    DMA_ITConfig(DMA1_Channel7, DMA_IT_TC, ENABLE);
+    vSemaphoreCreateBinary(i2cdevDmaEventI2c1);
+  }
+  else if (I2Cx == I2C2)
+  {
+    i2cdevResetAndLowLevelInitBusI2c2();
+    // Enable the DMA1 channel4 Interrupt
+    NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_ADC_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+
+    // Enable the DMA1 channel5 Interrupt
+    NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel5_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_ADC_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+
+    // Enable the I2C error interrupt
+    NVIC_InitStructure.NVIC_IRQChannel = I2C2_ER_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_ADC_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+
+    DMA_ITConfig(DMA1_Channel4, DMA_IT_TC, ENABLE);
+    DMA_ITConfig(DMA1_Channel5, DMA_IT_TC, ENABLE);
+    vSemaphoreCreateBinary(i2cdevDmaEventI2c2);
+  }
+  else
+  {
+    return FALSE;
+  }
+  
+  return TRUE;
+}
+
+bool i2cdevReadByte(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t *data)
+{
+  return i2cdevRead(I2Cx, devAddress, memAddress, 1, data);
+}
+
+bool i2cdevReadBit(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+                     uint8_t bitNum, uint8_t *data)
+{
+  uint8_t byte;
+  bool status;
+  
+  status = i2cdevRead(I2Cx, devAddress, memAddress, 1, &byte);
+  *data = byte & (1 << bitNum);
+
+  return status;
+}
+
+bool i2cdevReadBits(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t bitStart, uint8_t length, uint8_t *data)
+{
+  bool status;
+  uint8_t byte;
+
+  if ((status = i2cdevReadByte(I2Cx, devAddress, memAddress, &byte)) == TRUE)
+  {
+      uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+      byte &= mask;
+      byte >>= (bitStart - length + 1);
+      *data = byte;
+  }
+  return status;
+}
+
+bool i2cdevRead(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+               uint16_t len, uint8_t *data)
+{
+  bool status = TRUE;
+
+  if (memAddress != I2CDEV_NO_MEM_ADDR)
+  {
+    status = I2C_Master_BufferWrite(I2Cx, &memAddress,  1, INTERRUPT, devAddress << 1, I2C_TIMEOUT);
+  }
+  if (status)
+  {
+    //TODO: Fix DMA transfer if more then 3 bytes
+    status = I2C_Master_BufferRead(I2Cx, (uint8_t*)data,  len, INTERRUPT, devAddress << 1, I2C_TIMEOUT);
+  }
+
+  return status;
+}
+
+bool i2cdevRead16(I2C_Dev *dev, uint8_t devAddress, uint16_t memAddress,
+               uint16_t len, uint8_t *data)
+{
+  // TODO: Implement
+  return false;
+}
+
+bool i2cdevWriteByte(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t data)
+{
+  return i2cdevWrite(I2Cx, devAddress, memAddress, 1, &data);
+}
+
+bool i2cdevWrite16(I2C_Dev *dev, uint8_t devAddress, uint16_t memAddress,
+                   uint16_t len, uint8_t *data)
+{
+  // TODO: Implement
+  return false;
+}
+
+bool i2cdevWriteBit(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t bitNum, uint8_t data)
+{
+    uint8_t byte;
+    i2cdevReadByte(I2Cx, devAddress, memAddress, &byte);
+    byte = (data != 0) ? (byte | (1 << bitNum)) : (byte & ~(1 << bitNum));
+    return i2cdevWriteByte(I2Cx, devAddress, memAddress, byte);
+}
+
+bool i2cdevWriteBits(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+                     uint8_t bitStart, uint8_t length, uint8_t data)
+{
+  bool status;
+  uint8_t byte;
+
+  if ((status = i2cdevReadByte(I2Cx, devAddress, memAddress, &byte)) == TRUE)
+  {
+      uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+      data <<= (bitStart - length + 1); // shift data into correct position
+      data &= mask; // zero all non-important bits in data
+      byte &= ~(mask); // zero all important bits in existing byte
+      byte |= data; // combine data with existing byte
+      status = i2cdevWriteByte(I2Cx, devAddress, memAddress, byte);
+  }
+
+  return status;
+}
+
+bool i2cdevWrite(I2C_Dev *I2Cx, uint8_t devAddress, uint8_t memAddress,
+                uint16_t len, uint8_t *data)
+{
+  bool status;
+  static uint8_t buffer[17];
+  int i;
+
+  if (memAddress != I2CDEV_NO_MEM_ADDR)
+  {
+    // Sorry ...
+    if (len > 16) len = 16;
+
+    if(len == 0) return 0;
+
+    buffer[0] = memAddress;
+    for(i = 0; i < len ; i++)
+      buffer[i + 1] = data[i];
+
+    status = I2C_Master_BufferWrite(I2Cx, buffer,  len + 1, INTERRUPT, devAddress << 1, I2C_TIMEOUT);
+  }
+  else
+  {
+    status = I2C_Master_BufferWrite(I2Cx, data,  len, INTERRUPT, devAddress << 1, I2C_TIMEOUT);
+  }
+
+  return status;
+}
+
+static inline void i2cdevRoughLoopDelay(uint32_t us)
+{
+  volatile uint32_t delay;
+
+  for(delay = I2CDEV_LOOPS_PER_US * us; delay > 0; delay--);
+}
+
+static void i2cdevResetAndLowLevelInitBusI2c1(void)
+{
+  /* Reset the I2C block */
+  I2C_DeInit(I2C1);
+
+  /* Make sure the bus is free by clocking it until any slaves release the bus. */
+  GPIO_InitTypeDef  GPIO_InitStructure;
+
+  /* I2C1 clock enable */
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
+  /* I2C1 SDA configuration */
+  GPIO_InitStructure.GPIO_Pin = I2CDEV_I2C1_PIN_SDA;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+  /* I2C1 SCL configuration */
+  GPIO_InitStructure.GPIO_Pin = I2CDEV_I2C1_PIN_SCL;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  GPIO_SetBits(GPIOB, I2CDEV_I2C1_PIN_SDA);
+  /* Check SDA line to determine if slave is asserting bus and clock out if so */
+  while(GPIO_ReadInputDataBit(GPIOB, I2CDEV_I2C1_PIN_SDA) == Bit_RESET)
+  {
+    /* Set clock high */
+    GPIO_SetBits(GPIOB, I2CDEV_I2C1_PIN_SCL);
+    /* Wait for any clock stretching to finish. */
+    GPIO_WAIT_LOW(GPIOB, I2CDEV_I2C1_PIN_SCL, 10 * I2CDEV_LOOPS_PER_MS);
+    i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+
+    /* Generate a clock cycle */
+    GPIO_ResetBits(GPIOB, I2CDEV_I2C1_PIN_SCL);
+    i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+    GPIO_SetBits(GPIOB, I2CDEV_I2C1_PIN_SCL);
+    i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+  }
+
+  /* Generate a start then stop condition */
+  GPIO_SetBits(GPIOB, I2CDEV_I2C1_PIN_SCL);
+  i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+  GPIO_ResetBits(GPIOB, I2CDEV_I2C1_PIN_SDA);
+  i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+  GPIO_ResetBits(GPIOB, I2CDEV_I2C1_PIN_SDA);
+  i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+
+  /* Set data and clock high and wait for any clock stretching to finish. */
+  GPIO_SetBits(GPIOB, I2CDEV_I2C1_PIN_SDA);
+  GPIO_SetBits(GPIOB, I2CDEV_I2C1_PIN_SCL);
+  GPIO_WAIT_LOW(GPIOB, I2CDEV_I2C1_PIN_SCL, 10 * I2CDEV_LOOPS_PER_MS);
+  /* Wait for data to be high */
+  GPIO_WAIT_HIGH(GPIOB, I2CDEV_I2C1_PIN_SDA, 10 * I2CDEV_LOOPS_PER_MS);
+
+  /* Initialize the I2C block */
+  I2C_LowLevel_Init(I2C1);
+
+  /* Reset if I2C device is busy */
+  if (I2C1->SR2 & 0x20)
+  {
+    /* Reset the I2C block */
+    I2C_SoftwareResetCmd(I2C1, ENABLE);
+    I2C_SoftwareResetCmd(I2C1, DISABLE);
+  }
+}
+
+static void i2cdevResetAndLowLevelInitBusI2c2(void)
+{
+  /* Reset the I2C block */
+  I2C_DeInit(I2C2);
+
+  /* Make sure the bus is free by clocking it until any slaves release the bus. */
+  GPIO_InitTypeDef  GPIO_InitStructure;
+
+  /* I2C1 clock enable */
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
+  /* I2C1 SDA configuration */
+  GPIO_InitStructure.GPIO_Pin = I2CDEV_I2C2_PIN_SDA;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+  /* I2C1 SCL configuration */
+  GPIO_InitStructure.GPIO_Pin = I2CDEV_I2C2_PIN_SCL;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  GPIO_SetBits(GPIOB, I2CDEV_I2C2_PIN_SDA);
+  /* Check SDA line to determine if slave is asserting bus and clock out if so */
+  while(GPIO_ReadInputDataBit(GPIOB, I2CDEV_I2C2_PIN_SDA) == Bit_RESET)
+  {
+    /* Set clock high */
+    GPIO_SetBits(GPIOB, I2CDEV_I2C2_PIN_SCL);
+    /* Wait for any clock stretching to finish. */
+    GPIO_WAIT_LOW(GPIOB, I2CDEV_I2C2_PIN_SCL, 10 * I2CDEV_LOOPS_PER_MS);
+    i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+
+    /* Generate a clock cycle */
+    GPIO_ResetBits(GPIOB, I2CDEV_I2C2_PIN_SCL);
+    i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+    GPIO_SetBits(GPIOB, I2CDEV_I2C2_PIN_SCL);
+    i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+  }
+
+  /* Generate a start then stop condition */
+  GPIO_SetBits(GPIOB, I2CDEV_I2C2_PIN_SCL);
+  i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+  GPIO_ResetBits(GPIOB, I2CDEV_I2C2_PIN_SDA);
+  i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+  GPIO_ResetBits(GPIOB, I2CDEV_I2C2_PIN_SDA);
+  i2cdevRoughLoopDelay(I2CDEV_CLK_TS);
+
+  /* Set data and clock high and wait for any clock stretching to finish. */
+  GPIO_SetBits(GPIOB, I2CDEV_I2C2_PIN_SDA);
+  GPIO_SetBits(GPIOB, I2CDEV_I2C2_PIN_SCL);
+  GPIO_WAIT_LOW(GPIOB, I2CDEV_I2C2_PIN_SCL, 10 * I2CDEV_LOOPS_PER_MS);
+  /* Wait for data to be high */
+  GPIO_WAIT_HIGH(GPIOB, I2CDEV_I2C2_PIN_SDA, 10 * I2CDEV_LOOPS_PER_MS);
+
+  /* Initialize the I2C block */
+  I2C_LowLevel_Init(I2C2);
+
+  /* Reset if I2C device is busy */
+  if (I2C2->SR2 & 0x20)
+  {
+    /* Reset the I2C block */
+    I2C_SoftwareResetCmd(I2C2, ENABLE);
+    I2C_SoftwareResetCmd(I2C2, DISABLE);
+  }
+}
+
+void i2cDmaInterruptHandlerI2c1(void)
+{
+  if(DMA_GetITStatus(DMA1_IT_TC6))
+  {
+    DMA_ClearITPendingBit(DMA1_IT_TC6);
+
+    xSemaphoreGive(i2cdevDmaEventI2c1);
+  }
+  if(DMA_GetITStatus(DMA1_IT_TC7))
+  {
+    DMA_ClearITPendingBit(DMA1_IT_TC7);
+
+    xSemaphoreGive(i2cdevDmaEventI2c1);
+  }
+}
+
+void i2cDmaInterruptHandlerI2c2(void)
+{
+  if(DMA_GetITStatus(DMA1_IT_TC4))
+  {
+    DMA_ClearITPendingBit(DMA1_IT_TC4);
+
+    xSemaphoreGive(i2cdevDmaEventI2c2);
+  }
+  if(DMA_GetITStatus(DMA1_IT_TC5))
+  {
+    DMA_ClearITPendingBit(DMA1_IT_TC5);
+
+    xSemaphoreGive(i2cdevDmaEventI2c2);
+  }
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/i2cdev_f405.c b/crazyflie-firmware-src/src/drivers/src/i2cdev_f405.c
new file mode 100644
index 0000000000000000000000000000000000000000..f53885eb6022d80412775795f48fa4bbe1a7ec0b
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/i2cdev_f405.c
@@ -0,0 +1,177 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * i2cdev.c - Functions to write to I2C devices
+ */
+#define DEBUG_MODULE "I2CDEV"
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+#include "task.h"
+#include "queue.h"
+
+#include "i2cdev.h"
+#include "i2c_drv.h"
+#include "nvicconf.h"
+#include "debug.h"
+
+int i2cdevInit(I2C_Dev *dev)
+{
+  i2cdrvInit(dev);
+
+  return true;
+}
+
+bool i2cdevReadByte(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t *data)
+{
+  return i2cdevRead(dev, devAddress, memAddress, 1, data);
+}
+
+bool i2cdevReadBit(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                     uint8_t bitNum, uint8_t *data)
+{
+  uint8_t byte;
+  bool status;
+
+  status = i2cdevRead(dev, devAddress, memAddress, 1, &byte);
+  *data = byte & (1 << bitNum);
+
+  return status;
+}
+
+bool i2cdevReadBits(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t bitStart, uint8_t length, uint8_t *data)
+{
+  bool status;
+  uint8_t byte;
+
+  if ((status = i2cdevReadByte(dev, devAddress, memAddress, &byte)) == true)
+  {
+      uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+      byte &= mask;
+      byte >>= (bitStart - length + 1);
+      *data = byte;
+  }
+  return status;
+}
+
+bool i2cdevRead(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+               uint16_t len, uint8_t *data)
+{
+  I2cMessage message;
+
+#ifdef PLATFORM_CF1
+  if (memAddress == I2CDEV_NO_MEM_ADDR)
+  {
+    i2cdrvCreateMessage(&message, devAddress, i2cRead, len, data);
+  }
+  else
+#endif
+  {
+    i2cdrvCreateMessageIntAddr(&message, devAddress, false, memAddress,
+                            i2cRead, len, data);
+  }
+
+  return i2cdrvMessageTransfer(dev, &message);
+}
+
+bool i2cdevRead16(I2C_Dev *dev, uint8_t devAddress, uint16_t memAddress,
+               uint16_t len, uint8_t *data)
+{
+  I2cMessage message;
+
+  i2cdrvCreateMessageIntAddr(&message, devAddress, true, memAddress,
+                          i2cRead, len, data);
+
+  return i2cdrvMessageTransfer(dev, &message);
+}
+
+bool i2cdevWriteByte(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t data)
+{
+  return i2cdevWrite(dev, devAddress, memAddress, 1, &data);
+}
+
+bool i2cdevWriteBit(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                    uint8_t bitNum, uint8_t data)
+{
+    uint8_t byte;
+    i2cdevReadByte(dev, devAddress, memAddress, &byte);
+    byte = (data != 0) ? (byte | (1 << bitNum)) : (byte & ~(1 << bitNum));
+    return i2cdevWriteByte(dev, devAddress, memAddress, byte);
+}
+
+bool i2cdevWriteBits(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                     uint8_t bitStart, uint8_t length, uint8_t data)
+{
+  bool status;
+  uint8_t byte;
+
+  if ((status = i2cdevReadByte(dev, devAddress, memAddress, &byte)) == true)
+  {
+      uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+      data <<= (bitStart - length + 1); // shift data into correct position
+      data &= mask; // zero all non-important bits in data
+      byte &= ~(mask); // zero all important bits in existing byte
+      byte |= data; // combine data with existing byte
+      status = i2cdevWriteByte(dev, devAddress, memAddress, byte);
+  }
+
+  return status;
+}
+
+bool i2cdevWrite(I2C_Dev *dev, uint8_t devAddress, uint8_t memAddress,
+                uint16_t len, uint8_t *data)
+{
+  I2cMessage message;
+
+#ifdef PLATFORM_CF1
+  if (memAddress == I2CDEV_NO_MEM_ADDR)
+  {
+    i2cdrvCreateMessage(&message, devAddress, i2cWrite, len, data);
+  }
+  else
+#endif
+  {
+    i2cdrvCreateMessageIntAddr(&message, devAddress, false, memAddress,
+                            i2cWrite, len, data);
+  }
+
+  return i2cdrvMessageTransfer(dev, &message);
+}
+
+bool i2cdevWrite16(I2C_Dev *dev, uint8_t devAddress, uint16_t memAddress,
+                   uint16_t len, uint8_t *data)
+{
+  I2cMessage message;
+
+  i2cdrvCreateMessageIntAddr(&message, devAddress, true, memAddress,
+                          i2cWrite, len, data);
+
+  return i2cdrvMessageTransfer(dev, &message);
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/i2croutines.c b/crazyflie-firmware-src/src/drivers/src/i2croutines.c
new file mode 100644
index 0000000000000000000000000000000000000000..5034ce28ec8c6a1b3f0169302646d4a61221cc28
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/i2croutines.c
@@ -0,0 +1,803 @@
+/**
+ ******************************************************************************
+ * @file OptimizedI2Cexamples/src/I2CRoutines.c
+ * @author  MCD Application Team
+ * @version  V4.0.0
+ * @date  06/18/2010
+ * @brief  Contains the I2Cx slave/Master read and write routines.
+ ******************************************************************************
+ * @copy
+ *
+ * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+ * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+ * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+ * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+ * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+ * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+ *
+ * <h2><center>&copy; COPYRIGHT 2010 STMicroelectronics</center></h2>
+ */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32fxxx.h"
+#include "i2croutines.h"
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+
+#include "i2cdev.h"
+#include "nvicconf.h"
+
+extern xSemaphoreHandle i2cdevDmaEventI2c1;
+extern xSemaphoreHandle i2cdevDmaEventI2c2;
+/* Buffer of data to be received by I2C1, I2C2 */
+uint8_t* Buffer_Rx1;
+uint8_t* Buffer_Tx1;
+/* Buffer of data to be transmitted by I2C1, I2C2 */
+uint8_t* Buffer_Rx2;
+uint8_t* Buffer_Tx2;
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+DMA_InitTypeDef I2CDMA_InitStructure;
+__IO uint32_t I2CDirection1 = I2C_DIRECTION_TX;
+__IO uint32_t I2CDirection2 = I2C_DIRECTION_TX;
+__IO uint32_t NumbOfBytes1;
+__IO uint32_t NumbOfBytes2;
+__IO uint8_t Address1;
+__IO uint8_t Address2;
+__IO uint8_t Tx_Idx1 = 0, Rx_Idx1 = 0;
+__IO uint8_t Tx_Idx2 = 0, Rx_Idx2 = 0;
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief  Reads buffer of bytes  from the slave.
+ * @param pBuffer: Buffer of bytes to be read from the slave.
+ * @param NumByteToRead: Number of bytes to be read by the Master.
+ * @param Mode: Polling or DMA or Interrupt having the highest priority in the application.
+ * @param SlaveAddress: The address of the slave to be addressed by the Master.
+ * @retval : None.
+ */
+ErrorStatus I2C_Master_BufferRead(I2C_TypeDef* I2Cx, uint8_t* pBuffer,
+    uint32_t NumByteToRead, I2C_ProgrammingModel Mode, uint8_t SlaveAddress,
+    uint32_t timeoutMs)
+
+{
+  __IO uint32_t temp = 0;
+  __IO uint32_t Timeout = 0;
+
+  /* Enable I2C errors interrupts (used in all modes: Polling, DMA and Interrupts */
+  I2Cx->CR2 |= I2C_IT_ERR;
+
+  if (Mode == DMA) /* I2Cx Master Reception using DMA */
+  {
+    /* Configure I2Cx DMA channel */
+    I2C_DMAConfig(I2Cx, pBuffer, NumByteToRead, I2C_DIRECTION_RX);
+    /* Set Last bit to have a NACK on the last received byte */
+    I2Cx->CR2 |= CR2_LAST_Set;
+    /* Enable I2C DMA requests */
+    I2Cx->CR2 |= CR2_DMAEN_Set;
+    Timeout = 0xFFFF;
+    /* Send START condition */
+    I2Cx->CR1 |= CR1_START_Set;
+    /* Wait until SB flag is set: EV5  */
+    while ((I2Cx->SR1 & 0x0001) != 0x0001)
+    {
+      if (Timeout-- == 0)
+        return ERROR;
+    }
+    Timeout = 0xFFFF;
+    /* Send slave address */
+    /* Set the address bit0 for read */
+    SlaveAddress |= OAR1_ADD0_Set;
+    I2Cx->DR = SlaveAddress;
+    /* Wait until ADDR is set: EV6 */
+    while ((I2Cx->SR1 & 0x0002) != 0x0002)
+    {
+      if (Timeout-- == 0)
+        return ERROR;
+    }
+    /* Clear ADDR flag by reading SR2 register */
+    temp = I2Cx->SR2;
+    if (I2Cx == I2C1)
+    {
+      /* Wait until DMA end of transfer */
+      //while (!DMA_GetFlagStatus(DMA1_FLAG_TC7));
+      xSemaphoreTake(i2cdevDmaEventI2c1, M2T(timeoutMs));
+      /* Disable DMA Channel */
+      DMA_Cmd(I2C1_DMA_CHANNEL_RX, DISABLE);
+      /* Clear the DMA Transfer Complete flag */
+      DMA_ClearFlag(DMA1_FLAG_TC7);
+    }
+    else /* I2Cx = I2C2*/
+    {
+      /* Wait until DMA end of transfer */
+      //while (!DMA_GetFlagStatus(DMA1_FLAG_TC5))
+      xSemaphoreTake(i2cdevDmaEventI2c2, M2T(timeoutMs));
+      /* Disable DMA Channel */
+      DMA_Cmd(I2C2_DMA_CHANNEL_RX, DISABLE);
+      /* Clear the DMA Transfer Complete flag */
+      DMA_ClearFlag(DMA1_FLAG_TC5);
+    }
+    /* Program the STOP */
+    I2Cx->CR1 |= CR1_STOP_Set;
+    /* Make sure that the STOP bit is cleared by Hardware before CR1 write access */
+    while ((I2Cx->CR1 & 0x200) == 0x200)
+      ;
+  }
+  /* I2Cx Master Reception using Interrupts with highest priority in an application */
+  else
+  {
+    /* Enable EVT IT*/
+    I2Cx->CR2 |= I2C_IT_EVT;
+    /* Enable BUF IT */
+    I2Cx->CR2 |= I2C_IT_BUF;
+    SlaveAddress |= OAR1_ADD0_Set;
+    if (I2Cx== I2C1)
+    {
+      /* Set the I2C direction to reception */
+      I2CDirection1 = I2C_DIRECTION_RX;
+      Buffer_Rx1 = pBuffer;
+      Address1 = SlaveAddress;
+      NumbOfBytes1 = NumByteToRead;
+    }
+    else
+    {
+      /* Set the I2C direction to reception */
+      I2CDirection2 = I2C_DIRECTION_RX;
+      Buffer_Rx2 = pBuffer;
+      Address2 = SlaveAddress;
+      NumbOfBytes2 = NumByteToRead;
+    }
+    /* Send START condition */
+    I2Cx->CR1 |= CR1_START_Set;
+    Timeout = timeoutMs * I2CDEV_LOOPS_PER_MS;
+    /* Wait until the START condition is generated on the bus: START bit is cleared by hardware */
+    while ((I2Cx->CR1 & 0x100) == 0x100 && Timeout)
+    {
+      Timeout--;
+    }
+    /* Wait until BUSY flag is reset (until a STOP is generated) */
+    while ((I2Cx->SR2 & 0x0002) == 0x0002 && Timeout)
+    {
+      Timeout--;
+    }
+    /* Enable Acknowledgement to be ready for another reception */
+    I2Cx->CR1 |= CR1_ACK_Set;
+
+    if (Timeout == 0)
+      return ERROR;
+  }
+
+  return SUCCESS;
+
+  temp++; //To avoid GCC warning!
+}
+
+/**
+ * @brief  Writes buffer of bytes.
+ * @param pBuffer: Buffer of bytes to be sent to the slave.
+ * @param NumByteToWrite: Number of bytes to be sent by the Master.
+ * @param Mode: Polling or DMA or Interrupt having the highest priority in the application.
+ * @param SlaveAddress: The address of the slave to be addressed by the Master.
+ * @retval : None.
+ */
+ErrorStatus I2C_Master_BufferWrite(I2C_TypeDef* I2Cx, uint8_t* pBuffer,
+    uint32_t NumByteToWrite, I2C_ProgrammingModel Mode, uint8_t SlaveAddress,
+    uint32_t timeoutMs)
+{
+
+  __IO uint32_t temp = 0;
+  __IO uint32_t Timeout = 0;
+
+  /* Enable Error IT (used in all modes: DMA, Polling and Interrupts */
+  I2Cx->CR2 |= I2C_IT_ERR;
+  if (Mode == DMA) /* I2Cx Master Transmission using DMA */
+  {
+    Timeout = 0xFFFF;
+    /* Configure the DMA channel for I2Cx transmission */
+    I2C_DMAConfig(I2Cx, pBuffer, NumByteToWrite, I2C_DIRECTION_TX);
+    /* Enable the I2Cx DMA requests */
+    I2Cx->CR2 |= CR2_DMAEN_Set;
+    /* Send START condition */
+    I2Cx->CR1 |= CR1_START_Set;
+    /* Wait until SB flag is set: EV5 */
+    while ((I2Cx->SR1 & 0x0001) != 0x0001)
+    {
+      if (Timeout-- == 0)
+        return ERROR;
+    }
+    Timeout = 0xFFFF;
+    /* Send slave address */
+    /* Reset the address bit0 for write */
+    SlaveAddress &= OAR1_ADD0_Reset;
+    I2Cx->DR = SlaveAddress;
+    /* Wait until ADDR is set: EV6 */
+    while ((I2Cx->SR1 & 0x0002) != 0x0002)
+    {
+      if (Timeout-- == 0)
+        return ERROR;
+    }
+
+    /* Clear ADDR flag by reading SR2 register */
+    temp = I2Cx->SR2;
+    if (I2Cx == I2C1)
+    {
+      /* Wait until DMA end of transfer */
+//            while (!DMA_GetFlagStatus(DMA1_FLAG_TC6));
+      xSemaphoreTake(i2cdevDmaEventI2c1, M2T(5));
+      /* Disable the DMA1 Channel 6 */
+      DMA_Cmd(I2C1_DMA_CHANNEL_TX, DISABLE);
+      /* Clear the DMA Transfer complete flag */
+      DMA_ClearFlag(DMA1_FLAG_TC6);
+    }
+    else /* I2Cx = I2C2 */
+    {
+      /* Wait until DMA end of transfer */
+      //while (!DMA_GetFlagStatus(DMA1_FLAG_TC4))
+      xSemaphoreTake(i2cdevDmaEventI2c2, M2T(5));
+      /* Disable the DMA1 Channel 4 */
+      DMA_Cmd(I2C2_DMA_CHANNEL_TX, DISABLE);
+      /* Clear the DMA Transfer complete flag */
+      DMA_ClearFlag(DMA1_FLAG_TC4);
+    }
+
+    /* EV8_2: Wait until BTF is set before programming the STOP */
+    while ((I2Cx->SR1 & 0x00004) != 0x000004)
+      ;
+    /* Program the STOP */
+    I2Cx->CR1 |= CR1_STOP_Set;
+    /* Make sure that the STOP bit is cleared by Hardware */
+    while ((I2Cx->CR1 & 0x200) == 0x200)
+      ;
+  }
+  /* I2Cx Master Transmission using Interrupt with highest priority in the application */
+  else
+  {
+    /* Enable EVT IT*/
+    I2Cx->CR2 |= I2C_IT_EVT;
+    /* Enable BUF IT */
+    I2Cx->CR2 |= I2C_IT_BUF;
+    /* Set the I2C direction to Transmission */
+    SlaveAddress &= OAR1_ADD0_Reset;
+    if (I2Cx== I2C1)
+    {
+      /* Set the I2C direction to reception */
+      I2CDirection1 = I2C_DIRECTION_TX;
+      Buffer_Tx1 = pBuffer;
+      Address1 = SlaveAddress;
+      NumbOfBytes1 = NumByteToWrite;
+    }
+    else
+    {
+      /* Set the I2C direction to reception */
+      I2CDirection2 = I2C_DIRECTION_TX;
+      Buffer_Tx2 = pBuffer;
+      Address2 = SlaveAddress;
+      NumbOfBytes2 = NumByteToWrite;
+    }
+    /* Send START condition */
+    I2Cx->CR1 |= CR1_START_Set;
+    Timeout = timeoutMs * I2CDEV_LOOPS_PER_MS;
+    /* Wait until the START condition is generated on the bus: the START bit is cleared by hardware */
+    while ((I2Cx->CR1 & 0x100) == 0x100 && Timeout)
+    {
+      Timeout--;
+    }
+    /* Wait until BUSY flag is reset: a STOP has been generated on the bus signaling the end
+     of transmission */
+    while ((I2Cx->SR2 & 0x0002) == 0x0002 && Timeout)
+    {
+      Timeout--;
+    }
+
+    if (Timeout == 0)
+      return ERROR;
+  }
+  return SUCCESS;
+
+  temp++; //To avoid GCC warning!
+}
+
+/**
+ * @brief Prepares the I2Cx slave for transmission.
+ * @param I2Cx: I2C1 or I2C2.
+ * @param Mode: DMA or Interrupt having the highest priority in the application.
+ * @retval : None.
+ */
+void I2C_Slave_BufferReadWrite(I2C_TypeDef* I2Cx, I2C_ProgrammingModel Mode)
+
+{
+  /* Enable Event IT needed for ADDR and STOPF events ITs */
+  I2Cx->CR2 |= I2C_IT_EVT;
+  /* Enable Error IT */
+  I2Cx->CR2 |= I2C_IT_ERR;
+
+  if (Mode == DMA) /* I2Cx Slave Transmission using DMA */
+  {
+    /* Enable I2Cx DMA requests */
+    I2Cx->CR2 |= CR2_DMAEN_Set;
+  }
+  else /* I2Cx Slave Transmission using Interrupt with highest priority in the application */
+  {
+    /* Enable Buffer IT (TXE and RXNE ITs) */
+    I2Cx->CR2 |= I2C_IT_BUF;
+  }
+}
+
+/**
+ * @brief  Initializes peripherals: I2Cx, GPIO, DMA channels .
+ * @param  None
+ * @retval None
+ */
+void I2C_LowLevel_Init(I2C_TypeDef* I2Cx)
+{
+  GPIO_InitTypeDef GPIO_InitStructure;
+  I2C_InitTypeDef I2C_InitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  /* GPIOB clock enable */
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+  /* Enable the DMA1 clock */
+  RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
+  if (I2Cx == I2C1)
+  {
+    /* I2C1 clock enable */
+    RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
+    /* I2C1 SDA and SCL configuration */
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+    GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7;
+    GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+    /* Enable I2C1 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE);
+    /* Release I2C1 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE);
+
+    NVIC_InitStructure.NVIC_IRQChannel = I2C1_EV_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_I2C_HIGH_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+    NVIC_InitStructure.NVIC_IRQChannel = I2C1_ER_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_I2C_LOW_PRI;
+    NVIC_Init(&NVIC_InitStructure);
+  }
+  else /* I2Cx = I2C2 */
+  {
+
+    /* I2C2 clock enable */
+    RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
+    /* I2C1 SDA and SCL configuration */
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+    GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11;
+    GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+    /* Enable I2C2 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE);
+    /* Release I2C2 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE);
+
+    NVIC_InitStructure.NVIC_IRQChannel = I2C2_EV_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_I2C_HIGH_PRI;
+    NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+    NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+    NVIC_Init(&NVIC_InitStructure);
+    NVIC_InitStructure.NVIC_IRQChannel = I2C2_ER_IRQn;
+    NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_I2C_LOW_PRI;
+    NVIC_Init(&NVIC_InitStructure);
+  }
+
+  /* I2C1 and I2C2 configuration */
+  I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
+  I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
+  I2C_InitStructure.I2C_OwnAddress1 = OwnAddress1;
+  I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
+  I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+  I2C_InitStructure.I2C_ClockSpeed = ClockSpeed;
+  I2C_Init(I2C1, &I2C_InitStructure);
+  I2C_InitStructure.I2C_OwnAddress1 = OwnAddress2;
+  I2C_Init(I2C2, &I2C_InitStructure);
+
+  if (I2Cx == I2C1)
+
+  { /* I2C1 TX DMA Channel configuration */
+    DMA_DeInit(I2C1_DMA_CHANNEL_TX);
+    I2CDMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) I2C1_DR_Address;
+    I2CDMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t) 0; /* This parameter will be configured durig communication */
+    I2CDMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; /* This parameter will be configured durig communication */
+    I2CDMA_InitStructure.DMA_BufferSize = 0xFFFF; /* This parameter will be configured durig communication */
+    I2CDMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+    I2CDMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+    I2CDMA_InitStructure.DMA_PeripheralDataSize = DMA_MemoryDataSize_Byte;
+    I2CDMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+    I2CDMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+    I2CDMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+    I2CDMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+    DMA_Init(I2C1_DMA_CHANNEL_TX, &I2CDMA_InitStructure);
+
+    /* I2C1 RX DMA Channel configuration */
+    DMA_DeInit(I2C1_DMA_CHANNEL_RX);
+    DMA_Init(I2C1_DMA_CHANNEL_RX, &I2CDMA_InitStructure);
+  }
+
+  else /* I2Cx = I2C2 */
+
+  {
+    /* I2C2 TX DMA Channel configuration */
+    DMA_DeInit(I2C2_DMA_CHANNEL_TX);
+    I2CDMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) I2C2_DR_Address;
+    I2CDMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t) 0; /* This parameter will be configured durig communication */
+    I2CDMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; /* This parameter will be configured durig communication */
+    I2CDMA_InitStructure.DMA_BufferSize = 0xFFFF; /* This parameter will be configured durig communication */
+    I2CDMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+    I2CDMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+    I2CDMA_InitStructure.DMA_PeripheralDataSize = DMA_MemoryDataSize_Byte;
+    I2CDMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+    I2CDMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+    I2CDMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+    I2CDMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+    DMA_Init(I2C2_DMA_CHANNEL_TX, &I2CDMA_InitStructure);
+
+    /* I2C2 RX DMA Channel configuration */
+    DMA_DeInit(I2C2_DMA_CHANNEL_RX);
+    DMA_Init(I2C2_DMA_CHANNEL_RX, &I2CDMA_InitStructure);
+
+  }
+}
+
+/**
+ * @brief  Initializes DMA channel used by the I2C Write/read routines.
+ * @param  None.
+ * @retval None.
+ */
+void I2C_DMAConfig(I2C_TypeDef* I2Cx, uint8_t* pBuffer, uint32_t BufferSize,
+    uint32_t Direction)
+{
+  /* Initialize the DMA with the new parameters */
+  if (Direction == I2C_DIRECTION_TX)
+  {
+    /* Configure the DMA Tx Channel with the buffer address and the buffer size */
+    I2CDMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t) pBuffer;
+    I2CDMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+    I2CDMA_InitStructure.DMA_BufferSize = (uint32_t) BufferSize;
+
+    if (I2Cx == I2C1)
+    {
+      I2CDMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) I2C1_DR_Address;
+      DMA_Cmd(I2C1_DMA_CHANNEL_TX, DISABLE);
+      DMA_Init(I2C1_DMA_CHANNEL_TX, &I2CDMA_InitStructure);
+      DMA_Cmd(I2C1_DMA_CHANNEL_TX, ENABLE);
+    }
+    else
+    {
+      I2CDMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) I2C2_DR_Address;
+      DMA_Cmd(I2C2_DMA_CHANNEL_TX, DISABLE);
+      DMA_Init(I2C2_DMA_CHANNEL_TX, &I2CDMA_InitStructure);
+      DMA_ITConfig(DMA1_Channel4, DMA_IT_TC, ENABLE);
+      DMA_Cmd(I2C2_DMA_CHANNEL_TX, ENABLE);
+    }
+  }
+  else /* Reception */
+  {
+    /* Configure the DMA Rx Channel with the buffer address and the buffer size */
+    I2CDMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t) pBuffer;
+    I2CDMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
+    I2CDMA_InitStructure.DMA_BufferSize = (uint32_t) BufferSize;
+    if (I2Cx == I2C1)
+    {
+
+      I2CDMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) I2C1_DR_Address;
+      DMA_Cmd(I2C1_DMA_CHANNEL_RX, DISABLE);
+      DMA_Init(I2C1_DMA_CHANNEL_RX, &I2CDMA_InitStructure);
+      DMA_Cmd(I2C1_DMA_CHANNEL_RX, ENABLE);
+    }
+
+    else
+    {
+      I2CDMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) I2C2_DR_Address;
+      DMA_Cmd(I2C2_DMA_CHANNEL_RX, DISABLE);
+      DMA_Init(I2C2_DMA_CHANNEL_RX, &I2CDMA_InitStructure);
+      DMA_Cmd(I2C2_DMA_CHANNEL_RX, ENABLE);
+    }
+
+  }
+}
+
+/**
+ * @brief  This function handles I2C Event interrupt request.
+ * @param  None
+ * @retval : None
+ */
+void __attribute__((used)) I2C1_EV_IRQHandler(void)
+{
+
+  __IO uint32_t SR1Register = 0;
+  __IO uint32_t SR2Register = 0;
+
+  /* Read the I2C SR1 and SR2 status registers */
+  SR1Register = I2C1->SR1;
+  SR2Register = I2C1->SR2;
+
+  /* If SB = 1, I2C master sent a START on the bus: EV5) */
+  if ((SR1Register & 0x0001) == 0x0001)
+  {
+    /* Send the slave address for transmssion or for reception (according to the configured value
+     in the write master write routine */
+    I2C1->DR = Address1;
+    SR1Register = 0;
+    SR2Register = 0;
+  }
+  /* If I2C is Master (MSL flag = 1) */
+
+  if ((SR2Register & 0x0001) == 0x0001)
+  {
+    /* If ADDR = 1, EV6 */
+    if ((SR1Register & 0x0002) == 0x0002)
+    {
+      /* Write the first data in case the Master is Transmitter */
+      if (I2CDirection1 == I2C_DIRECTION_TX)
+      {
+        /* Initialize the Transmit counter */
+        Tx_Idx1 = 0;
+        /* Write the first data in the data register */
+        I2C1->DR = Buffer_Tx1[Tx_Idx1++];
+        /* Decrement the number of bytes to be written */
+        NumbOfBytes1--;
+        /* If no further data to be sent, disable the I2C BUF IT
+         in order to not have a TxE  interrupt */
+        if (NumbOfBytes1 == 0)
+        {
+          I2C1->CR2 &= (uint16_t) ~I2C_IT_BUF;
+        }
+      }
+      /* Master Receiver */
+      else
+      {
+        /* Initialize Receive counter */
+        Rx_Idx1 = 0;
+        /* At this stage, ADDR is cleared because both SR1 and SR2 were read.*/
+        /* EV6_1: used for single byte reception. The ACK disable and the STOP
+         Programming should be done just after ADDR is cleared. */
+        if (NumbOfBytes1 == 1)
+        {
+          /* Clear ACK */
+          I2C1->CR1 &= CR1_ACK_Reset;
+          /* Program the STOP */
+          I2C1->CR1 |= CR1_STOP_Set;
+        }
+      }
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+    /* Master transmits the remaing data: from data2 until the last one.  */
+    /* If TXE is set */
+    if ((SR1Register & 0x0084) == 0x0080)
+    {
+      /* If there is still data to write */
+      if (NumbOfBytes1 != 0)
+      {
+        /* Write the data in DR register */
+        I2C1->DR = Buffer_Tx1[Tx_Idx1++];
+        /* Decrment the number of data to be written */
+        NumbOfBytes1--;
+        /* If  no data remains to write, disable the BUF IT in order
+         to not have again a TxE interrupt. */
+        if (NumbOfBytes1 == 0)
+        {
+          /* Disable the BUF IT */
+          I2C1->CR2 &= (uint16_t) ~I2C_IT_BUF;
+        }
+      }
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+    /* If BTF and TXE are set (EV8_2), program the STOP */
+    if ((SR1Register & 0x0084) == 0x0084)
+    {
+      /* Program the STOP */
+      I2C1->CR1 |= CR1_STOP_Set;
+      /* Disable EVT IT In order to not have again a BTF IT */
+      I2C1->CR2 &= (uint16_t) ~I2C_IT_EVT;
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+    /* If RXNE is set */
+    if ((SR1Register & 0x0040) == 0x0040)
+    {
+      /* Read the data register */
+      Buffer_Rx1[Rx_Idx1++] = I2C1->DR;
+      /* Decrement the number of bytes to be read */
+      NumbOfBytes1--;
+      /* If it remains only one byte to read, disable ACK and program the STOP (EV7_1) */
+      if (NumbOfBytes1 == 1)
+      {
+        /* Clear ACK */
+        I2C1->CR1 &= CR1_ACK_Reset;
+        /* Program the STOP */
+        I2C1->CR1 |= CR1_STOP_Set;
+      }
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+  }
+}
+
+/**
+ * @brief  This function handles I2C Event interrupt request.
+ * @param  None
+ * @retval : None
+ */
+void __attribute__((used)) I2C2_EV_IRQHandler(void)
+{
+  __IO uint32_t SR1Register = 0;
+  __IO uint32_t SR2Register = 0;
+
+  /* Read the I2C SR1 and SR2 status registers */
+  SR1Register = I2C2->SR1;
+  SR2Register = I2C2->SR2;
+
+  /* If SB = 1, I2C master sent a START on the bus: EV5) */
+  if ((SR1Register & 0x0001) == 0x0001)
+  {
+    /* Send the slave address for transmssion or for reception (according to the configured value
+     in the write master write routine */
+    I2C2->DR = Address2;
+    SR1Register = 0;
+    SR2Register = 0;
+  }
+  /* If I2C is Master (MSL flag = 1) */
+
+  if ((SR2Register & 0x0001) == 0x0001)
+  {
+    /* If ADDR = 1, EV6 */
+    if ((SR1Register & 0x0002) == 0x0002)
+    {
+      /* Write the first data in case the Master is Transmitter */
+      if (I2CDirection2 == I2C_DIRECTION_TX)
+      {
+        /* Initialize the Transmit counter */
+        Tx_Idx2 = 0;
+        /* Write the first data in the data register */
+        I2C2->DR = Buffer_Tx2[Tx_Idx2++];
+        /* Decrement the number of bytes to be written */
+        NumbOfBytes2--;
+        /* If no further data to be sent, disable the I2C BUF IT
+         in order to not have a TxE  interrupt */
+        if (NumbOfBytes2 == 0)
+        {
+          I2C2->CR2 &= (uint16_t) ~I2C_IT_BUF;
+        }
+      }
+      /* Master Receiver */
+      else
+      {
+        /* Initialize Receive counter */
+        Rx_Idx2 = 0;
+        /* At this stage, ADDR is cleared because both SR1 and SR2 were read.*/
+        /* EV6_1: used for single byte reception. The ACK disable and the STOP
+         Programming should be done just after ADDR is cleared. */
+        if (NumbOfBytes2 == 1)
+        {
+          /* Clear ACK */
+          I2C2->CR1 &= CR1_ACK_Reset;
+          /* Program the STOP */
+          I2C2->CR1 |= CR1_STOP_Set;
+        }
+      }
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+    /* Master transmits the remaing data: from data2 until the last one.  */
+    /* If TXE is set */
+    if ((SR1Register & 0x0084) == 0x0080)
+    {
+      /* If there is still data to write */
+      if (NumbOfBytes2 != 0)
+      {
+        /* Write the data in DR register */
+        I2C2->DR = Buffer_Tx2[Tx_Idx2++];
+        /* Decrment the number of data to be written */
+        NumbOfBytes2--;
+        /* If  no data remains to write, disable the BUF IT in order
+         to not have again a TxE interrupt. */
+        if (NumbOfBytes2 == 0)
+        {
+          /* Disable the BUF IT */
+          I2C2->CR2 &= (uint16_t) ~I2C_IT_BUF;
+        }
+      }
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+    /* If BTF and TXE are set (EV8_2), program the STOP */
+    if ((SR1Register & 0x0084) == 0x0084)
+    {
+      /* Program the STOP */
+      I2C2->CR1 |= CR1_STOP_Set;
+      /* Disable EVT IT In order to not have again a BTF IT */
+      I2C2->CR2 &= (uint16_t) ~I2C_IT_EVT;
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+    /* If RXNE is set */
+    if ((SR1Register & 0x0040) == 0x0040)
+    {
+      /* Read the data register */
+      Buffer_Rx2[Rx_Idx2++] = I2C2->DR;
+      /* Decrement the number of bytes to be read */
+      NumbOfBytes2--;
+      /* If it remains only one byte to read, disable ACK and program the STOP (EV7_1) */
+      if (NumbOfBytes2 == 1)
+      {
+        /* Clear ACK */
+        I2C2->CR1 &= CR1_ACK_Reset;
+        /* Program the STOP */
+        I2C2->CR1 |= CR1_STOP_Set;
+      }
+      SR1Register = 0;
+      SR2Register = 0;
+    }
+  }
+}
+
+void __attribute__((used)) I2C1_ER_IRQHandler(void)
+{
+  i2cErrorInterruptHandler(I2C1);
+}
+
+void __attribute__((used)) I2C2_ER_IRQHandler(void)
+{
+  i2cErrorInterruptHandler(I2C2);
+}
+
+/**
+ * @brief  This function handles I2C Error interrupt request.
+ * @param  None
+ * @retval : None
+ */
+void i2cErrorInterruptHandler(I2C_TypeDef* I2Cx)
+{
+
+  __IO uint32_t SR1Register = 0;
+
+  /* Read the I2C status register */
+  SR1Register = I2Cx->SR1;
+  /* If AF = 1 */
+  if ((SR1Register & 0x0400) == 0x0400)
+  {
+    I2Cx->SR1 &= 0xFBFF;
+    SR1Register = 0;
+  }
+  /* If ARLO = 1 */
+  if ((SR1Register & 0x0200) == 0x0200)
+  {
+    I2Cx->SR1 &= 0xFBFF;
+    SR1Register = 0;
+  }
+  /* If BERR = 1 */
+  if ((SR1Register & 0x0100) == 0x0100)
+  {
+    I2Cx->SR1 &= 0xFEFF;
+    SR1Register = 0;
+  }
+  /* If OVR = 1 */
+  if ((SR1Register & 0x0800) == 0x0800)
+  {
+    I2Cx->SR1 &= 0xF7FF;
+    SR1Register = 0;
+  }
+}
+
+/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/drivers/src/led_f103.c b/crazyflie-firmware-src/src/drivers/src/led_f103.c
new file mode 100644
index 0000000000000000000000000000000000000000..915b11f0908e907541a44d260360761edc905750
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/led_f103.c
@@ -0,0 +1,119 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * led.c - LED handing functions
+ */
+#include "led.h"
+
+#include "motors.h"
+
+#include <stdbool.h>
+#include "stm32fxxx.h"
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+
+static bool isInit=false;
+
+static GPIO_TypeDef* led_port[] = {
+  [LED_GREEN] = LED_GPIO_PORT, 
+  [LED_RED] = LED_GPIO_PORT,
+};
+static unsigned int led_pin[] = {
+  [LED_GREEN] = LED_GPIO_GREEN, 
+  [LED_RED]   = LED_GPIO_RED,
+};
+static int led_polarity[] = {
+  [LED_GREEN] = LED_POL_GREEN, 
+  [LED_RED] = LED_POL_RED,
+};
+
+//Initialize the green led pin as output
+void ledInit()
+{
+  if(isInit)
+    return;
+
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  // Enable GPIO
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | LED_GPIO_PERIF, ENABLE);
+
+  // Remap PB4
+  GPIO_PinRemapConfig(GPIO_Remap_SWJ_NoJTRST , ENABLE);
+
+  //Initialize the LED pins as an output
+  GPIO_InitStructure.GPIO_Pin = LED_GPIO_GREEN | LED_GPIO_RED;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  //Turn off the LED:s
+  ledSet(LED_GREEN, 0);
+  ledSet(LED_RED, 0);
+
+  isInit = true;
+}
+
+bool ledTest(void)
+{
+  return isInit;
+}
+
+void ledClearAll(void)
+{
+  int i;
+
+  for (i = 0; i < LED_NUM; i++)
+  {
+    //Turn off the LED:s
+    ledSet(i, 0);
+  }
+}
+
+void ledSetAll(void)
+{
+  int i;
+
+  for (i = 0; i < LED_NUM; i++)
+  {
+    //Turn on the LED:s
+    ledSet(i, 1);
+  }
+}
+void ledSet(led_t led, bool value)
+{
+  if (led>LED_NUM)
+    return;
+
+  if (led_polarity[led]==LED_POL_NEG)
+    value = !value;
+  
+  if(value)
+    GPIO_SetBits(led_port[led], led_pin[led]);
+  else
+    GPIO_ResetBits(led_port[led], led_pin[led]); 
+}
+
+
diff --git a/crazyflie-firmware-src/src/drivers/src/led_f405.c b/crazyflie-firmware-src/src/drivers/src/led_f405.c
new file mode 100644
index 0000000000000000000000000000000000000000..67e05e8dcf50cc4a36e5b9f36499af23d527df7f
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/led_f405.c
@@ -0,0 +1,162 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * led.c - LED handing functions
+ */
+#include <stdbool.h>
+
+#include "stm32fxxx.h"
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "led.h"
+
+#ifdef PLATFORM_CF1
+static GPIO_TypeDef* led_port[] = {
+  [LED_GREEN] = LED_GPIO_PORT, 
+  [LED_RED] = LED_GPIO_PORT,
+};
+static unsigned int led_pin[] = {
+  [LED_GREEN] = LED_GPIO_GREEN, 
+  [LED_RED]   = LED_GPIO_RED,
+};
+static int led_polarity[] = {
+  [LED_GREEN] = LED_POL_GREEN, 
+  [LED_RED] = LED_POL_RED,
+};
+#else
+static GPIO_TypeDef* led_port[] =
+{
+  [LED_BLUE_L] = LED_GPIO_PORT_BLUE,
+  [LED_GREEN_L] = LED_GPIO_PORT,
+  [LED_RED_L] = LED_GPIO_PORT,
+  [LED_GREEN_R] = LED_GPIO_PORT,
+  [LED_RED_R] = LED_GPIO_PORT,
+};
+static unsigned int led_pin[] =
+{
+  [LED_BLUE_L] = LED_GPIO_BLUE_L,
+  [LED_GREEN_L] = LED_GPIO_GREEN_L,
+  [LED_RED_L]   = LED_GPIO_RED_L,
+  [LED_GREEN_R] = LED_GPIO_GREEN_R,
+  [LED_RED_R]   = LED_GPIO_RED_R,
+};
+static int led_polarity[] =
+{
+  [LED_BLUE_L] = LED_POL_BLUE_L,
+  [LED_GREEN_L] = LED_POL_GREEN_L,
+  [LED_RED_L]   = LED_POL_RED_L,
+  [LED_GREEN_R] = LED_POL_GREEN_R,
+  [LED_RED_R]   = LED_POL_RED_R,
+};
+#endif
+
+static bool isInit = false;
+
+//Initialize the green led pin as output
+void ledInit()
+{
+  int i;
+
+  if(isInit)
+    return;
+
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  // Enable GPIO
+  RCC_AHB1PeriphClockCmd(LED_GPIO_PERIF, ENABLE);
+
+  for (i = 0; i < LED_NUM; i++)
+  {
+    //Initialize the LED pins as an output
+    GPIO_InitStructure.GPIO_Pin = led_pin[i];
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+    GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
+    GPIO_Init(led_port[i], &GPIO_InitStructure);
+
+    //Turn off the LED:s
+    ledSet(i, 0);
+  }
+
+  isInit = true;
+}
+
+bool ledTest(void)
+{
+  ledSet(LED_GREEN_L, 1);
+  ledSet(LED_GREEN_R, 1);
+  ledSet(LED_RED_L, 0);
+  ledSet(LED_RED_R, 0);
+  vTaskDelay(M2T(250));
+  ledSet(LED_GREEN_L, 0);
+  ledSet(LED_GREEN_R, 0);
+  ledSet(LED_RED_L, 1);
+  ledSet(LED_RED_R, 1);
+  vTaskDelay(M2T(250));
+
+  // LED test end
+  ledClearAll();
+  ledSet(LED_BLUE_L, 1);
+
+  return isInit;
+}
+
+void ledClearAll(void)
+{
+  int i;
+
+  for (i = 0; i < LED_NUM; i++)
+  {
+    //Turn off the LED:s
+    ledSet(i, 0);
+  }
+}
+
+void ledSetAll(void)
+{
+  int i;
+
+  for (i = 0; i < LED_NUM; i++)
+  {
+    //Turn on the LED:s
+    ledSet(i, 1);
+  }
+}
+void ledSet(led_t led, bool value)
+{
+  if (led>LED_NUM)
+    return;
+
+  if (led_polarity[led]==LED_POL_NEG)
+    value = !value;
+  
+  if(value)
+    GPIO_SetBits(led_port[led], led_pin[led]);
+  else
+    GPIO_ResetBits(led_port[led], led_pin[led]); 
+}
+
+
diff --git a/crazyflie-firmware-src/src/drivers/src/lps25h.c b/crazyflie-firmware-src/src/drivers/src/lps25h.c
new file mode 100644
index 0000000000000000000000000000000000000000..e477fac1c1997be12870b19d469a3ff48b00ab0e
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/lps25h.c
@@ -0,0 +1,184 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011 Fabio Varesano <fvaresano@yahoo.it>
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file lps25h.c
+ * Driver for the lps25h pressure sensor from ST.
+ *
+ */
+#define DEBUG_MODULE "LPS25H"
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "lps25h.h"
+#include "i2cdev.h"
+#include "debug.h"
+#include "eprintf.h"
+
+static uint8_t devAddr;
+static I2C_Dev *I2Cx;
+static bool isInit;
+
+bool lps25hInit(I2C_Dev *i2cPort)
+{
+  if (isInit)
+    return true;
+
+  I2Cx = i2cPort;
+  devAddr = LPS25H_I2C_ADDR;
+
+  vTaskDelay(M2T(5));
+
+  isInit = true;
+
+  return true;
+}
+
+bool lps25hTestConnection(void)
+{
+  uint8_t id;
+  bool status;
+
+  if (!isInit)
+	return false;
+
+
+  status = i2cdevRead(I2Cx, devAddr, LPS25H_WHO_AM_I, 1, &id);
+
+  if (status == true && id == LPS25H_WAI_ID)
+	  return true;
+
+  return false;
+}
+
+bool lps25hSelfTest(void)
+{
+  float pressure;
+  float temperature;
+  float asl;
+
+  if (!isInit)
+    return false;
+
+  lps25hGetData(&pressure, &temperature, &asl);
+
+  if (lps25hEvaluateSelfTest(LPS25H_ST_PRESS_MIN, LPS25H_ST_PRESS_MAX, pressure, "pressure") &&
+      lps25hEvaluateSelfTest(LPS25H_ST_TEMP_MIN, LPS25H_ST_TEMP_MAX, temperature, "temperature"))
+  {
+    return true;
+  }
+  else
+  {
+   return false;
+  }
+}
+
+bool lps25hEvaluateSelfTest(float min, float max, float value, char* string)
+{
+  if (value < min || value > max)
+  {
+    DEBUG_PRINT("Self test %s [FAIL]. low: %0.2f, high: %0.2f, measured: %0.2f\n",
+                string, min, max, value);
+    return false;
+  }
+  return true;
+}
+
+bool lps25hSetEnabled(bool enable)
+{
+  uint8_t enable_mask;
+  bool status;
+
+	if (!isInit)
+	  return false;
+
+	if (enable)
+	{
+	  enable_mask = 0b11000110; // Power on, 25Hz, BDU, reset zero
+	  status = i2cdevWrite(I2Cx, devAddr, LPS25H_CTRL_REG1, 1, &enable_mask);
+	  enable_mask = 0b00001111; // AVG-P 512, AVG-T 64
+	  status = i2cdevWrite(I2Cx, devAddr, LPS25H_RES_CONF, 1, &enable_mask);
+	  // FIFO averaging. This requres temp reg to be read in different read as reg auto inc
+	  // wraps back to LPS25H_PRESS_OUT_L after LPS25H_PRESS_OUT_H is read.
+	  enable_mask = 0b11000011; // FIFO Mean mode, 4 moving average
+	  status = i2cdevWrite(I2Cx, devAddr, LPS25H_FIFO_CTRL, 1, &enable_mask);
+	  enable_mask = 0b01000000; // FIFO Enable
+	  status = i2cdevWrite(I2Cx, devAddr, LPS25H_CTRL_REG2, 1, &enable_mask);
+	}
+	else
+	{
+	  enable_mask = 0x00; // Power off and default values
+	  status = i2cdevWrite(I2Cx, devAddr, LPS25H_CTRL_REG1, 1, &enable_mask);
+	}
+
+	return status;
+}
+
+bool lps25hGetData(float* pressure, float* temperature, float* asl)
+{
+  uint8_t data[5];
+  uint32_t rawPressure;
+  int16_t rawTemp;
+  bool status;
+
+  status =  i2cdevRead(I2Cx, devAddr, LPS25H_PRESS_OUT_XL | LPS25H_ADDR_AUTO_INC, 3, data);
+  // If LPS25H moving avg filter is activated the temp must be read out in separate read.
+  status &= i2cdevRead(I2Cx, devAddr, LPS25H_TEMP_OUT_L | LPS25H_ADDR_AUTO_INC, 2, &data[3]);
+
+  rawPressure = ((uint32_t)data[2] << 16) | ((uint32_t)data[1] << 8) | data[0];
+  *pressure = (float)rawPressure / LPS25H_LSB_PER_MBAR;
+
+  rawTemp = ((int16_t)data[4] << 8) | data[3];
+  *temperature = LPS25H_TEMP_OFFSET + ((float)rawTemp / LPS25H_LSB_PER_CELSIUS);
+
+  *asl = lps25hPressureToAltitude(pressure);
+
+  return status;
+}
+
+#include "math.h"
+// Constants used to determine altitude from pressure
+#define CONST_SEA_PRESSURE 102610.f //1026.1f //http://www.meteo.physik.uni-muenchen.de/dokuwiki/doku.php?id=wetter:stadt:messung
+#define CONST_PF 0.1902630958f //(1/5.25588f) Pressure factor
+#define CONST_PF2 44330.0f
+#define FIX_TEMP 25         // Fixed Temperature. ASL is a function of pressure and temperature, but as the temperature changes so much (blow a little towards the flie and watch it drop 5 degrees) it corrupts the ASL estimates.
+                            // TLDR: Adjusting for temp changes does more harm than good.
+
+//TODO: pretty expensive function. Rather smooth the pressure estimates and only call this when needed
+/**
+ * Converts pressure to altitude above sea level (ASL) in meters
+ */
+float lps25hPressureToAltitude(float* pressure/*, float* ground_pressure, float* ground_temp*/)
+{
+    if (*pressure > 0)
+    {
+        //return (1.f - pow(*pressure / CONST_SEA_PRESSURE, CONST_PF)) * CONST_PF2;
+        //return ((pow((1015.7 / *pressure), CONST_PF) - 1.0) * (25. + 273.15)) / 0.0065;
+        return ((powf((1015.7f / *pressure), CONST_PF) - 1.0f) * (FIX_TEMP + 273.15f)) / 0.0065f;
+    }
+    else
+    {
+        return 0;
+    }
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/maxsonar.c b/crazyflie-firmware-src/src/drivers/src/maxsonar.c
new file mode 100644
index 0000000000000000000000000000000000000000..2981784b7331308c3428b281ff4378c3db24f303
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/maxsonar.c
@@ -0,0 +1,156 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * maxSonar.c - Implementation for the MaxSonar MB1040 (LV-MaxSonar-EZ04)
+ */
+
+#include <stddef.h>
+
+#include "config.h"
+#include "log.h"
+#include "maxsonar.h"
+#include "deck.h"
+
+#define IN2MM(x) ((x) * 25.4f)
+
+/* Internal tracking of last measured distance. */
+static uint32_t maxSonarDistance = 0;
+static uint32_t maxSonarAccuracy = 0; /* 0 accuracy means no measurement or unknown accuracy. */
+
+#if defined(MAXSONAR_LOG_ENABLED)
+/* Define a log group. */
+LOG_GROUP_START(maxSonar)
+LOG_ADD(LOG_UINT32, distance, &maxSonarDistance)
+LOG_ADD(LOG_UINT32, accuracy, &maxSonarAccuracy)
+LOG_GROUP_STOP(maxSonar)
+#endif
+
+/**
+ * Gets the accuracy for a distance measurement from an MB1040 sonar range finder (LV-MaxSonar-EZ4).
+ *
+ * @param distance The distance measurement to report the accuracy for (mm).
+ *
+ * @return Accuracy in millimeters.
+ */
+static uint32_t maxSonarGetAccuracyMB1040(uint32_t distance)
+{
+  /* Specify the accuracy of the measurement from the MB1040 (LV-MaxBotix-EZ4) sensor. */
+
+  if(distance <= IN2MM(6)) {
+    /**
+     * The datasheet for the MB1040 specifies that any distance below 6 inches is reported as 6 inches.
+     * Since all measurements are given in 1 inch steps, the actual distance can be anything
+     * from 7 (exclusive) to 0 (inclusive) inches.
+     *
+     * The accuracy is therefore set to 7(!) inches.
+     */
+    maxSonarAccuracy = IN2MM(7);
+  }
+  else if(distance >= IN2MM(20)) {
+    /**
+     * The datasheet for the MB1040 specifies that any distance between 6 and 20 inches may result in
+     * measurement inaccuracies up to 2 inches.
+     */
+    maxSonarAccuracy = IN2MM(2);
+  }
+  else if(distance > IN2MM(254)) {
+    /**
+     * The datasheet for the MB1040 specifies that maximum reported distance is 254 inches. If we for
+     * some reason should measure more than this, set the accuracy to 0.
+     */
+    maxSonarAccuracy = 0;
+  }
+  else {
+    /**
+     * Otherwise the accuracy is specified by the datasheet for the MB1040 to be 1 inch.
+     */
+    maxSonarAccuracy = IN2MM(1);
+  }
+
+  /* Report accuracy if the caller asked for this. */
+  return maxSonarAccuracy;
+}
+
+/**
+ * Reads distance measurement from an MB1040 sonar range finder (LV-MaxBotix-EZ4) via an analog input interface.
+ *
+ * @param pin      The GPIO pin to use for ADC conversion.
+ * @param accuracy If not NULL, this function will write the accuracy of the distance measurement (in mm) to this parameter.
+ *
+ * @return The distance measurement in millimeters.
+ */
+static uint32_t maxSonarReadDistanceMB1040AN(uint8_t pin, uint32_t *accuracy)
+{
+  /*
+   * analogRead() returns a 12-bit (0-4095) value scaled to the range between GND (0V) and VREF.
+   * The voltage conversion is: V = analogRead() / 4096 * VREF)
+   *
+   * The MB1040 sensor returns a voltage between GND and VREF, but scaled to VREF / 512 (volts-per-inch).
+   * Inches-per-volt is therefore expressed by (512 / VREF).
+   *
+   * The distance conversion is:             D = (512 / VREF) * V
+   * Expanding V, we get:                    D = (512 / VREF) * (analogRead() / 4096 * VREF)
+   * Which can be simplified to:             D = analogRead() / 8
+   * Last, we convert inches to millimeters: D = 25.4 * analogRead() / 8
+   * Which can be written as:                D = IN2MM(analogRead()) / 8
+   *   (to retain the sample's LSB)
+   *
+   * The above conversion assumes the ADC VREF is the same as the LV-MaxSonar-EZ4 VREF. This means
+   * that the MB1040 Sensor must have its VCC pin connected to the VCC pin on the deck port.
+   *
+   * According to the datasheet for the MB1040, the sensor draws typically 2mA, so powering it with
+   * the VCC pin on the deck port is safe.
+   */
+
+  maxSonarDistance = (uint32_t) (IN2MM(analogRead(pin)) / 8);
+
+  if(NULL != accuracy) {
+    *accuracy = maxSonarGetAccuracyMB1040(maxSonarDistance);
+  }
+  return maxSonarDistance;
+}
+
+/**
+ * Reads distance measurement from the specified sensor type.
+ *
+ * @param type     The MaxSonar sensor type.
+ * @param accuracy If not NULL, this function will write the accuracy of the distance measurement (in mm) to this parameter.
+ *
+ * @return The distance measurement in millimeters.
+ */
+uint32_t maxSonarReadDistance(maxSonarSensor_t type, uint32_t *accuracy)
+{
+  switch(type) {
+    case MAXSONAR_MB1040_AN: {
+      return maxSonarReadDistanceMB1040AN(MAXSONAR_DECK_GPIO, accuracy);
+    }
+  }
+
+  maxSonarDistance = 0;
+  maxSonarAccuracy = 0;
+  if(accuracy) {
+    *accuracy = maxSonarAccuracy;
+  }
+
+  return(maxSonarDistance);
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/motors.c b/crazyflie-firmware-src/src/drivers/src/motors.c
new file mode 100644
index 0000000000000000000000000000000000000000..3255a9f9604470090a50c609240d4ad78d9459cc
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/motors.c
@@ -0,0 +1,328 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * motors.c - Motor driver
+ *
+ * This code mainly interfacing the PWM peripheral lib of ST.
+ */
+
+#include <stdbool.h>
+
+/* ST includes */
+#include "stm32fxxx.h"
+
+#include "motors.h"
+#include "pm.h"
+
+//FreeRTOS includes
+#include "task.h"
+
+//Logging includes
+#include "log.h"
+
+static uint16_t motorsBLConvBitsTo16(uint16_t bits);
+static uint16_t motorsBLConv16ToBits(uint16_t bits);
+static uint16_t motorsConvBitsTo16(uint16_t bits);
+static uint16_t motorsConv16ToBits(uint16_t bits);
+
+uint32_t motor_ratios[] = {0, 0, 0, 0};
+
+void motorsPlayTone(uint16_t frequency, uint16_t duration_msec);
+void motorsPlayMelody(uint16_t *notes);
+void motorsBeep(int id, bool enable, uint16_t frequency, uint16_t ratio);
+
+#ifdef PLATFORM_CF1
+#include "motors_def_cf1.c"
+#else
+#include "motors_def_cf2.c"
+#endif
+
+const MotorPerifDef** motorMap;  /* Current map configuration */
+
+const uint32_t MOTORS[] = { MOTOR_M1, MOTOR_M2, MOTOR_M3, MOTOR_M4 };
+
+static const uint16_t testsound[NBR_OF_MOTORS] = {A4, A5, F5, D5 };
+
+static bool isInit = false;
+
+/* Private functions */
+
+static uint16_t motorsBLConvBitsTo16(uint16_t bits)
+{
+  return (0xFFFF * (bits - MOTORS_BL_PWM_CNT_FOR_HIGH) / MOTORS_BL_PWM_CNT_FOR_HIGH);
+}
+
+static uint16_t motorsBLConv16ToBits(uint16_t bits)
+{
+  return (MOTORS_BL_PWM_CNT_FOR_HIGH + ((bits * MOTORS_BL_PWM_CNT_FOR_HIGH) / 0xFFFF));
+}
+
+static uint16_t motorsConvBitsTo16(uint16_t bits)
+{
+  return ((bits) << (16 - MOTORS_PWM_BITS));
+}
+
+static uint16_t motorsConv16ToBits(uint16_t bits)
+{
+  return ((bits) >> (16 - MOTORS_PWM_BITS) & ((1 << MOTORS_PWM_BITS) - 1));
+}
+
+/* Public functions */
+
+//Initialization. Will set all motors ratio to 0%
+void motorsInit(const MotorPerifDef** motorMapSelect)
+{
+  int i;
+  //Init structures
+  GPIO_InitTypeDef GPIO_InitStructure;
+  TIM_TimeBaseInitTypeDef  TIM_TimeBaseStructure;
+  TIM_OCInitTypeDef  TIM_OCInitStructure;
+
+  if (isInit)
+  {
+    motorsDeInit(motorMap);
+  }
+
+  motorMap = motorMapSelect;
+
+  for (i = 0; i < NBR_OF_MOTORS; i++)
+  {
+    //Clock the gpio and the timers
+    MOTORS_RCC_GPIO_CMD(motorMap[i]->gpioPerif, ENABLE);
+    MOTORS_RCC_TIM_CMD(motorMap[i]->timPerif, ENABLE);
+
+    // Configure the GPIO for the timer output
+    GPIO_StructInit(&GPIO_InitStructure);
+    GPIO_InitStructure.GPIO_Mode = MOTORS_GPIO_MODE;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+#ifdef PLATFORM_CF2
+    GPIO_InitStructure.GPIO_OType = motorMap[i]->gpioOType;
+#endif
+    GPIO_InitStructure.GPIO_Pin = motorMap[i]->gpioPin;
+    GPIO_Init(motorMap[i]->gpioPort, &GPIO_InitStructure);
+
+    //Map timers to alternate functions
+    MOTORS_GPIO_AF_CFG(motorMap[i]->gpioPort, motorMap[i]->gpioPinSource, motorMap[i]->gpioAF);
+
+    //Timer configuration
+    TIM_TimeBaseStructure.TIM_Period = motorMap[i]->timPeriod;
+    TIM_TimeBaseStructure.TIM_Prescaler = motorMap[i]->timPrescaler;
+    TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+    TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+    TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+    TIM_TimeBaseInit(motorMap[i]->tim, &TIM_TimeBaseStructure);
+
+    // PWM channels configuration (All identical!)
+    TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+    TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+    TIM_OCInitStructure.TIM_Pulse = 0;
+    TIM_OCInitStructure.TIM_OCPolarity = motorMap[i]->timPolarity;
+    TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
+
+    // Configure Output Compare for PWM
+    motorMap[i]->ocInit(motorMap[i]->tim, &TIM_OCInitStructure);
+    motorMap[i]->preloadConfig(motorMap[i]->tim, TIM_OCPreload_Enable);
+
+    MOTORS_TIM_DBG_CFG(motorMap[i]->timDbgStop, ENABLE);
+    //Enable the timer PWM outputs
+    TIM_CtrlPWMOutputs(motorMap[i]->tim, ENABLE);
+  }
+
+  // Start the timers
+  for (i = 0; i < NBR_OF_MOTORS; i++)
+  {
+    TIM_Cmd(motorMap[i]->tim, ENABLE);
+  }
+
+  isInit = true;
+}
+
+void motorsDeInit(const MotorPerifDef** motorMapSelect)
+{
+  int i;
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  for (i = 0; i < NBR_OF_MOTORS; i++)
+  {
+    // Configure default
+    GPIO_StructInit(&GPIO_InitStructure);
+    GPIO_InitStructure.GPIO_Pin = motorMap[i]->gpioPin;
+    GPIO_Init(motorMap[i]->gpioPort, &GPIO_InitStructure);
+
+#ifdef PLATFORM_CF1
+    //Map timers to alternate functions
+    GPIO_PinRemapConfig(motorMap[i]->gpioAF , DISABLE);
+#else
+    //Map timers to alternate functions
+    GPIO_PinAFConfig(motorMap[i]->gpioPort, motorMap[i]->gpioPinSource, 0x00);
+#endif
+
+    //Deinit timer
+    TIM_DeInit(motorMap[i]->tim);
+  }
+}
+
+bool motorsTest(void)
+{
+  int i;
+
+  for (i = 0; i < sizeof(MOTORS) / sizeof(*MOTORS); i++)
+  {
+    if (motorMap[i]->drvType == BRUSHED)
+    {
+#ifdef ACTIVATE_STARTUP_SOUND
+      motorsBeep(MOTORS[i], true, testsound[i], (uint16_t)(MOTORS_TIM_BEEP_CLK_FREQ / A4)/ 20);
+      vTaskDelay(M2T(MOTORS_TEST_ON_TIME_MS));
+      motorsBeep(MOTORS[i], false, 0, 0);
+      vTaskDelay(M2T(MOTORS_TEST_DELAY_TIME_MS));
+#else
+      motorsSetRatio(MOTORS[i], MOTORS_TEST_RATIO);
+      vTaskDelay(M2T(MOTORS_TEST_ON_TIME_MS));
+      motorsSetRatio(MOTORS[i], 0);
+      vTaskDelay(M2T(MOTORS_TEST_DELAY_TIME_MS));
+#endif
+    }
+  }
+
+  return isInit;
+}
+
+// Ithrust is thrust mapped for 65536 <==> 60 grams
+void motorsSetRatio(uint32_t id, uint16_t ithrust)
+{
+  if (isInit) {
+    uint16_t ratio;
+
+    ASSERT(id < NBR_OF_MOTORS);
+
+    ratio = ithrust;
+
+  #ifdef ENABLE_THRUST_BAT_COMPENSATED
+    if (motorMap[id]->drvType == BRUSHED)
+    {
+      float thrust = ((float)ithrust / 65536.0f) * 60;
+      float volts = -0.0006239 * thrust * thrust + 0.088 * thrust;
+      float supply_voltage = pmGetBatteryVoltage();
+      float percentage = volts / supply_voltage;
+      percentage = percentage > 1.0 ? 1.0 : percentage;
+      ratio = percentage * UINT16_MAX;
+      motor_ratios[id] = ratio;
+
+    }
+  #endif
+    if (motorMap[id]->drvType == BRUSHLESS)
+    {
+      motorMap[id]->setCompare(motorMap[id]->tim, motorsBLConv16ToBits(ratio));
+    }
+    else
+    {
+      motorMap[id]->setCompare(motorMap[id]->tim, motorsConv16ToBits(ratio));
+    }
+  }
+}
+
+int motorsGetRatio(uint32_t id)
+{
+  int ratio;
+
+  ASSERT(id < NBR_OF_MOTORS);
+  if (motorMap[id]->drvType == BRUSHLESS)
+  {
+    ratio = motorsBLConvBitsTo16(motorMap[id]->getCompare(motorMap[id]->tim));
+  }
+  else
+  {
+    ratio = motorsConvBitsTo16(motorMap[id]->getCompare(motorMap[id]->tim));
+  }
+
+  return ratio;
+}
+
+/* Set PWM frequency for motor controller
+ * This function will set all motors into a "beep"-mode,
+ * each of the motor will turned on with a given ratio and frequency.
+ * The higher the ratio the higher the given power to the motors.
+ * ATTENTION: To much ratio can push your crazyflie into the air and hurt you!
+ * Example:
+ *     motorsBeep(true, 1000, (uint16_t)(72000000L / frequency)/ 20);
+ *     motorsBeep(false, 0, 0); *
+ * */
+void motorsBeep(int id, bool enable, uint16_t frequency, uint16_t ratio)
+{
+  TIM_TimeBaseInitTypeDef  TIM_TimeBaseStructure;
+
+  ASSERT(id < NBR_OF_MOTORS);
+
+  TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
+
+  if (enable)
+  {
+    TIM_TimeBaseStructure.TIM_Prescaler = (5 - 1);
+    TIM_TimeBaseStructure.TIM_Period = (uint16_t)(MOTORS_TIM_BEEP_CLK_FREQ / frequency);
+  }
+  else
+  {
+    TIM_TimeBaseStructure.TIM_Period = motorMap[id]->timPeriod;
+    TIM_TimeBaseStructure.TIM_Prescaler = motorMap[id]->timPrescaler;
+  }
+
+  // Timer configuration
+  TIM_TimeBaseInit(motorMap[id]->tim, &TIM_TimeBaseStructure);
+  motorMap[id]->setCompare(motorMap[id]->tim, ratio);
+}
+
+
+// Play a tone with a given frequency and a specific duration in milliseconds (ms)
+void motorsPlayTone(uint16_t frequency, uint16_t duration_msec)
+{
+  motorsBeep(MOTOR_M1, true, frequency, (uint16_t)(MOTORS_TIM_BEEP_CLK_FREQ / frequency)/ 20);
+  motorsBeep(MOTOR_M2, true, frequency, (uint16_t)(MOTORS_TIM_BEEP_CLK_FREQ / frequency)/ 20);
+  motorsBeep(MOTOR_M3, true, frequency, (uint16_t)(MOTORS_TIM_BEEP_CLK_FREQ / frequency)/ 20);
+  motorsBeep(MOTOR_M4, true, frequency, (uint16_t)(MOTORS_TIM_BEEP_CLK_FREQ / frequency)/ 20);
+  vTaskDelay(M2T(duration_msec));
+  motorsBeep(MOTOR_M1, false, frequency, 0);
+  motorsBeep(MOTOR_M2, false, frequency, 0);
+  motorsBeep(MOTOR_M3, false, frequency, 0);
+  motorsBeep(MOTOR_M4, false, frequency, 0);
+}
+
+// Plays a melody from a note array
+void motorsPlayMelody(uint16_t *notes)
+{
+  int i = 0;
+  uint16_t note;      // Note in hz
+  uint16_t duration;  // Duration in ms
+
+  do
+  {
+    note = notes[i++];
+    duration = notes[i++];
+    motorsPlayTone(note, duration);
+  } while (duration != 0);
+}
+LOG_GROUP_START(pwm)
+LOG_ADD(LOG_UINT32, m1_pwm, &motor_ratios[0])
+LOG_ADD(LOG_UINT32, m2_pwm, &motor_ratios[1])
+LOG_ADD(LOG_UINT32, m3_pwm, &motor_ratios[2])
+LOG_ADD(LOG_UINT32, m4_pwm, &motor_ratios[3])
+LOG_GROUP_STOP(pwm)
diff --git a/crazyflie-firmware-src/src/drivers/src/motors_def_cf1.c b/crazyflie-firmware-src/src/drivers/src/motors_def_cf1.c
new file mode 100644
index 0000000000000000000000000000000000000000..10d12b58980b5ebc78ee15c8638fd2305ec1d2fe
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/motors_def_cf1.c
@@ -0,0 +1,217 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * motors.c - Motor driver
+ *
+ * This code mainly interfacing the PWM peripheral lib of ST.
+ */
+
+static const MotorPerifDef CONN_M1 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_1,
+    .gpioPinSource = GPIO_PinSource1,
+    .gpioOType     = 0,
+    .gpioAF        = GPIO_PartialRemap_TIM3,
+    .timPerif      = RCC_APB1Periph_TIM3,
+    .tim           = TIM3,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM3_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+static const MotorPerifDef CONN_M2 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_0,
+    .gpioPinSource = GPIO_PinSource0,
+    .gpioOType     = 0,
+    .gpioAF        = GPIO_PartialRemap_TIM3,
+    .timPerif      = RCC_APB1Periph_TIM3,
+    .tim           = TIM3,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM3_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare3,
+    .getCompare    = TIM_GetCapture3,
+    .ocInit        = TIM_OC3Init,
+    .preloadConfig = TIM_OC3PreloadConfig,
+};
+
+static const MotorPerifDef CONN_M3 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_9,
+    .gpioPinSource = GPIO_PinSource9,
+    .gpioOType     = 0,
+    .gpioAF        = 0,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+static const MotorPerifDef CONN_M4 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_8,
+    .gpioPinSource = GPIO_PinSource8,
+    .gpioOType     = 0,
+    .gpioAF        = 0,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare3,
+    .getCompare    = TIM_GetCapture3,
+    .ocInit        = TIM_OC3Init,
+    .preloadConfig = TIM_OC3PreloadConfig,
+};
+
+static const MotorPerifDef CONN_M1_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_1,
+    .gpioPinSource = GPIO_PinSource1,
+    .gpioOType     = 0,
+    .gpioAF        = GPIO_PartialRemap_TIM3,
+    .timPerif      = RCC_APB1Periph_TIM3,
+    .tim           = TIM3,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM3_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+static const MotorPerifDef CONN_M2_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_0,
+    .gpioPinSource = GPIO_PinSource0,
+    .gpioOType     = 0,
+    .gpioAF        = GPIO_PartialRemap_TIM3,
+    .timPerif      = RCC_APB1Periph_TIM3,
+    .tim           = TIM3,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM3_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare3,
+    .getCompare    = TIM_GetCapture3,
+    .ocInit        = TIM_OC3Init,
+    .preloadConfig = TIM_OC3PreloadConfig,
+};
+
+static const MotorPerifDef CONN_M3_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_9,
+    .gpioPinSource = GPIO_PinSource9,
+    .gpioOType     = 0,
+    .gpioAF        = 0,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+static const MotorPerifDef CONN_M4_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_APB2Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_8,
+    .gpioPinSource = GPIO_PinSource8,
+    .gpioOType     = 0,
+    .gpioAF        = 0,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare3,
+    .getCompare    = TIM_GetCapture3,
+    .ocInit        = TIM_OC3Init,
+    .preloadConfig = TIM_OC3PreloadConfig,
+};
+
+/**
+ * Default brushed mapping to M1-M4 connectors.
+ */
+const MotorPerifDef* motorMapDefaultBrushed[NBR_OF_MOTORS] =
+{
+  &CONN_M1,
+  &CONN_M2,
+  &CONN_M3,
+  &CONN_M4
+};
+
+/**
+ * Brushless motors mapped to the standard motor connectors with pull-ups (~1K) to VBAT soldered.
+ */
+const MotorPerifDef* motorMapDefaltConBrushless[NBR_OF_MOTORS] =
+{
+  &CONN_M1_BL,
+  &CONN_M2_BL,
+  &CONN_M3_BL,
+  &CONN_M4_BL
+};
diff --git a/crazyflie-firmware-src/src/drivers/src/motors_def_cf2.c b/crazyflie-firmware-src/src/drivers/src/motors_def_cf2.c
new file mode 100644
index 0000000000000000000000000000000000000000..0df13a46be53d35254a4fbd683be9fd3402ed367
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/motors_def_cf2.c
@@ -0,0 +1,559 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * motors.c - Motor driver
+ *
+ * This code mainly interfacing the PWM peripheral lib of ST.
+ */
+// Connector M1, PA1, TIM2_CH2
+static const MotorPerifDef CONN_M1 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_1,
+    .gpioPinSource = GPIO_PinSource1,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare2,
+    .getCompare    = TIM_GetCapture2,
+    .ocInit        = TIM_OC2Init,
+    .preloadConfig = TIM_OC2PreloadConfig,
+};
+
+// Connector M2, PB11, TIM2_CH4
+static const MotorPerifDef CONN_M2 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_11,
+    .gpioPinSource = GPIO_PinSource11,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// Connector M3, PA15, TIM2_CH1
+static const MotorPerifDef CONN_M3 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_15,
+    .gpioPinSource = GPIO_PinSource15,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare1,
+    .getCompare    = TIM_GetCapture1,
+    .ocInit        = TIM_OC1Init,
+    .preloadConfig = TIM_OC1PreloadConfig,
+};
+
+// Connector M4, PB9, TIM4_CH4
+static const MotorPerifDef CONN_M4 =
+{
+    .drvType       = BRUSHED,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_9,
+    .gpioPinSource = GPIO_PinSource9,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM4,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_PWM_PERIOD,
+    .timPrescaler  = MOTORS_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// Connector M1, PA1, TIM2_CH2, Brushless config, inversed
+static const MotorPerifDef CONN_M1_BL_INV =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_1,
+    .gpioPinSource = GPIO_PinSource1,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare2,
+    .getCompare    = TIM_GetCapture2,
+    .ocInit        = TIM_OC2Init,
+    .preloadConfig = TIM_OC2PreloadConfig,
+};
+
+// Connector M2, PB11, TIM2_CH4, Brushless config, inversed
+static const MotorPerifDef CONN_M2_BL_INV =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_11,
+    .gpioPinSource = GPIO_PinSource11,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// Connector M3, PA15, TIM2_CH1, Brushless config, inversed
+static const MotorPerifDef CONN_M3_BL_INV =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_15,
+    .gpioPinSource = GPIO_PinSource15,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare1,
+    .getCompare    = TIM_GetCapture1,
+    .ocInit        = TIM_OC1Init,
+    .preloadConfig = TIM_OC1PreloadConfig,
+};
+
+// Connector M4, PB9, TIM4_CH4, Brushless config, inversed
+static const MotorPerifDef CONN_M4_BL_INV =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_9,
+    .gpioPinSource = GPIO_PinSource9,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM4,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_Low,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// RZR M1, PA1, TIM2_CH2, Brushless config
+static const MotorPerifDef RZR_M1_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_1,
+    .gpioPinSource = GPIO_PinSource1,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare2,
+    .getCompare    = TIM_GetCapture2,
+    .ocInit        = TIM_OC2Init,
+    .preloadConfig = TIM_OC2PreloadConfig,
+};
+
+// RZR M2, PB11, TIM2_CH4, Brushless config
+static const MotorPerifDef RZR_M2_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_11,
+    .gpioPinSource = GPIO_PinSource11,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// RZR M3, PA15, TIM2_CH1, Brushless config
+static const MotorPerifDef RZR_M3_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_15,
+    .gpioPinSource = GPIO_PinSource15,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare1,
+    .getCompare    = TIM_GetCapture1,
+    .ocInit        = TIM_OC1Init,
+    .preloadConfig = TIM_OC1PreloadConfig,
+};
+
+// RZR M4, PB9, TIM4_CH4, Brushless config
+static const MotorPerifDef RZR_M4_BL =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_9,
+    .gpioPinSource = GPIO_PinSource9,
+    .gpioOType     = GPIO_OType_PP,
+    .gpioAF        = GPIO_AF_TIM4,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// Deck TX2, PA2, TIM2_CH3
+static const MotorPerifDef DECK_TX2_TIM2 =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_2,
+    .gpioPinSource = GPIO_PinSource2,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare3,
+    .getCompare    = TIM_GetCapture3,
+    .ocInit        = TIM_OC3Init,
+    .preloadConfig = TIM_OC3PreloadConfig,
+};
+
+// Deck TX2, PA2, TIM5_CH3
+static const MotorPerifDef DECK_TX2_TIM5 =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_2,
+    .gpioPinSource = GPIO_PinSource2,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM5,
+    .timPerif      = RCC_APB1Periph_TIM5,
+    .tim           = TIM5,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM5_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare3,
+    .getCompare    = TIM_GetCapture3,
+    .ocInit        = TIM_OC3Init,
+    .preloadConfig = TIM_OC3PreloadConfig,
+};
+
+// Deck RX2, PA3, TIM2_CH4
+static const MotorPerifDef DECK_RX2_TIM2 =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_3,
+    .gpioPinSource = GPIO_PinSource3,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// Deck RX2, PA3, TIM5_CH4
+static const MotorPerifDef DECK_RX2_TIM5 =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_3,
+    .gpioPinSource = GPIO_PinSource3,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM5,
+    .timPerif      = RCC_APB1Periph_TIM5,
+    .tim           = TIM5,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM5_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare4,
+    .getCompare    = TIM_GetCapture4,
+    .ocInit        = TIM_OC4Init,
+    .preloadConfig = TIM_OC4PreloadConfig,
+};
+
+// Deck IO1, PB8, TIM4_CH3
+static const MotorPerifDef DECK_IO1_TIM4 =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_8,
+    .gpioPinSource = GPIO_PinSource8,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM4,
+    .timPerif      = RCC_APB1Periph_TIM4,
+    .tim           = TIM4,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM4_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare3,
+    .getCompare    = TIM_GetCapture3,
+    .ocInit        = TIM_OC3Init,
+    .preloadConfig = TIM_OC3PreloadConfig,
+};
+
+// Deck IO2, PB5, TIM3_CH2
+static const MotorPerifDef DECK_IO2 =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_5,
+    .gpioPinSource = GPIO_PinSource5,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM3,
+    .timPerif      = RCC_APB1Periph_TIM3,
+    .tim           = TIM3,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM3_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare2,
+    .getCompare    = TIM_GetCapture2,
+    .ocInit        = TIM_OC2Init,
+    .preloadConfig = TIM_OC2PreloadConfig,
+};
+
+// Deck IO3, PB4, TIM3_CH1
+static const MotorPerifDef DECK_IO3 =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOB,
+    .gpioPort      = GPIOB,
+    .gpioPin       = GPIO_Pin_4,
+    .gpioPinSource = GPIO_PinSource4,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM3,
+    .timPerif      = RCC_APB1Periph_TIM3,
+    .tim           = TIM3,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM3_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare1,
+    .getCompare    = TIM_GetCapture1,
+    .ocInit        = TIM_OC1Init,
+    .preloadConfig = TIM_OC1PreloadConfig,
+};
+
+// Deck SCK, PA5, TIM2_CH1
+static const MotorPerifDef DECK_SCK =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_5,
+    .gpioPinSource = GPIO_PinSource5,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM2,
+    .timPerif      = RCC_APB1Periph_TIM2,
+    .tim           = TIM2,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM2_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare1,
+    .getCompare    = TIM_GetCapture1,
+    .ocInit        = TIM_OC1Init,
+    .preloadConfig = TIM_OC1PreloadConfig,
+};
+
+// Deck MISO, PA6, TIM3_CH1
+static const MotorPerifDef DECK_MISO =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_6,
+    .gpioPinSource = GPIO_PinSource6,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM3,
+    .timPerif      = RCC_APB1Periph_TIM3,
+    .tim           = TIM3,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM3_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare1,
+    .getCompare    = TIM_GetCapture1,
+    .ocInit        = TIM_OC1Init,
+    .preloadConfig = TIM_OC1PreloadConfig,
+};
+
+// Deck MOSI, PA7, TIM14_CH1
+static const MotorPerifDef DECK_MOSI =
+{
+    .drvType       = BRUSHLESS,
+    .gpioPerif     = RCC_AHB1Periph_GPIOA,
+    .gpioPort      = GPIOA,
+    .gpioPin       = GPIO_Pin_7,
+    .gpioPinSource = GPIO_PinSource7,
+    .gpioOType     = GPIO_OType_OD,
+    .gpioAF        = GPIO_AF_TIM14,
+    .timPerif      = RCC_APB1Periph_TIM14,
+    .tim           = TIM14,
+    .timPolarity   = TIM_OCPolarity_High,
+    .timDbgStop    = DBGMCU_TIM14_STOP,
+    .timPeriod     = MOTORS_BL_PWM_PERIOD,
+    .timPrescaler  = MOTORS_BL_PWM_PRESCALE,
+    .setCompare    = TIM_SetCompare1,
+    .getCompare    = TIM_GetCapture1,
+    .ocInit        = TIM_OC1Init,
+    .preloadConfig = TIM_OC1PreloadConfig,
+};
+
+/**
+ * Default brushed mapping to M1-M4 connectors.
+ */
+const MotorPerifDef* motorMapDefaultBrushed[NBR_OF_MOTORS] =
+{
+  &CONN_M1,
+  &CONN_M2,
+  &CONN_M3,
+  &CONN_M4
+};
+
+/**
+ * Brushless motors mapped as on the Big-Quad deck
+ * M1 -> TX2
+ * M2 -> IO3
+ * M3 -> IO2
+ * M4 -> RX2
+ */
+const MotorPerifDef* motorMapBigQuadDeck[NBR_OF_MOTORS] =
+{
+  &DECK_TX2_TIM2,
+  &DECK_IO3,
+  &DECK_IO2,
+  &DECK_RX2_TIM2
+};
+
+/**
+ * Brushless motors mapped to the standard motor connectors with pull-ups (~1K) to VBAT soldered.
+ */
+const MotorPerifDef* motorMapDefaltConBrushless[NBR_OF_MOTORS] =
+{
+  &CONN_M1_BL_INV,
+  &CONN_M2_BL_INV,
+  &CONN_M3_BL_INV,
+  &CONN_M4_BL_INV
+};
+
+/**
+ * Brushless motors mapped to the RZR PWM outputs.
+ */
+const MotorPerifDef* motorMapRZRBrushless[NBR_OF_MOTORS] =
+{
+  &RZR_M1_BL,
+  &RZR_M2_BL,
+  &RZR_M3_BL,
+  &RZR_M4_BL
+};
+
diff --git a/crazyflie-firmware-src/src/drivers/src/mpu6050.c b/crazyflie-firmware-src/src/drivers/src/mpu6050.c
new file mode 100644
index 0000000000000000000000000000000000000000..2019e48d48544630dbf7463bffa5202734844cdd
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/mpu6050.c
@@ -0,0 +1,3675 @@
+// I2Cdev library collection - MPU6050 I2C device class
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 8/24/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+
+/* ============================================
+ I2Cdev device library code is placed under the MIT license
+ Copyright (c) 2011 Jeff Rowberg
+ Adapted to Crazyflie FW by Bitcraze
+
+ Permission is hereby granted, free of charge, to any person obtaining a copy
+ of this software and associated documentation files (the "Software"), to deal
+ in the Software without restriction, including without limitation the rights
+ to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ copies of the Software, and to permit persons to whom the Software is
+ furnished to do so, subject to the following conditions:
+
+ The above copyright notice and this permission notice shall be included in
+ all copies or substantial portions of the Software.
+
+ THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ THE SOFTWARE.
+ ===============================================
+ */
+#define DEBUG_MODULE "MPU6050"
+
+#include "stm32fxxx.h"
+#include "FreeRTOS.h"
+#include "task.h"
+
+// TA: Maybe not so good to bring in these dependencies...
+#include "debug.h"
+#include "eprintf.h"
+#include "i2cdev.h"
+
+#include "mpu6050.h"
+
+static uint8_t devAddr;
+static I2C_Dev *I2Cx;
+static uint8_t buffer[14];
+static bool isInit;
+
+/** Default constructor, uses default I2C address.
+ * @see MPU6050_DEFAULT_ADDRESS
+ */
+void mpu6050Init(I2C_Dev *i2cPort)
+{
+  if (isInit)
+    return;
+
+  I2Cx = i2cPort;
+  devAddr = MPU6050_ADDRESS_AD0_HIGH;
+//FIXME    devAddr = MPU6050_ADDRESS_AD0_LOW;
+
+  isInit = true;
+}
+
+bool mpu6050Test(void)
+{
+  bool testStatus;
+
+  if (!isInit)
+    return false;
+
+  testStatus = mpu6050TestConnection();
+
+  return testStatus;
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool mpu6050TestConnection()
+{
+  return mpu6050GetDeviceID() == 0b110100;
+}
+
+/** Do a MPU6050 self test.
+ * @return True if self test passed, false otherwise
+ */
+bool mpu6050SelfTest()
+{
+  bool testStatus = true;
+  int16_t axi16, ayi16, azi16;
+  int16_t gxi16, gyi16, gzi16;
+//  int8_t axfi8, ayfi8, azfi8;
+//  int8_t gxfi8, gyfi8, gzfi8;
+  float axf, ayf, azf;
+  float gxf, gyf, gzf;
+  float axfTst, ayfTst, azfTst;
+  float gxfTst, gyfTst, gzfTst;
+  float axfDiff, ayfDiff, azfDiff;
+  float gxfDiff, gyfDiff, gzfDiff;
+  float gRange, aRange;
+  uint32_t scrap;
+
+  aRange = mpu6050GetFullScaleAccelGPL();
+  gRange = mpu6050GetFullScaleGyroDPL();
+
+  // First values after startup can be read as zero. Scrap a couple to be sure.
+  for (scrap = 0; scrap < 20; scrap++)
+  {
+    mpu6050GetMotion6(&axi16, &ayi16, &azi16, &gxi16, &gyi16, &gzi16);
+    vTaskDelay(M2T(2));
+  }
+  // First measurement
+  gxf = gxi16 * gRange;
+  gyf = gyi16 * gRange;
+  gzf = gzi16 * gRange;
+  axf = axi16 * aRange;
+  ayf = ayi16 * aRange;
+  azf = azi16 * aRange;
+
+  // Enable self test
+  mpu6050SetGyroXSelfTest(true);
+  mpu6050SetGyroYSelfTest(true);
+  mpu6050SetGyroZSelfTest(true);
+  mpu6050SetAccelXSelfTest(true);
+  mpu6050SetAccelYSelfTest(true);
+  mpu6050SetAccelZSelfTest(true);
+
+  // Wait for self test to take effect
+  vTaskDelay(M2T(MPU6050_SELF_TEST_DELAY_MS));
+  // Take second measurement
+  mpu6050GetMotion6(&axi16, &ayi16, &azi16, &gxi16, &gyi16, &gzi16);
+  gxfTst = gxi16 * gRange;
+  gyfTst = gyi16 * gRange;
+  gzfTst = gzi16 * gRange;
+  axfTst = axi16 * aRange;
+  ayfTst = ayi16 * aRange;
+  azfTst = azi16 * aRange;
+
+  // Disable self test
+  mpu6050SetGyroXSelfTest(false);
+  mpu6050SetGyroYSelfTest(false);
+  mpu6050SetGyroZSelfTest(false);
+  mpu6050SetAccelXSelfTest(false);
+  mpu6050SetAccelYSelfTest(false);
+  mpu6050SetAccelZSelfTest(false);
+
+//  // Read factory values
+//  i2cdevReadByte(I2Cx, devAddr, 0x00, (uint8_t *)&gxfi8);
+//  i2cdevReadByte(I2Cx, devAddr, 0x01, (uint8_t *)&gyfi8);
+//  i2cdevReadByte(I2Cx, devAddr, 0x02, (uint8_t *)&gzfi8);
+//  i2cdevReadByte(I2Cx, devAddr, 0x0D, (uint8_t *)&axfi8);
+//  i2cdevReadByte(I2Cx, devAddr, 0x0E, (uint8_t *)&ayfi8);
+//  i2cdevReadByte(I2Cx, devAddr, 0x0F, (uint8_t *)&azfi8);
+//
+//  DEBUG_PRINT("gxf:%i, gyf:%i, gzf:%i, axf:%i, ayf:%i, azf:%i\n",
+//              (int)gxfi8, (int)gyfi8, (int)gzfi8, (int)axfi8, (int)ayfi8, (int)azfi8);
+
+  // Calculate difference
+  gxfDiff = gxfTst - gxf;
+  gyfDiff = gyfTst - gyf;
+  gzfDiff = gzfTst - gzf;
+  axfDiff = axfTst - axf;
+  ayfDiff = ayfTst - ayf;
+  azfDiff = azfTst - azf;
+
+  // Check result
+  if (mpu6050EvaluateSelfTest(MPU6050_ST_GYRO_LOW, MPU6050_ST_GYRO_HIGH, gxfDiff, "gyro X") &&
+      mpu6050EvaluateSelfTest(-MPU6050_ST_GYRO_HIGH, -MPU6050_ST_GYRO_LOW, gyfDiff, "gyro Y") &&
+      mpu6050EvaluateSelfTest(MPU6050_ST_GYRO_LOW, MPU6050_ST_GYRO_HIGH, gzfDiff, "gyro Z") &&
+      mpu6050EvaluateSelfTest(MPU6050_ST_ACCEL_LOW, MPU6050_ST_ACCEL_HIGH, axfDiff, "acc X") &&
+      mpu6050EvaluateSelfTest(MPU6050_ST_ACCEL_LOW, MPU6050_ST_ACCEL_HIGH, ayfDiff, "acc Y") &&
+      mpu6050EvaluateSelfTest(MPU6050_ST_ACCEL_LOW, MPU6050_ST_ACCEL_HIGH, azfDiff, "acc Z"))
+  {
+    DEBUG_PRINT("Self test [OK].\n");
+  }
+  else
+  {
+    testStatus = false;
+  }
+
+  return testStatus;
+}
+
+/** Evaluate the values from a MPU6050 self test.
+ * @param low The low limit of the self test
+ * @param high The high limit of the self test
+ * @param value The value to compare with.
+ * @param string A pointer to a string describing the value.
+ * @return True if self test within low - high limit, false otherwise
+ */
+bool mpu6050EvaluateSelfTest(float low, float high, float value, char* string)
+{
+  if (value < low || value > high)
+  {
+    DEBUG_PRINT("Self test %s [FAIL]. low: %0.2f, high: %0.2f, measured: %0.2f\n",
+                string, low, high, value);
+    return false;
+  }
+  return true;
+}
+
+// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC)
+
+/** Get the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @return I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+uint8_t mpu6050GetAuxVDDIOLevel()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer);
+  return buffer[0];
+}
+/** Set the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @param level I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+void mpu6050SetAuxVDDIOLevel(uint8_t level)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level);
+}
+
+// SMPLRT_DIV register
+
+/** Get gyroscope output rate divider.
+ * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero
+ * Motion detection, and Free Fall detection are all based on the Sample Rate.
+ * The Sample Rate is generated by dividing the gyroscope output rate by
+ * SMPLRT_DIV:
+ *
+ * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
+ *
+ * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or
+ * 7), and 1kHz when the DLPF is enabled (see Register 26).
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * For a diagram of the gyroscope and accelerometer signal paths, see Section 8
+ * of the MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current sample rate
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+uint8_t mpu6050GetRate()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_SMPLRT_DIV, buffer);
+  return buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+void mpu6050SetRate(uint8_t rate)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_SMPLRT_DIV, rate);
+}
+
+// CONFIG register
+
+/** Get external FSYNC configuration.
+ * Configures the external Frame Synchronization (FSYNC) pin sampling. An
+ * external signal connected to the FSYNC pin can be sampled by configuring
+ * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short
+ * strobes may be captured. The latched FSYNC signal will be sampled at the
+ * Sampling Rate, as defined in register 25. After sampling, the latch will
+ * reset to the current FSYNC signal state.
+ *
+ * The sampled value will be reported in place of the least significant bit in
+ * a sensor data register determined by the value of EXT_SYNC_SET according to
+ * the following table.
+ *
+ * <pre>
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0            | Input disabled
+ * 1            | TEMP_OUT_L[0]
+ * 2            | GYRO_XOUT_L[0]
+ * 3            | GYRO_YOUT_L[0]
+ * 4            | GYRO_ZOUT_L[0]
+ * 5            | ACCEL_XOUT_L[0]
+ * 6            | ACCEL_YOUT_L[0]
+ * 7            | ACCEL_ZOUT_L[0]
+ * </pre>
+ *
+ * @return FSYNC configuration value
+ */
+uint8_t mpu6050GetExternalFrameSync()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT,
+      MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set external FSYNC configuration.
+ * @see getExternalFrameSync()
+ * @see MPU6050_RA_CONFIG
+ * @param sync New FSYNC configuration value
+ */
+void mpu6050SetExternalFrameSync(uint8_t sync)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT,
+      MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync);
+}
+/** Get digital low-pass filter configuration.
+ * The DLPF_CFG parameter sets the digital low pass filter configuration. It
+ * also determines the internal sampling rate used by the device as shown in
+ * the table below.
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * <pre>
+ *          |   ACCELEROMETER    |           GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
+ * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
+ * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
+ * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
+ * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
+ * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
+ * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
+ * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
+ * </pre>
+ *
+ * @return DLFP configuration
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+uint8_t mpu6050GetDLPFMode()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT,
+      MPU6050_CFG_DLPF_CFG_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set digital low-pass filter configuration.
+ * @param mode New DLFP configuration setting
+ * @see getDLPFBandwidth()
+ * @see MPU6050_DLPF_BW_256
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+void mpu6050SetDLPFMode(uint8_t mode)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT,
+      MPU6050_CFG_DLPF_CFG_LENGTH, mode);
+}
+
+// GYRO_CONFIG register
+
+/** Get full-scale gyroscope range id.
+ * The FS_SEL parameter allows setting the full-scale range of the gyro sensors,
+ * as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * </pre>
+ *
+ * @return Current full-scale gyroscope range setting
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+uint8_t mpu6050GetFullScaleGyroRangeId()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT,
+      MPU6050_GCONFIG_FS_SEL_LENGTH, buffer);
+  return buffer[0];
+}
+
+/** Get full-scale gyroscope degrees per LSB.
+ *
+ * @return float of current full-scale gyroscope setting as degrees per LSB
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+float mpu6050GetFullScaleGyroDPL()
+{
+  int32_t rangeId;
+  float range;
+
+  rangeId = mpu6050GetFullScaleGyroRangeId();
+  switch (rangeId)
+  {
+    case MPU6050_GYRO_FS_250:
+      range = MPU6050_DEG_PER_LSB_250;
+      break;
+    case MPU6050_GYRO_FS_500:
+      range = MPU6050_DEG_PER_LSB_500;
+      break;
+    case MPU6050_GYRO_FS_1000:
+      range = MPU6050_DEG_PER_LSB_1000;
+      break;
+    case MPU6050_GYRO_FS_2000:
+      range = MPU6050_DEG_PER_LSB_2000;
+      break;
+    default:
+      range = MPU6050_DEG_PER_LSB_1000;
+      break;
+  }
+
+  return range;
+}
+
+/** Set full-scale gyroscope range.
+ * @param range New full-scale gyroscope range value
+ * @see getFullScaleRange()
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+void mpu6050SetFullScaleGyroRange(uint8_t range)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT,
+      MPU6050_GCONFIG_FS_SEL_LENGTH, range);
+}
+
+void mpu6050SetGyroXSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_XG_ST_BIT, enabled);
+}
+
+void mpu6050SetGyroYSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_YG_ST_BIT, enabled);
+}
+
+void mpu6050SetGyroZSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_ZG_ST_BIT, enabled);
+}
+
+// ACCEL_CONFIG register
+
+/** Get self-test enabled setting for accelerometer X axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool mpu6050GetAccelXSelfTest()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer);
+  return buffer[0];
+}
+/** Get self-test enabled setting for accelerometer X axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void mpu6050SetAccelXSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool mpu6050GetAccelYSelfTest()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer);
+  return buffer[0];
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void mpu6050SetAccelYSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Z axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool mpu6050GetAccelZSelfTest()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer);
+  return buffer[0];
+}
+/** Set self-test enabled value for accelerometer Z axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void mpu6050SetAccelZSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled);
+}
+/** Get full-scale accelerometer range.
+ * The FS_SEL parameter allows setting the full-scale range of the accelerometer
+ * sensors, as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * </pre>
+ *
+ * @return Current full-scale accelerometer range setting
+ * @see MPU6050_ACCEL_FS_2
+ * @see MPU6050_RA_ACCEL_CONFIG
+ * @see MPU6050_ACONFIG_AFS_SEL_BIT
+ * @see MPU6050_ACONFIG_AFS_SEL_LENGTH
+ */
+uint8_t mpu6050GetFullScaleAccelRangeId()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT,
+      MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer);
+  return buffer[0];
+}
+
+/** Get full-scale accelerometer G per LSB.
+ *
+ * @return float of current full-scale accelerometer setting as G per LSB
+ * @see MPU6050_ACCEL_FS_2
+ * @see MPU6050_RA_ACCEL_CONFIG
+ * @see MPU6050_ACONFIG_AFS_SEL_BIT
+ * @see MPU6050_ACONFIG_AFS_SEL_LENGTH
+ */
+float mpu6050GetFullScaleAccelGPL()
+{
+  int32_t rangeId;
+  float range;
+
+  rangeId = mpu6050GetFullScaleAccelRangeId();
+  switch (rangeId)
+  {
+    case MPU6050_ACCEL_FS_2:
+      range = MPU6050_G_PER_LSB_2;
+      break;
+    case MPU6050_ACCEL_FS_4:
+      range = MPU6050_G_PER_LSB_4;
+      break;
+    case MPU6050_ACCEL_FS_8:
+      range = MPU6050_G_PER_LSB_8;
+      break;
+    case MPU6050_ACCEL_FS_16:
+      range = MPU6050_G_PER_LSB_16;
+      break;
+    default:
+      range = MPU6050_DEG_PER_LSB_1000;
+      break;
+  }
+
+  return range;
+}
+
+/** Set full-scale accelerometer range.
+ * @param range New full-scale accelerometer range setting
+ * @see getFullScaleAccelRange()
+ */
+void mpu6050SetFullScaleAccelRange(uint8_t range)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT,
+      MPU6050_ACONFIG_AFS_SEL_LENGTH, range);
+}
+/** Get the high-pass filter configuration.
+ * The DHPF is a filter module in the path leading to motion detectors (Free
+ * Fall, Motion threshold, and Zero Motion). The high pass filter output is not
+ * available to the data registers (see Figure in Section 8 of the MPU-6000/
+ * MPU-6050 Product Specification document).
+ *
+ * The high pass filter has three modes:
+ *
+ * <pre>
+ *    Reset: The filter output settles to zero within one sample. This
+ *           effectively disables the high pass filter. This mode may be toggled
+ *           to quickly settle the filter.
+ *
+ *    On:    The high pass filter will pass signals above the cut off frequency.
+ *
+ *    Hold:  When triggered, the filter holds the present sample. The filter
+ *           output will be the difference between the input sample and the held
+ *           sample.
+ * </pre>
+ *
+ * <pre>
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0         | Reset       | None
+ * 1         | On          | 5Hz
+ * 2         | On          | 2.5Hz
+ * 3         | On          | 1.25Hz
+ * 4         | On          | 0.63Hz
+ * 7         | Hold        | None
+ * </pre>
+ *
+ * @return Current high-pass filter configuration
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+uint8_t mpu6050GetDHPFMode()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT,
+      MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set the high-pass filter configuration.
+ * @param bandwidth New high-pass filter configuration
+ * @see setDHPFMode()
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void mpu6050SetDHPFMode(uint8_t bandwidth)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT,
+      MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth);
+}
+
+// FF_THR register
+
+/** Get free-fall event acceleration threshold.
+ * This register configures the detection threshold for Free Fall event
+ * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the
+ * absolute value of the accelerometer measurements for the three axes are each
+ * less than the detection threshold. This condition increments the Free Fall
+ * duration counter (Register 30). The Free Fall interrupt is triggered when the
+ * Free Fall duration counter reaches the time specified in FF_DUR.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current free-fall acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_FF_THR
+ */
+uint8_t mpu6050GetFreefallDetectionThreshold()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_FF_THR, buffer);
+  return buffer[0];
+}
+/** Get free-fall event acceleration threshold.
+ * @param threshold New free-fall acceleration threshold value (LSB = 2mg)
+ * @see getFreefallDetectionThreshold()
+ * @see MPU6050_RA_FF_THR
+ */
+void mpu6050SetFreefallDetectionThreshold(uint8_t threshold)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_FF_THR, threshold);
+}
+
+// FF_DUR register
+
+/** Get free-fall event duration threshold.
+ * This register configures the duration counter threshold for Free Fall event
+ * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit
+ * of 1 LSB = 1 ms.
+ *
+ * The Free Fall duration counter increments while the absolute value of the
+ * accelerometer measurements are each less than the detection threshold
+ * (Register 29). The Free Fall interrupt is triggered when the Free Fall
+ * duration counter reaches the time specified in this register.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current free-fall duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_FF_DUR
+ */
+uint8_t mpu6050GetFreefallDetectionDuration()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_FF_DUR, buffer);
+  return buffer[0];
+}
+/** Get free-fall event duration threshold.
+ * @param duration New free-fall duration threshold value (LSB = 1ms)
+ * @see getFreefallDetectionDuration()
+ * @see MPU6050_RA_FF_DUR
+ */
+void mpu6050SetFreefallDetectionDuration(uint8_t duration)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_FF_DUR, duration);
+}
+
+// MOT_THR register
+
+/** Get motion detection event acceleration threshold.
+ * This register configures the detection threshold for Motion interrupt
+ * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the
+ * absolute value of any of the accelerometer measurements exceeds this Motion
+ * detection threshold. This condition increments the Motion detection duration
+ * counter (Register 32). The Motion detection interrupt is triggered when the
+ * Motion Detection counter reaches the time count specified in MOT_DUR
+ * (Register 32).
+ *
+ * The Motion interrupt will indicate the axis and polarity of detected motion
+ * in MOT_DETECT_STATUS (Register 97).
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_MOT_THR
+ */
+uint8_t mpu6050GetMotionDetectionThreshold()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_MOT_THR, buffer);
+  return buffer[0];
+}
+/** Set free-fall event acceleration threshold.
+ * @param threshold New motion detection acceleration threshold value (LSB = 2mg)
+ * @see getMotionDetectionThreshold()
+ * @see MPU6050_RA_MOT_THR
+ */
+void mpu6050SetMotionDetectionThreshold(uint8_t threshold)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_MOT_THR, threshold);
+}
+
+// MOT_DUR register
+
+/** Get motion detection event duration threshold.
+ * This register configures the duration counter threshold for Motion interrupt
+ * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit
+ * of 1LSB = 1ms. The Motion detection duration counter increments when the
+ * absolute value of any of the accelerometer measurements exceeds the Motion
+ * detection threshold (Register 31). The Motion detection interrupt is
+ * triggered when the Motion detection counter reaches the time count specified
+ * in this register.
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current motion detection duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_MOT_DUR
+ */
+uint8_t mpu6050GetMotionDetectionDuration()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_MOT_DUR, buffer);
+  return buffer[0];
+}
+/** Set motion detection event duration threshold.
+ * @param duration New motion detection duration threshold value (LSB = 1ms)
+ * @see getMotionDetectionDuration()
+ * @see MPU6050_RA_MOT_DUR
+ */
+void mpu6050SetMotionDetectionDuration(uint8_t duration)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_MOT_DUR, duration);
+}
+
+// ZRMOT_THR register
+
+/** Get zero motion detection event acceleration threshold.
+ * This register configures the detection threshold for Zero Motion interrupt
+ * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when
+ * the absolute value of the accelerometer measurements for the 3 axes are each
+ * less than the detection threshold. This condition increments the Zero Motion
+ * duration counter (Register 34). The Zero Motion interrupt is triggered when
+ * the Zero Motion duration counter reaches the time count specified in
+ * ZRMOT_DUR (Register 34).
+ *
+ * Unlike Free Fall or Motion detection, Zero Motion detection triggers an
+ * interrupt both when Zero Motion is first detected and when Zero Motion is no
+ * longer detected.
+ *
+ * When a zero motion event is detected, a Zero Motion Status will be indicated
+ * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion
+ * condition is detected, the status bit is set to 1. When a zero-motion-to-
+ * motion condition is detected, the status bit is set to 0.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+uint8_t mpu6050GetZeroMotionDetectionThreshold()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_ZRMOT_THR, buffer);
+  return buffer[0];
+}
+/** Set zero motion detection event acceleration threshold.
+ * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see getZeroMotionDetectionThreshold()
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+void mpu6050SetZeroMotionDetectionThreshold(uint8_t threshold)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_ZRMOT_THR, threshold);
+}
+
+// ZRMOT_DUR register
+
+/** Get zero motion detection event duration threshold.
+ * This register configures the duration counter threshold for Zero Motion
+ * interrupt generation. The duration counter ticks at 16 Hz, therefore
+ * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter
+ * increments while the absolute value of the accelerometer measurements are
+ * each less than the detection threshold (Register 33). The Zero Motion
+ * interrupt is triggered when the Zero Motion duration counter reaches the time
+ * count specified in this register.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection duration threshold value (LSB = 64ms)
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+uint8_t mpu6050GetZeroMotionDetectionDuration()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_ZRMOT_DUR, buffer);
+  return buffer[0];
+}
+/** Set zero motion detection event duration threshold.
+ * @param duration New zero motion detection duration threshold value (LSB = 1ms)
+ * @see getZeroMotionDetectionDuration()
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+void mpu6050SetZeroMotionDetectionDuration(uint8_t duration)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_ZRMOT_DUR, duration);
+}
+
+// FIFO_EN register
+
+/** Get temperature FIFO enabled value.
+ * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and
+ * 66) to be written into the FIFO buffer.
+ * @return Current temperature FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetTempFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set temperature FIFO enabled value.
+ * @param enabled New temperature FIFO enabled value
+ * @see getTempFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetTempFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope X-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and
+ * 68) to be written into the FIFO buffer.
+ * @return Current gyroscope X-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetXGyroFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set gyroscope X-axis FIFO enabled value.
+ * @param enabled New gyroscope X-axis FIFO enabled value
+ * @see getXGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetXGyroFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Y-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and
+ * 70) to be written into the FIFO buffer.
+ * @return Current gyroscope Y-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetYGyroFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set gyroscope Y-axis FIFO enabled value.
+ * @param enabled New gyroscope Y-axis FIFO enabled value
+ * @see getYGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetYGyroFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Z-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and
+ * 72) to be written into the FIFO buffer.
+ * @return Current gyroscope Z-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetZGyroFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set gyroscope Z-axis FIFO enabled value.
+ * @param enabled New gyroscope Z-axis FIFO enabled value
+ * @see getZGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetZGyroFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled);
+}
+/** Get accelerometer FIFO enabled value.
+ * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H,
+ * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be
+ * written into the FIFO buffer.
+ * @return Current accelerometer FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetAccelFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set accelerometer FIFO enabled value.
+ * @param enabled New accelerometer FIFO enabled value
+ * @see getAccelFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetAccelFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 2 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 2 to be written into the FIFO buffer.
+ * @return Current Slave 2 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetSlave2FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 2 FIFO enabled value.
+ * @param enabled New Slave 2 FIFO enabled value
+ * @see getSlave2FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetSlave2FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 1 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 1 to be written into the FIFO buffer.
+ * @return Current Slave 1 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetSlave1FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 1 FIFO enabled value.
+ * @param enabled New Slave 1 FIFO enabled value
+ * @see getSlave1FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetSlave1FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 0 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 0 to be written into the FIFO buffer.
+ * @return Current Slave 0 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool mpu6050GetSlave0FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 0 FIFO enabled value.
+ * @param enabled New Slave 0 FIFO enabled value
+ * @see getSlave0FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void mpu6050SetSlave0FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled);
+}
+
+// I2C_MST_CTRL register
+
+/** Get multi-master enabled value.
+ * Multi-master capability allows multiple I2C masters to operate on the same
+ * bus. In circuits where multi-master capability is required, set MULT_MST_EN
+ * to 1. This will increase current drawn by approximately 30uA.
+ *
+ * In circuits where multi-master capability is required, the state of the I2C
+ * bus must always be monitored by each separate I2C Master. Before an I2C
+ * Master can assume arbitration of the bus, it must first confirm that no other
+ * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the
+ * MPU-60X0's bus arbitration detection logic is turned on, enabling it to
+ * detect when the bus is available.
+ *
+ * @return Current multi-master enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool mpu6050GetMultiMasterEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set multi-master enabled value.
+ * @param enabled New multi-master enabled value
+ * @see getMultiMasterEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void mpu6050SetMultiMasterEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled);
+}
+/** Get wait-for-external-sensor-data enabled value.
+ * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be
+ * delayed until External Sensor data from the Slave Devices are loaded into the
+ * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor
+ * data (i.e. from gyro and accel) and external sensor data have been loaded to
+ * their respective data registers (i.e. the data is synced) when the Data Ready
+ * interrupt is triggered.
+ *
+ * @return Current wait-for-external-sensor-data enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool mpu6050GetWaitForExternalSensorEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer);
+  return buffer[0];
+}
+/** Set wait-for-external-sensor-data enabled value.
+ * @param enabled New wait-for-external-sensor-data enabled value
+ * @see getWaitForExternalSensorEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void mpu6050SetWaitForExternalSensorEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled);
+}
+/** Get Slave 3 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 3 to be written into the FIFO buffer.
+ * @return Current Slave 3 FIFO enabled value
+ * @see MPU6050_RA_MST_CTRL
+ */
+bool mpu6050GetSlave3FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 3 FIFO enabled value.
+ * @param enabled New Slave 3 FIFO enabled value
+ * @see getSlave3FIFOEnabled()
+ * @see MPU6050_RA_MST_CTRL
+ */
+void mpu6050SetSlave3FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled);
+}
+/** Get slave read/write transition enabled value.
+ * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave
+ * read to the next slave read. If the bit equals 0, there will be a restart
+ * between reads. If the bit equals 1, there will be a stop followed by a start
+ * of the following read. When a write transaction follows a read transaction,
+ * the stop followed by a start of the successive write will be always used.
+ *
+ * @return Current slave read/write transition enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool mpu6050GetSlaveReadWriteTransitionEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer);
+  return buffer[0];
+}
+/** Set slave read/write transition enabled value.
+ * @param enabled New slave read/write transition enabled value
+ * @see getSlaveReadWriteTransitionEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void mpu6050SetSlaveReadWriteTransitionEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled);
+}
+/** Get I2C master clock speed.
+ * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the
+ * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to
+ * the following table:
+ *
+ * <pre>
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0           | 348kHz                 | 23
+ * 1           | 333kHz                 | 24
+ * 2           | 320kHz                 | 25
+ * 3           | 308kHz                 | 26
+ * 4           | 296kHz                 | 27
+ * 5           | 286kHz                 | 28
+ * 6           | 276kHz                 | 29
+ * 7           | 267kHz                 | 30
+ * 8           | 258kHz                 | 31
+ * 9           | 500kHz                 | 16
+ * 10          | 471kHz                 | 17
+ * 11          | 444kHz                 | 18
+ * 12          | 421kHz                 | 19
+ * 13          | 400kHz                 | 20
+ * 14          | 381kHz                 | 21
+ * 15          | 364kHz                 | 22
+ * </pre>
+ *
+ * @return Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+uint8_t mpu6050GetMasterClockSpeed()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT,
+      MPU6050_I2C_MST_CLK_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set I2C master clock speed.
+ * @reparam speed Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void mpu6050SetMasterClockSpeed(uint8_t speed)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT,
+      MPU6050_I2C_MST_CLK_LENGTH, speed);
+}
+
+// I2C_SLV* registers (Slave 0-3)
+
+/** Get the I2C address of the specified slave (0-3).
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * In read mode, the result of the read is placed in the lowest available 
+ * EXT_SENS_DATA register. For further information regarding the allocation of
+ * read results, please refer to the EXT_SENS_DATA register description
+ * (Registers 73 - 96).
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions (getSlave4* and setSlave4*).
+ *
+ * I2C data transactions are performed at the Sample Rate, as defined in
+ * Register 25. The user is responsible for ensuring that I2C data transactions
+ * to and from each enabled Slave can be completed within a single period of the
+ * Sample Rate.
+ *
+ * The I2C slave access rate can be reduced relative to the Sample Rate. This
+ * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a
+ * slave's access rate is reduced relative to the Sample Rate is determined by
+ * I2C_MST_DELAY_CTRL (Register 103).
+ *
+ * The processing order for the slaves is fixed. The sequence followed for
+ * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a
+ * particular Slave is disabled it will be skipped.
+ *
+ * Each slave can either be accessed at the sample rate or at a reduced sample
+ * rate. In a case where some slaves are accessed at the Sample Rate and some
+ * slaves are accessed at the reduced rate, the sequence of accessing the slaves
+ * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will
+ * be skipped if their access rate dictates that they should not be accessed
+ * during that particular cycle. For further information regarding the reduced
+ * access rate, please refer to Register 52. Whether a slave is accessed at the
+ * Sample Rate or at the reduced rate is determined by the Delay Enable bits in
+ * Register 103.
+ *
+ * @param num Slave number (0-3)
+ * @return Current address for specified slave
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+uint8_t mpu6050GetSlaveAddress(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_ADDR + num * 3, buffer);
+  return buffer[0];
+}
+/** Set the I2C address of the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param address New address for specified slave
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+void mpu6050SetSlaveAddress(uint8_t num, uint8_t address)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_ADDR + num * 3, address);
+}
+/** Get the active internal register for the specified slave (0-3).
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions.
+ *
+ * @param num Slave number (0-3)
+ * @return Current active register for specified slave
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+uint8_t mpu6050GetSlaveRegister(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_REG + num * 3, buffer);
+  return buffer[0];
+}
+/** Set the active internal register for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param reg New active register for specified slave
+ * @see getSlaveRegister()
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+void mpu6050SetSlaveRegister(uint8_t num, uint8_t reg)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_REG + num * 3, reg);
+}
+/** Get the enabled value for the specified slave (0-3).
+ * When set to 1, this bit enables Slave 0 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 0 from data transfer operations.
+ * @param num Slave number (0-3)
+ * @return Current enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool mpu6050GetSlaveEnabled(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set the enabled value for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New enabled value for specified slave
+ * @see getSlaveEnabled()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void mpu6050SetSlaveEnabled(uint8_t num, bool enabled)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_EN_BIT,
+      enabled);
+}
+/** Get word pair byte-swapping enabled for the specified slave (0-3).
+ * When set to 1, this bit enables byte swapping. When byte swapping is enabled,
+ * the high and low bytes of a word pair are swapped. Please refer to
+ * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0,
+ * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA
+ * registers in the order they were transferred.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair byte-swapping enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool mpu6050GetSlaveWordByteSwap(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_BYTE_SW_BIT,
+      buffer);
+  return buffer[0];
+}
+/** Set word pair byte-swapping enabled for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair byte-swapping enabled value for specified slave
+ * @see getSlaveWordByteSwap()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void mpu6050SetSlaveWordByteSwap(uint8_t num, bool enabled)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_BYTE_SW_BIT,
+      enabled);
+}
+/** Get write mode for the specified slave (0-3).
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @param num Slave number (0-3)
+ * @return Current write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool mpu6050GetSlaveWriteMode(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_REG_DIS_BIT,
+      buffer);
+  return buffer[0];
+}
+/** Set write mode for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param mode New write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see getSlaveWriteMode()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void mpu6050SetSlaveWriteMode(uint8_t num, bool mode)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_REG_DIS_BIT,
+      mode);
+}
+/** Get word pair grouping order offset for the specified slave (0-3).
+ * This sets specifies the grouping order of word pairs received from registers.
+ * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even,
+ * then odd register addresses) are paired to form a word. When set to 1, bytes
+ * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even
+ * register addresses) are paired to form a word.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair grouping order offset for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool mpu6050GetSlaveWordGroupOffset(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_GRP_BIT, buffer);
+  return buffer[0];
+}
+/** Set word pair grouping order offset for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair grouping order offset for specified slave
+ * @see getSlaveWordGroupOffset()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void mpu6050SetSlaveWordGroupOffset(uint8_t num, bool enabled)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_GRP_BIT,
+      enabled);
+}
+/** Get number of bytes to read for the specified slave (0-3).
+ * Specifies the number of bytes transferred to and from Slave 0. Clearing this
+ * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN.
+ * @param num Slave number (0-3)
+ * @return Number of bytes to read for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+uint8_t mpu6050GetSlaveDataLength(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_LEN_BIT,
+      MPU6050_I2C_SLV_LEN_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set number of bytes to read for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param length Number of bytes to read for specified slave
+ * @see getSlaveDataLength()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void mpu6050SetSlaveDataLength(uint8_t num, uint8_t length)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, MPU6050_I2C_SLV_LEN_BIT,
+      MPU6050_I2C_SLV_LEN_LENGTH, length);
+}
+
+// I2C_SLV* registers (Slave 4)
+
+/** Get the I2C address of Slave 4.
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * @return Current address for Slave 4
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+uint8_t mpu6050GetSlave4Address()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer);
+  return buffer[0];
+}
+/** Set the I2C address of Slave 4.
+ * @param address New address for Slave 4
+ * @see getSlave4Address()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+void mpu6050SetSlave4Address(uint8_t address)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_ADDR, address);
+}
+/** Get the active internal register for the Slave 4.
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * @return Current active register for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+uint8_t mpu6050GetSlave4Register()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_REG, buffer);
+  return buffer[0];
+}
+/** Set the active internal register for Slave 4.
+ * @param reg New active register for Slave 4
+ * @see getSlave4Register()
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+void mpu6050SetSlave4Register(uint8_t reg)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_REG, reg);
+}
+/** Set new byte to write to Slave 4.
+ * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW
+ * is set 1 (set to read), this register has no effect.
+ * @param data New byte to write to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DO
+ */
+void mpu6050SetSlave4OutputByte(uint8_t data)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_DO, data);
+}
+/** Get the enabled value for the Slave 4.
+ * When set to 1, this bit enables Slave 4 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 4 from data transfer operations.
+ * @return Current enabled value for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool mpu6050GetSlave4Enabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set the enabled value for Slave 4.
+ * @param enabled New enabled value for Slave 4
+ * @see getSlave4Enabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void mpu6050SetSlave4Enabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled);
+}
+/** Get the enabled value for Slave 4 transaction interrupts.
+ * When set to 1, this bit enables the generation of an interrupt signal upon
+ * completion of a Slave 4 transaction. When cleared to 0, this bit disables the
+ * generation of an interrupt signal upon completion of a Slave 4 transaction.
+ * The interrupt status can be observed in Register 54.
+ *
+ * @return Current enabled value for Slave 4 transaction interrupts.
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool mpu6050GetSlave4InterruptEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set the enabled value for Slave 4 transaction interrupts.
+ * @param enabled New enabled value for Slave 4 transaction interrupts.
+ * @see getSlave4InterruptEnabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void mpu6050SetSlave4InterruptEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled);
+}
+/** Get write mode for Slave 4.
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool mpu6050GetSlave4WriteMode()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer);
+  return buffer[0];
+}
+/** Set write mode for the Slave 4.
+ * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see getSlave4WriteMode()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void mpu6050SetSlave4WriteMode(bool mode)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode);
+}
+/** Get Slave 4 master delay value.
+ * This configures the reduced access rate of I2C slaves relative to the Sample
+ * Rate. When a slave's access rate is decreased relative to the Sample Rate,
+ * the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and
+ * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to
+ * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For
+ * further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @return Current Slave 4 master delay value
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+uint8_t mpu6050GetSlave4MasterDelay()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT,
+      MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set Slave 4 master delay value.
+ * @param delay New Slave 4 master delay value
+ * @see getSlave4MasterDelay()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void mpu6050SetSlave4MasterDelay(uint8_t delay)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT,
+      MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay);
+}
+/** Get last available byte read from Slave 4.
+ * This register stores the data read from Slave 4. This field is populated
+ * after a read transaction.
+ * @return Last available byte read from to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DI
+ */
+uint8_t mpu6050GetSlate4InputByte()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV4_DI, buffer);
+  return buffer[0];
+}
+
+// I2C_MST_STATUS register
+
+/** Get FSYNC interrupt status.
+ * This bit reflects the status of the FSYNC interrupt from an external device
+ * into the MPU-60X0. This is used as a way to pass an external interrupt
+ * through the MPU-60X0 to the host application processor. When set to 1, this
+ * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG
+ * (Register 55).
+ * @return FSYNC interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetPassthroughStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 4 transaction done status.
+ * Automatically sets to 1 when a Slave 4 transaction has completed. This
+ * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register
+ * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the
+ * I2C_SLV4_CTRL register (Register 52).
+ * @return Slave 4 transaction done status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetSlave4IsDone()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer);
+  return buffer[0];
+}
+/** Get master arbitration lost status.
+ * This bit automatically sets to 1 when the I2C Master has lost arbitration of
+ * the auxiliary I2C bus (an error condition). This triggers an interrupt if the
+ * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Master arbitration lost status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetLostArbitration()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 4 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 4 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetSlave4Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 3 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 3 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetSlave3Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 2 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 2 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetSlave2Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 1 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 1 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetSlave1Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 0 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 0 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool mpu6050GetSlave0Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer);
+  return buffer[0];
+}
+
+// INT_PIN_CFG register
+
+/** Get interrupt logic level mode.
+ * Will be set 0 for active-high, 1 for active-low.
+ * @return Current interrupt mode (0=active-high, 1=active-low)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+bool mpu6050GetInterruptMode()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt logic level mode.
+ * @param mode New interrupt mode (0=active-high, 1=active-low)
+ * @see getInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+void mpu6050SetInterruptMode(bool mode)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode);
+}
+/** Get interrupt drive mode.
+ * Will be set 0 for push-pull, 1 for open-drain.
+ * @return Current interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+bool mpu6050GetInterruptDrive()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt drive mode.
+ * @param drive New interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see getInterruptDrive()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+void mpu6050SetInterruptDrive(bool drive)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive);
+}
+/** Get interrupt latch mode.
+ * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared.
+ * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+bool mpu6050GetInterruptLatch()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt latch mode.
+ * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see getInterruptLatch()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+void mpu6050SetInterruptLatch(bool latch)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch);
+}
+/** Get interrupt latch clear mode.
+ * Will be set 0 for status-read-only, 1 for any-register-read.
+ * @return Current latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+bool mpu6050GetInterruptLatchClear()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt latch clear mode.
+ * @param clear New latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see getInterruptLatchClear()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+void mpu6050SetInterruptLatchClear(bool clear)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear);
+}
+/** Get FSYNC interrupt logic level mode.
+ * @return Current FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+bool mpu6050GetFSyncInterruptLevel()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer);
+  return buffer[0];
+}
+/** Set FSYNC interrupt logic level mode.
+ * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+void mpu6050SetFSyncInterruptLevel(bool level)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level);
+}
+/** Get FSYNC pin interrupt enabled setting.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled setting
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+bool mpu6050GetFSyncInterruptEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set FSYNC pin interrupt enabled setting.
+ * @param enabled New FSYNC pin interrupt enabled setting
+ * @see getFSyncInterruptEnabled()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+void mpu6050SetFSyncInterruptEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled);
+}
+/** Get I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @return Current I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+bool mpu6050GetI2CBypassEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @param enabled New I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+void mpu6050SetI2CBypassEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled);
+}
+/** Get reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @return Current reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+bool mpu6050GetClockOutputEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @param enabled New reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+void mpu6050SetClockOutputEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled);
+}
+
+// INT_ENABLE register
+
+/** Get full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit will be
+ * set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+uint8_t mpu6050GetIntEnabled()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, buffer);
+  return buffer[0];
+}
+/** Set full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit should be
+ * set 0 for disabled, 1 for enabled.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void mpu6050SetIntEnabled(uint8_t enabled)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, enabled);
+}
+/** Get Free Fall interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+bool mpu6050GetIntFreefallEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer);
+  return buffer[0];
+}
+/** Set Free Fall interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void mpu6050SetIntFreefallEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled);
+}
+/** Get Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+bool mpu6050GetIntMotionEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer);
+  return buffer[0];
+}
+/** Set Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+void mpu6050SetIntMotionEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled);
+}
+/** Get Zero Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+bool mpu6050GetIntZeroMotionEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+  return buffer[0];
+}
+/** Set Zero Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntZeroMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+void mpu6050SetIntZeroMotionEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled);
+}
+/** Get FIFO Buffer Overflow interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+bool mpu6050GetIntFIFOBufferOverflowEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+  return buffer[0];
+}
+/** Set FIFO Buffer Overflow interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFIFOBufferOverflowEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+void mpu6050SetIntFIFOBufferOverflowEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled);
+}
+/** Get I2C Master interrupt enabled status.
+ * This enables any of the I2C Master interrupt sources to generate an
+ * interrupt. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+bool mpu6050GetIntI2CMasterEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+  return buffer[0];
+}
+/** Set I2C Master interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntI2CMasterEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+void mpu6050SetIntI2CMasterEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled);
+}
+/** Get Data Ready interrupt enabled setting.
+ * This event occurs each time a write operation to all of the sensor registers
+ * has been completed. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool mpu6050GetIntDataReadyEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+  return buffer[0];
+}
+/** Set Data Ready interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntDataReadyEnabled()
+ * @see MPU6050_RA_INT_CFG
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+void mpu6050SetIntDataReadyEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled);
+}
+
+// INT_STATUS register
+
+/** Get full set of interrupt status bits.
+ * These bits clear to 0 after the register has been read. Very useful
+ * for getting multiple INT statuses, since each single bit read clears
+ * all of them because it has to read the whole byte.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ */
+uint8_t mpu6050GetIntStatus()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_INT_STATUS, buffer);
+  return buffer[0];
+}
+/** Get Free Fall interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FF_BIT
+ */
+bool mpu6050GetIntFreefallStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer);
+  return buffer[0];
+}
+/** Get Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Motion Detection interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ */
+bool mpu6050GetIntMotionStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer);
+  return buffer[0];
+}
+/** Get Zero Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Zero Motion Detection interrupt has
+ * been generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ */
+bool mpu6050GetIntZeroMotionStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+  return buffer[0];
+}
+/** Get FIFO Buffer Overflow interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ */
+bool mpu6050GetIntFIFOBufferOverflowStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+  return buffer[0];
+}
+/** Get I2C Master interrupt status.
+ * This bit automatically sets to 1 when an I2C Master interrupt has been
+ * generated. For a list of I2C Master interrupts, please refer to Register 54.
+ * The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ */
+bool mpu6050GetIntI2CMasterStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+  return buffer[0];
+}
+/** Get Data Ready interrupt status.
+ * This bit automatically sets to 1 when a Data Ready interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool mpu6050GetIntDataReadyStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+  return buffer[0];
+}
+
+// ACCEL_*OUT_* registers
+
+/** Get raw 9-axis motion sensor readings (accel/gyro/compass).
+ * FUNCTION NOT FULLY IMPLEMENTED YET.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @param mx 16-bit signed integer container for magnetometer X-axis value
+ * @param my 16-bit signed integer container for magnetometer Y-axis value
+ * @param mz 16-bit signed integer container for magnetometer Z-axis value
+ * @see getMotion6()
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void mpu6050GetMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz,
+    int16_t* mx, int16_t* my, int16_t* mz)
+{
+  mpu6050GetMotion6(ax, ay, az, gx, gy, gz);
+  // TODO: magnetometer integration
+}
+/** Get raw 6-axis motion sensor readings (accel/gyro).
+ * Retrieves all currently available motion sensor values.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void mpu6050GetMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer);
+  *ax = (((int16_t) buffer[0]) << 8) | buffer[1];
+  *ay = (((int16_t) buffer[2]) << 8) | buffer[3];
+  *az = (((int16_t) buffer[4]) << 8) | buffer[5];
+  *gx = (((int16_t) buffer[8]) << 8) | buffer[9];
+  *gy = (((int16_t) buffer[10]) << 8) | buffer[11];
+  *gz = (((int16_t) buffer[12]) << 8) | buffer[13];
+}
+/** Get 3-axis accelerometer readings.
+ * These registers store the most recent accelerometer measurements.
+ * Accelerometer measurements are written to these registers at the Sample Rate
+ * as defined in Register 25.
+ *
+ * The accelerometer measurement registers, along with the temperature
+ * measurement registers, gyroscope measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ *
+ * The data within the accelerometer sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS
+ * (Register 28). For each full scale setting, the accelerometers' sensitivity
+ * per LSB in ACCEL_xOUT is shown in the table below:
+ *
+ * <pre>
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0       | +/- 2g           | 8192 LSB/mg
+ * 1       | +/- 4g           | 4096 LSB/mg
+ * 2       | +/- 8g           | 2048 LSB/mg
+ * 3       | +/- 16g          | 1024 LSB/mg
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis acceleration
+ * @param y 16-bit signed integer container for Y-axis acceleration
+ * @param z 16-bit signed integer container for Z-axis acceleration
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void mpu6050GetAcceleration(int16_t* x, int16_t* y, int16_t* z)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer);
+  *x = (((int16_t) buffer[0]) << 8) | buffer[1];
+  *y = (((int16_t) buffer[2]) << 8) | buffer[3];
+  *z = (((int16_t) buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis accelerometer reading.
+ * @return X-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+int16_t mpu6050GetAccelerationX()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis accelerometer reading.
+ * @return Y-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_YOUT_H
+ */
+int16_t mpu6050GetAccelerationY()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis accelerometer reading.
+ * @return Z-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_ZOUT_H
+ */
+int16_t mpu6050GetAccelerationZ()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// TEMP_OUT_* registers
+
+/** Get current internal temperature.
+ * @return Temperature reading in 16-bit 2's complement format
+ * @see MPU6050_RA_TEMP_OUT_H
+ */
+int16_t mpu6050GetTemperature()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// GYRO_*OUT_* registers
+
+/** Get 3-axis gyroscope readings.
+ * These gyroscope measurement registers, along with the accelerometer
+ * measurement registers, temperature measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ * The data within the gyroscope sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL
+ * (Register 27). For each full scale setting, the gyroscopes' sensitivity per
+ * LSB in GYRO_xOUT is shown in the table below:
+ *
+ * <pre>
+ * FS_SEL | Full Scale Range   | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
+ * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
+ * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis rotation
+ * @param y 16-bit signed integer container for Y-axis rotation
+ * @param z 16-bit signed integer container for Z-axis rotation
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void mpu6050GetRotation(int16_t* x, int16_t* y, int16_t* z)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer);
+  *x = (((int16_t) buffer[0]) << 8) | buffer[1];
+  *y = (((int16_t) buffer[2]) << 8) | buffer[3];
+  *z = (((int16_t) buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis gyroscope reading.
+ * @return X-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+int16_t mpu6050GetRotationX()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis gyroscope reading.
+ * @return Y-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_YOUT_H
+ */
+int16_t mpu6050GetRotationY()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis gyroscope reading.
+ * @return Z-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_ZOUT_H
+ */
+int16_t mpu6050GetRotationZ()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// EXT_SENS_DATA_* registers
+
+/** Read single byte from external sensor data register.
+ * These registers store data read from external sensors by the Slave 0, 1, 2,
+ * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in
+ * I2C_SLV4_DI (Register 53).
+ *
+ * External sensor data is written to these registers at the Sample Rate as
+ * defined in Register 25. This access rate can be reduced by using the Slave
+ * Delay Enable registers (Register 103).
+ *
+ * External sensor data registers, along with the gyroscope measurement
+ * registers, accelerometer measurement registers, and temperature measurement
+ * registers, are composed of two sets of registers: an internal register set
+ * and a user-facing read register set.
+ *
+ * The data within the external sensors' internal register set is always updated
+ * at the Sample Rate (or the reduced access rate) whenever the serial interface
+ * is idle. This guarantees that a burst read of sensor registers will read
+ * measurements from the same sampling instant. Note that if burst reads are not
+ * used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Data is placed in these external sensor data registers according to
+ * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39,
+ * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from
+ * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as
+ * defined in Register 25) or delayed rate (if specified in Register 52 and
+ * 103). During each Sample cycle, slave reads are performed in order of Slave
+ * number. If all slaves are enabled with more than zero bytes to be read, the
+ * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3.
+ *
+ * Each enabled slave will have EXT_SENS_DATA registers associated with it by
+ * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from
+ * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may
+ * change the higher numbered slaves' associated registers. Furthermore, if
+ * fewer total bytes are being read from the external sensors as a result of
+ * such a change, then the data remaining in the registers which no longer have
+ * an associated slave device (i.e. high numbered registers) will remain in
+ * these previously allocated registers unless reset.
+ *
+ * If the sum of the read lengths of all SLVx transactions exceed the number of
+ * available EXT_SENS_DATA registers, the excess bytes will be dropped. There
+ * are 24 EXT_SENS_DATA registers and hence the total read lengths between all
+ * the slaves cannot be greater than 24 or some bytes will be lost.
+ *
+ * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further
+ * information regarding the characteristics of Slave 4, please refer to
+ * Registers 49 to 53.
+ *
+ * EXAMPLE:
+ * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and
+ * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that
+ * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00
+ * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05
+ * will be associated with Slave 1. If Slave 2 is enabled as well, registers
+ * starting from EXT_SENS_DATA_06 will be allocated to Slave 2.
+ *
+ * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then
+ * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3
+ * instead.
+ *
+ * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE:
+ * If a slave is disabled at any time, the space initially allocated to the
+ * slave in the EXT_SENS_DATA register, will remain associated with that slave.
+ * This is to avoid dynamic adjustment of the register allocation.
+ *
+ * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all
+ * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106).
+ *
+ * This above is also true if one of the slaves gets NACKed and stops
+ * functioning.
+ *
+ * @param position Starting position (0-23)
+ * @return Byte read from register
+ */
+uint8_t mpu6050GetExternalSensorByte(int position)
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer);
+  return buffer[0];
+}
+/** Read word (2 bytes) from external sensor data registers.
+ * @param position Starting position (0-21)
+ * @return Word read from register
+ * @see getExternalSensorByte()
+ */
+uint16_t mpu6050GetExternalSensorWord(int position)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer);
+  return (((uint16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Read double word (4 bytes) from external sensor data registers.
+ * @param position Starting position (0-20)
+ * @return Double word read from registers
+ * @see getExternalSensorByte()
+ */
+uint32_t mpu6050GetExternalSensorDWord(int position)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer);
+  return (((uint32_t) buffer[0]) << 24) | (((uint32_t) buffer[1]) << 16)
+      | (((uint16_t) buffer[2]) << 8) | buffer[3];
+}
+
+// MOT_DETECT_STATUS register
+
+/** Get X-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XNEG_BIT
+ */
+bool mpu6050GetXNegMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer);
+  return buffer[0];
+}
+/** Get X-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XPOS_BIT
+ */
+bool mpu6050GetXPosMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer);
+  return buffer[0];
+}
+/** Get Y-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YNEG_BIT
+ */
+bool mpu6050GetYNegMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer);
+  return buffer[0];
+}
+/** Get Y-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YPOS_BIT
+ */
+bool mpu6050GetYPosMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer);
+  return buffer[0];
+}
+/** Get Z-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZNEG_BIT
+ */
+bool mpu6050GetZNegMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer);
+  return buffer[0];
+}
+/** Get Z-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZPOS_BIT
+ */
+bool mpu6050GetZPosMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer);
+  return buffer[0];
+}
+/** Get zero motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZRMOT_BIT
+ */
+bool mpu6050GetZeroMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer);
+  return buffer[0];
+}
+
+// I2C_SLV*_DO register
+
+/** Write byte to Data Output container for specified slave.
+ * This register holds the output data written into Slave when Slave is set to
+ * write mode. For further information regarding Slave control, please
+ * refer to Registers 37 to 39 and immediately following.
+ * @param num Slave number (0-3)
+ * @param data Byte to write
+ * @see MPU6050_RA_I2C_SLV0_DO
+ */
+void mpu6050SetSlaveOutputByte(uint8_t num, uint8_t data)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_I2C_SLV0_DO + num, data);
+}
+
+// I2C_MST_DELAY_CTRL register
+
+/** Get external data shadow delay enabled status.
+ * This register is used to specify the timing of external sensor data
+ * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external
+ * sensor data is delayed until all data has been received.
+ * @return Current external data shadow delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+bool mpu6050GetExternalShadowDelayEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT,
+      buffer);
+  return buffer[0];
+}
+/** Set external data shadow delay enabled status.
+ * @param enabled New external data shadow delay enabled status.
+ * @see getExternalShadowDelayEnabled()
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+void mpu6050SetExternalShadowDelayEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL,
+      MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled);
+}
+/** Get slave delay enabled status.
+ * When a particular slave delay is enabled, the rate of access for the that
+ * slave device is reduced. When a slave's access rate is decreased relative to
+ * the Sample Rate, the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) Samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register  * 25)
+ * and DLPF_CFG (register 26).
+ *
+ * For further information regarding I2C_MST_DLY, please refer to register 52.
+ * For further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @param num Slave number (0-4)
+ * @return Current slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+bool mpu6050GetSlaveDelayEnabled(uint8_t num)
+{
+  // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc.
+  if (num > 4)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer);
+  return buffer[0];
+}
+/** Set slave delay enabled status.
+ * @param num Slave number (0-4)
+ * @param enabled New slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+void mpu6050SetSlaveDelayEnabled(uint8_t num, bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled);
+}
+
+// SIGNAL_PATH_RESET register
+
+/** Reset gyroscope signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_GYRO_RESET_BIT
+ */
+void mpu6050ResetGyroscopePath()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, 1);
+}
+/** Reset accelerometer signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_ACCEL_RESET_BIT
+ */
+void mpu6050ResetAccelerometerPath()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, 1);
+}
+/** Reset temperature sensor signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_TEMP_RESET_BIT
+ */
+void mpu6050ResetTemperaturePath()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, 1);
+}
+
+// MOT_DETECT_CTRL register
+
+/** Get accelerometer power-on delay.
+ * The accelerometer data path provides samples to the sensor registers, Motion
+ * detection, Zero Motion detection, and Free Fall detection modules. The
+ * signal path contains filters which must be flushed on wake-up with new
+ * samples before the detection modules begin operations. The default wake-up
+ * delay, of 4ms can be lengthened by up to 3ms. This additional delay is
+ * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select
+ * any value above zero unless instructed otherwise by InvenSense. Please refer
+ * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for
+ * further information regarding the detection modules.
+ * @return Current accelerometer power-on delay
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+uint8_t mpu6050GetAccelerometerPowerOnDelay()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT,
+      MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set accelerometer power-on delay.
+ * @param delay New accelerometer power-on delay (0-3)
+ * @see getAccelerometerPowerOnDelay()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+void mpu6050SetAccelerometerPowerOnDelay(uint8_t delay)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT,
+      MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay);
+}
+/** Get Free Fall detection counter decrement configuration.
+ * Detection is registered by the Free Fall detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring FF_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * </pre>
+ *
+ * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Free Fall detection,
+ * please refer to Registers 29 to 32.
+ *
+ * @return Current decrement configuration
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+uint8_t mpu6050GetFreefallDetectionCounterDecrement()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT,
+      MPU6050_DETECT_FF_COUNT_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set Free Fall detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getFreefallDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+void mpu6050SetFreefallDetectionCounterDecrement(uint8_t decrement)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT,
+      MPU6050_DETECT_FF_COUNT_LENGTH, decrement);
+}
+/** Get Motion detection counter decrement configuration.
+ * Detection is registered by the Motion detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring MOT_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * </pre>
+ *
+ * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Motion detection,
+ * please refer to Registers 29 to 32.
+ *
+ */
+uint8_t mpu6050GetMotionDetectionCounterDecrement()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT,
+      MPU6050_DETECT_MOT_COUNT_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set Motion detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getMotionDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_MOT_COUNT_BIT
+ */
+void mpu6050SetMotionDetectionCounterDecrement(uint8_t decrement)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT,
+      MPU6050_DETECT_MOT_COUNT_LENGTH, decrement);
+}
+
+// USER_CTRL register
+
+/** Get FIFO enabled status.
+ * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer
+ * cannot be written to or read from while disabled. The FIFO buffer's state
+ * does not change unless the MPU-60X0 is power cycled.
+ * @return Current FIFO enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+bool mpu6050GetFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set FIFO enabled status.
+ * @param enabled New FIFO enabled status
+ * @see getFIFOEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+void mpu6050SetFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled);
+}
+/** Get I2C Master Mode enabled status.
+ * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the
+ * external sensor slave devices on the auxiliary I2C bus. When this bit is
+ * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically
+ * driven by the primary I2C bus (SDA and SCL). This is a precondition to
+ * enabling Bypass Mode. For further information regarding Bypass Mode, please
+ * refer to Register 55.
+ * @return Current I2C Master Mode enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+bool mpu6050GetI2CMasterModeEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set I2C Master Mode enabled status.
+ * @param enabled New I2C Master Mode enabled status
+ * @see getI2CMasterModeEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+void mpu6050SetI2CMasterModeEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled);
+}
+/** Switch from I2C to SPI mode (MPU-6000 only)
+ * If this is set, the primary SPI interface will be enabled in place of the
+ * disabled primary I2C interface.
+ */
+void mpu6050SwitchSPIEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled);
+}
+/** Reset the FIFO.
+ * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This
+ * bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_RESET_BIT
+ */
+void mpu6050ResetFIFO()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, 1);
+}
+/** Reset the I2C Master.
+ * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0.
+ * This bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT
+ */
+void mpu6050ResetI2CMaster()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, 1);
+}
+/** Reset all sensor registers and signal paths.
+ * When set to 1, this bit resets the signal paths for all sensors (gyroscopes,
+ * accelerometers, and temperature sensor). This operation will also clear the
+ * sensor registers. This bit automatically clears to 0 after the reset has been
+ * triggered.
+ *
+ * When resetting only the signal path (and not the sensor registers), please
+ * use Register 104, SIGNAL_PATH_RESET.
+ *
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT
+ */
+void mpu6050ResetSensors()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, 1);
+}
+
+// PWR_MGMT_1 register
+
+/** Trigger a full device reset.
+ * A small delay of ~50ms may be desirable after triggering a reset.
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_DEVICE_RESET_BIT
+ */
+void mpu6050Reset()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, 1);
+}
+/** Get sleep mode status.
+ * Setting the SLEEP bit in the register puts the device into very low power
+ * sleep mode. In this mode, only the serial interface and internal registers
+ * remain active, allowing for a very low standby current. Clearing this bit
+ * puts the device back into normal mode. To save power, the individual standby
+ * selections for each of the gyros should be used if any gyro axis is not used
+ * by the application.
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+bool mpu6050GetSleepEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer);
+  return buffer[0];
+}
+/** Set sleep mode status.
+ * @param enabled New sleep mode enabled status
+ * @see getSleepEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+void mpu6050SetSleepEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled);
+}
+/** Get wake cycle enabled status.
+ * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle
+ * between sleep mode and waking up to take a single sample of data from active
+ * sensors at a rate determined by LP_WAKE_CTRL (register 108).
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+bool mpu6050GetWakeCycleEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer);
+  return buffer[0];
+}
+/** Set wake cycle enabled status.
+ * @param enabled New sleep mode enabled status
+ * @see getWakeCycleEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+void mpu6050SetWakeCycleEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled);
+}
+/** Get temperature sensor enabled status.
+ * Control the usage of the internal temperature sensor.
+ *
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @return Current temperature sensor enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+bool mpu6050GetTempSensorEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer);
+  return buffer[0] == 0; // 1 is actually disabled here
+}
+/** Set temperature sensor enabled status.
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @param enabled New temperature sensor enabled status
+ * @see getTempSensorEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+void mpu6050SetTempSensorEnabled(bool enabled)
+{
+  // 1 is actually disabled here
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled);
+}
+/** Get clock source setting.
+ * @return Current clock source setting
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+uint8_t mpu6050GetClockSource()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT,
+      MPU6050_PWR1_CLKSEL_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set clock source setting.
+ * An internal 8MHz oscillator, gyroscope based clock, or external sources can
+ * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator
+ * or an external source is chosen as the clock source, the MPU-60X0 can operate
+ * in low power modes with the gyroscopes disabled.
+ *
+ * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator.
+ * However, it is highly recommended that the device be configured to use one of
+ * the gyroscopes (or an external clock source) as the clock reference for
+ * improved stability. The clock source can be selected according to the following table:
+ *
+ * <pre>
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0       | Internal oscillator
+ * 1       | PLL with X Gyro reference
+ * 2       | PLL with Y Gyro reference
+ * 3       | PLL with Z Gyro reference
+ * 4       | PLL with external 32.768kHz reference
+ * 5       | PLL with external 19.2MHz reference
+ * 6       | Reserved
+ * 7       | Stops the clock and keeps the timing generator in reset
+ * </pre>
+ *
+ * @param source New clock source setting
+ * @see getClockSource()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+void mpu6050SetClockSource(uint8_t source)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT,
+      MPU6050_PWR1_CLKSEL_LENGTH, source);
+}
+
+// PWR_MGMT_2 register
+
+/** Get wake frequency in Accel-Only Low Power Mode.
+ * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting
+ * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode,
+ * the device will power off all devices except for the primary I2C interface,
+ * waking only the accelerometer at fixed intervals to take a single
+ * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL
+ * as shown below:
+ *
+ * <pre>
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * <pre>
+ *
+ * For further information regarding the MPU-60X0's power modes, please refer to
+ * Register 107.
+ *
+ * @return Current wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+uint8_t mpu6050GetWakeFrequency()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT,
+      MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+void mpu6050SetWakeFrequency(uint8_t frequency)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT,
+      MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
+}
+
+/** Get X-axis accelerometer standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+bool mpu6050GetStandbyXAccelEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer);
+  return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+void mpu6050SetStandbyXAccelEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled);
+}
+/** Get Y-axis accelerometer standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+bool mpu6050GetStandbyYAccelEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer);
+  return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+void mpu6050SetStandbyYAccelEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled);
+}
+/** Get Z-axis accelerometer standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+bool mpu6050GetStandbyZAccelEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer);
+  return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+void mpu6050SetStandbyZAccelEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled);
+}
+/** Get X-axis gyroscope standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+bool mpu6050GetStandbyXGyroEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer);
+  return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+void mpu6050SetStandbyXGyroEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled);
+}
+/** Get Y-axis gyroscope standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+bool mpu6050GetStandbyYGyroEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer);
+  return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+void mpu6050SetStandbyYGyroEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled);
+}
+/** Get Z-axis gyroscope standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+bool mpu6050GetStandbyZGyroEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer);
+  return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+void mpu6050SetStandbyZGyroEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t mpu6050GetFIFOCount()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer);
+  return (((uint16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t mpu6050GetFIFOByte()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_FIFO_R_W, buffer);
+  return buffer[0];
+}
+void mpu6050GetFIFOBytes(uint8_t *data, uint8_t length)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU6050_RA_FIFO_R_W
+ */
+void mpu6050SetFIFOByte(uint8_t data)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_FIFO_R_W, data);
+}
+
+// WHO_AM_I register
+
+/** Get Device ID.
+ * This register is used to verify the identity of the device (0b110100).
+ * @return Device ID (should be 0x68, 104 dec, 150 oct)
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+uint8_t mpu6050GetDeviceID()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH,
+      buffer);
+  return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+void mpu6050SetDeviceID(uint8_t id)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH,
+      id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t mpu6050GetOTPBankValid()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer);
+  return buffer[0];
+}
+void mpu6050SetOTPBankValid(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t mpu6050GetXGyroOffset()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+      MPU6050_TC_OFFSET_LENGTH, buffer);
+  return buffer[0];
+}
+void mpu6050SetXGyroOffset(int8_t offset)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+      MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t mpu6050GetYGyroOffset()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+      MPU6050_TC_OFFSET_LENGTH, buffer);
+  return buffer[0];
+}
+void mpu6050SetYGyroOffset(int8_t offset)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+      MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t mpu6050GetZGyroOffset()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+      MPU6050_TC_OFFSET_LENGTH, buffer);
+  return buffer[0];
+}
+void mpu6050SetZGyroOffset(int8_t offset)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+      MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t mpu6050GetXFineGain()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_X_FINE_GAIN, buffer);
+  return buffer[0];
+}
+void mpu6050SetXFineGain(int8_t gain)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t mpu6050GetYFineGain()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_Y_FINE_GAIN, buffer);
+  return buffer[0];
+}
+void mpu6050SetYFineGain(int8_t gain)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t mpu6050GetZFineGain()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_Z_FINE_GAIN, buffer);
+  return buffer[0];
+}
+void mpu6050SetZFineGain(int8_t gain)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t mpu6050GetXAccelOffset()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_XA_OFFS_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+void mpu6050SetXAccelOffset(int16_t offset)
+{
+  i2cdevWrite(I2Cx, devAddr, MPU6050_RA_XA_OFFS_H, 2, (uint8_t *)&offset);
+}
+
+// YA_OFFS_* register
+
+int16_t mpu6050GetYAccelOffset()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_YA_OFFS_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+void mpu6050SetYAccelOffset(int16_t offset)
+{
+  i2cdevWrite(I2Cx, devAddr, MPU6050_RA_YA_OFFS_H, 2, (uint8_t *)&offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t mpu6050GetZAccelOffset()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_ZA_OFFS_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+void mpu6050SetZAccelOffset(int16_t offset)
+{
+  i2cdevWrite(I2Cx, devAddr, MPU6050_RA_ZA_OFFS_H, 2, (uint8_t *)&offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t mpu6050GetXGyroOffsetUser()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+void mpu6050SetXGyroOffsetUser(int16_t offset)
+{
+  i2cdevWrite(I2Cx, devAddr, MPU6050_RA_XG_OFFS_USRH, 2, (uint8_t *)&offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t mpu6050GetYGyroOffsetUser()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+void mpu6050SetYGyroOffsetUser(int16_t offset)
+{
+  i2cdevWrite(I2Cx, devAddr, MPU6050_RA_YG_OFFS_USRH, 2, (uint8_t *)&offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t mpu6050GetZGyroOffsetUser()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+void mpu6050SetZGyroOffsetUser(int16_t offset)
+{
+  i2cdevWrite(I2Cx, devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, (uint8_t *)&offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool mpu6050GetIntPLLReadyEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+  return buffer[0];
+}
+void mpu6050SetIntPLLReadyEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool mpu6050GetIntDMPEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+  return buffer[0];
+}
+void mpu6050SetIntDMPEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool mpu6050GetDMPInt5Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6050GetDMPInt4Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6050GetDMPInt3Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6050GetDMPInt2Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6050GetDMPInt1Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6050GetDMPInt0Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer);
+  return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool mpu6050GetIntPLLReadyStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6050GetIntDMPStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+  return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool mpu6050GetDMPEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer);
+  return buffer[0];
+}
+void mpu6050SetDMPEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled);
+}
+void mpu6050ResetDMP()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, 1);
+}
+
+// BANK_SEL register
+
+void mpu6050SetMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank)
+{
+  bank &= 0x1F;
+  if (userBank)
+    bank |= 0x20;
+  if (prefetchEnabled)
+    bank |= 0x40;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void mpu6050SetMemoryStartAddress(uint8_t address)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t mpu6050ReadMemoryByte()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_MEM_R_W, buffer);
+  return buffer[0];
+}
+void mpu6050WriteMemoryByte(uint8_t data)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_MEM_R_W, data);
+}
+void mpu6050ReadMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address)
+{
+  mpu6050SetMemoryBank(bank, true, true);
+  mpu6050SetMemoryStartAddress(address);
+  uint8_t chunkSize;
+  uint16_t i;
+
+  for (i = 0; i < dataSize;)
+  {
+    // determine correct chunk size according to bank position and data size
+    chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+    // make sure we don't go past the data size
+    if (i + chunkSize > dataSize)
+      chunkSize = dataSize - i;
+
+    // make sure this chunk doesn't go past the bank boundary (256 bytes)
+    if (chunkSize > 256 - address)
+      chunkSize = 256 - address;
+
+    // read the chunk of data as specified
+    i2cdevRead(I2Cx, devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i);
+
+    // increase byte index by [chunkSize]
+    i += chunkSize;
+
+    // uint8_t automatically wraps to 0 at 256
+    address += chunkSize;
+
+    // if we aren't done, update bank (if necessary) and address
+    if (i < dataSize)
+    {
+      if (address == 0)
+        bank++;
+      mpu6050SetMemoryBank(bank, true, true);
+      mpu6050SetMemoryStartAddress(address);
+    }
+  }
+}
+bool mpu6050WriteMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address,
+    bool verify)
+{
+  static uint8_t verifyBuffer[MPU6050_DMP_MEMORY_CHUNK_SIZE];
+  uint8_t chunkSize;
+  uint8_t *progBuffer;
+  uint16_t i;
+
+  mpu6050SetMemoryBank(bank, true, true);
+  mpu6050SetMemoryStartAddress(address);
+
+  for (i = 0; i < dataSize;)
+  {
+    // determine correct chunk size according to bank position and data size
+    chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+    // make sure we don't go past the data size
+    if (i + chunkSize > dataSize)
+      chunkSize = dataSize - i;
+
+    // make sure this chunk doesn't go past the bank boundary (256 bytes)
+    if (chunkSize > 256 - address)
+      chunkSize = 256 - address;
+
+    // write the chunk of data as specified
+    progBuffer = (uint8_t *) data + i;
+
+    i2cdevWrite(I2Cx, devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
+
+    // verify data if needed
+    if (verify)
+    {
+      uint32_t j;
+      mpu6050SetMemoryBank(bank, true, true);
+      mpu6050SetMemoryStartAddress(address);
+      i2cdevRead(I2Cx, devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer);
+
+      for (j = 0; j < chunkSize; j++)
+      {
+        if (progBuffer[j] != verifyBuffer[j])
+        {
+          /*Serial.print("Block write verification error, bank ");
+           Serial.print(bank, DEC);
+           Serial.print(", address ");
+           Serial.print(address, DEC);
+           Serial.print("!\nExpected:");
+           for (j = 0; j < chunkSize; j++) {
+           Serial.print(" 0x");
+           if (progBuffer[j] < 16) Serial.print("0");
+           Serial.print(progBuffer[j], HEX);
+           }
+           Serial.print("\nReceived:");
+           for (uint8_t j = 0; j < chunkSize; j++) {
+           Serial.print(" 0x");
+           if (verifyBuffer[i + j] < 16) Serial.print("0");
+           Serial.print(verifyBuffer[i + j], HEX);
+           }
+           Serial.print("\n");*/
+          return false;
+        }
+      }
+    }
+
+    // increase byte index by [chunkSize]
+    i += chunkSize;
+
+    // uint8_t automatically wraps to 0 at 256
+    address += chunkSize;
+
+    // if we aren't done, update bank (if necessary) and address
+    if (i < dataSize)
+    {
+      if (address == 0)
+        bank++;
+      mpu6050SetMemoryBank(bank, true, true);
+      mpu6050SetMemoryStartAddress(address);
+    }
+  }
+  return true;
+}
+bool mpu6050WriteProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank,
+    uint8_t address, bool verify)
+{
+  return mpu6050WriteMemoryBlock(data, dataSize, bank, address, verify);
+}
+#define MPU6050_DMP_CONFIG_BLOCK_SIZE 6
+bool mpu6050WriteDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
+{
+  uint8_t *progBuffer, success, special;
+  uint16_t i;
+
+  // config set data is a long string of blocks with the following structure:
+  // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+  uint8_t bank=0;
+  uint8_t offset=0;
+  uint8_t length=0;
+  for (i = 0; i < dataSize;)
+  {
+    bank = data[i++];
+    offset = data[i++];
+    length = data[i++];
+  }
+
+  // write data or perform special action
+  if (length > 0)
+  {
+    // regular block of data to write
+    /*Serial.print("Writing config block to bank ");
+     Serial.print(bank);
+     Serial.print(", offset ");
+     Serial.print(offset);
+     Serial.print(", length=");
+     Serial.println(length);*/
+    progBuffer = (uint8_t *) data + i;
+    success = mpu6050WriteMemoryBlock(progBuffer, length, bank, offset, true);
+    i += length;
+  }
+  else
+  {
+    // special instruction
+    // NOTE: this kind of behavior (what and when to do certain things)
+    // is totally undocumented. This code is in here based on observed
+    // behavior only, and exactly why (or even whether) it has to be here
+    // is anybody's guess for now.
+    special = data[i++];
+    /*Serial.print("Special command code ");
+     Serial.print(special, HEX);
+     Serial.println(" found...");*/
+    if (special == 0x01)
+    {
+      // enable DMP-related interrupts
+      mpu6050SetIntZeroMotionEnabled(true);
+      mpu6050SetIntFIFOBufferOverflowEnabled(true);
+      mpu6050SetIntDMPEnabled(true);
+      //i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_INT_ENABLE, 0x32);
+      success = true;
+    }
+    else
+    {
+      // unknown special command
+      success = false;
+    }
+  }
+
+  if (!success)
+  {
+    return false; // uh oh
+  }
+  return true;
+}
+
+bool mpu6050WriteProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
+{
+  return mpu6050WriteDMPConfigurationSet(data, dataSize);
+}
+
+// DMP_CFG_1 register
+
+uint8_t mpu6050GetDMPConfig1()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_DMP_CFG_1, buffer);
+  return buffer[0];
+}
+void mpu6050SetDMPConfig1(uint8_t config)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t mpu6050GetDMPConfig2()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6050_RA_DMP_CFG_2, buffer);
+  return buffer[0];
+}
+void mpu6050SetDMPConfig2(uint8_t config)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6050_RA_DMP_CFG_2, config);
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/mpu6500.c b/crazyflie-firmware-src/src/drivers/src/mpu6500.c
new file mode 100644
index 0000000000000000000000000000000000000000..95105660c93404a92beec9f7d5e6331f6d13b0da
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/mpu6500.c
@@ -0,0 +1,3367 @@
+// I2Cdev library collection - MPU6500 I2C device class
+// Based on InvenSense MPU-6500 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 8/24/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+
+/* ============================================
+ I2Cdev device library code is placed under the MIT license
+ Copyright (c) 2011 Jeff Rowberg
+ Adapted to Crazyflie FW by Bitcraze
+
+ Permission is hereby granted, free of charge, to any person obtaining a copy
+ of this software and associated documentation files (the "Software"), to deal
+ in the Software without restriction, including without limitation the rights
+ to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ copies of the Software, and to permit persons to whom the Software is
+ furnished to do so, subject to the following conditions:
+
+ The above copyright notice and this permission notice shall be included in
+ all copies or substantial portions of the Software.
+
+ THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ THE SOFTWARE.
+ ===============================================
+ */
+#define DEBUG_MODULE "MPU6500"
+
+#include <math.h>
+#include "stm32fxxx.h"
+#include "FreeRTOS.h"
+#include "task.h"
+
+// TA: Maybe not so good to bring in these dependencies...
+#include "debug.h"
+#include "eprintf.h"
+#include "i2cdev.h"
+
+#include "mpu6500.h"
+
+static uint8_t devAddr;
+static I2C_Dev *I2Cx;
+static uint8_t buffer[14];
+static bool isInit;
+
+static const unsigned short mpu6500StTb[256] = {
+  2620,2646,2672,2699,2726,2753,2781,2808, //7
+  2837,2865,2894,2923,2952,2981,3011,3041, //15
+  3072,3102,3133,3165,3196,3228,3261,3293, //23
+  3326,3359,3393,3427,3461,3496,3531,3566, //31
+  3602,3638,3674,3711,3748,3786,3823,3862, //39
+  3900,3939,3979,4019,4059,4099,4140,4182, //47
+  4224,4266,4308,4352,4395,4439,4483,4528, //55
+  4574,4619,4665,4712,4759,4807,4855,4903, //63
+  4953,5002,5052,5103,5154,5205,5257,5310, //71
+  5363,5417,5471,5525,5581,5636,5693,5750, //79
+  5807,5865,5924,5983,6043,6104,6165,6226, //87
+  6289,6351,6415,6479,6544,6609,6675,6742, //95
+  6810,6878,6946,7016,7086,7157,7229,7301, //103
+  7374,7448,7522,7597,7673,7750,7828,7906, //111
+  7985,8065,8145,8227,8309,8392,8476,8561, //119
+  8647,8733,8820,8909,8998,9088,9178,9270,
+  9363,9457,9551,9647,9743,9841,9939,10038,
+  10139,10240,10343,10446,10550,10656,10763,10870,
+  10979,11089,11200,11312,11425,11539,11654,11771,
+  11889,12008,12128,12249,12371,12495,12620,12746,
+  12874,13002,13132,13264,13396,13530,13666,13802,
+  13940,14080,14221,14363,14506,14652,14798,14946,
+  15096,15247,15399,15553,15709,15866,16024,16184,
+  16346,16510,16675,16842,17010,17180,17352,17526,
+  17701,17878,18057,18237,18420,18604,18790,18978,
+  19167,19359,19553,19748,19946,20145,20347,20550,
+  20756,20963,21173,21385,21598,21814,22033,22253,
+  22475,22700,22927,23156,23388,23622,23858,24097,
+  24338,24581,24827,25075,25326,25579,25835,26093,
+  26354,26618,26884,27153,27424,27699,27976,28255,
+  28538,28823,29112,29403,29697,29994,30294,30597,
+  30903,31212,31524,31839,32157,32479,32804,33132
+};
+
+/** Default constructor, uses default I2C address.
+ * @see MPU6500_DEFAULT_ADDRESS
+ */
+void mpu6500Init(I2C_Dev *i2cPort)
+{
+  if (isInit)
+    return;
+
+  I2Cx = i2cPort;
+  devAddr = MPU6500_ADDRESS_AD0_HIGH;
+
+  isInit = true;
+}
+
+bool mpu6500Test(void)
+{
+  bool testStatus;
+
+  if (!isInit)
+    return false;
+
+  testStatus = mpu6500TestConnection();
+
+  return testStatus;
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool mpu6500TestConnection()
+{
+  return mpu6500GetDeviceID() == 0x38; //0x38 is MPU9250 ID with AD0 = 0;
+}
+
+/** Do a MPU6500 self test.
+ * @return True if self test passed, false otherwise
+ */
+bool mpu6500SelfTest()
+{
+  uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
+  uint8_t saveReg[5];
+  uint8_t selfTest[6];
+  int32_t gAvg[3]={0}, aAvg[3]={0}, aSTAvg[3]={0}, gSTAvg[3]={0};
+  int32_t factoryTrim[6];
+  float aDiff[3], gDiff[3];
+  uint8_t FS = 0;
+  int i;
+
+  // Save old configuration
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_SMPLRT_DIV, &saveReg[0]);
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_CONFIG, &saveReg[1]);
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, &saveReg[2]);
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG_2, &saveReg[3]);
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, &saveReg[4]);
+  // Write test configuration
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG_2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
+
+  for(i = 0; i < 200; i++)
+  {
+    // get average current values of gyro and acclerometer
+    i2cdevRead(I2Cx, devAddr, MPU6500_RA_ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
+    aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+    aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+    aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+
+    i2cdevRead(I2Cx, devAddr, MPU6500_RA_GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
+    gAvg[0] += (int16_t)((int16_t)rawData[0] << 8) | rawData[1]; // Turn the MSB and LSB into a signed 16-bit value
+    gAvg[1] += (int16_t)((int16_t)rawData[2] << 8) | rawData[3];
+    gAvg[2] += (int16_t)((int16_t)rawData[4] << 8) | rawData[5];
+  }
+
+  for (i = 0; i < 3; i++)
+  { // Get average of 200 values and store as average current readings
+    aAvg[i] /= 200;
+    gAvg[i] /= 200;
+  }
+
+  // Configure the accelerometer for self-test
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
+  vTaskDelay(M2T(25)); // Delay a while to let the device stabilize
+
+  for(i = 0; i < 200; i++)
+  {
+    // get average self-test values of gyro and acclerometer
+    i2cdevRead(I2Cx, devAddr, MPU6500_RA_ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
+    aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+    aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+    aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+
+    i2cdevRead(I2Cx, devAddr, MPU6500_RA_GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
+    gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
+    gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
+    gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
+  }
+
+  for (i =0; i < 3; i++)
+  { // Get average of 200 values and store as average self-test readings
+    aSTAvg[i] /= 200;
+    gSTAvg[i] /= 200;
+  }
+
+   // Configure the gyro and accelerometer for normal operation
+   i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, 0x00);
+   i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, 0x00);
+   vTaskDelay(M2T(25)); // Delay a while to let the device stabilize
+
+   // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
+   i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ST_X_ACCEL, &selfTest[0]); // X-axis accel self-test results
+   i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ST_Y_ACCEL, &selfTest[1]); // Y-axis accel self-test results
+   i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ST_Z_ACCEL, &selfTest[2]); // Z-axis accel self-test results
+   i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ST_X_GYRO, &selfTest[3]); // X-axis gyro self-test results
+   i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ST_Y_GYRO, &selfTest[4]); // Y-axis gyro self-test results
+   i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_ST_Z_GYRO, &selfTest[5]); // Z-axis gyro self-test results
+
+   for (i = 0; i < 6; i++)
+   {
+      if (selfTest[i] != 0)
+      {
+        factoryTrim[i] = mpu6500StTb[selfTest[i] - 1];
+      }
+      else
+      {
+        factoryTrim[i] = 0;
+      }
+    }
+
+  // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
+  // To get percent, must multiply by 100
+  for (i = 0; i < 3; i++)
+  {
+   aDiff[i] = 100.0f*((float)((aSTAvg[i] - aAvg[i]) - factoryTrim[i]))/factoryTrim[i]; // Report percent differences
+   gDiff[i] = 100.0f*((float)((gSTAvg[i] - gAvg[i]) - factoryTrim[i+3]))/factoryTrim[i+3]; // Report percent differences
+//   DEBUG_PRINT("a[%d] Avg:%d, StAvg:%d, Shift:%d, FT:%d, Diff:%0.2f\n", i, aAvg[i], aSTAvg[i], aSTAvg[i] - aAvg[i], factoryTrim[i], aDiff[i]);
+//   DEBUG_PRINT("g[%d] Avg:%d, StAvg:%d, Shift:%d, FT:%d, Diff:%0.2f\n", i, gAvg[i], gSTAvg[i], gSTAvg[i] - gAvg[i], factoryTrim[i+3], gDiff[i]);
+  }
+
+  // Restore old configuration
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_SMPLRT_DIV, saveReg[0]);
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_CONFIG, saveReg[1]);
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, saveReg[2]);
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG_2, saveReg[3]);
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, saveReg[4]);
+
+   // Check result
+  if (mpu6500EvaluateSelfTest(MPU6500_ST_GYRO_LOW, MPU6500_ST_GYRO_HIGH, gDiff[0], "gyro X") &&
+      mpu6500EvaluateSelfTest(MPU6500_ST_GYRO_LOW, MPU6500_ST_GYRO_HIGH, gDiff[1], "gyro Y") &&
+      mpu6500EvaluateSelfTest(MPU6500_ST_GYRO_LOW, MPU6500_ST_GYRO_HIGH, gDiff[2], "gyro Z") &&
+      mpu6500EvaluateSelfTest(MPU6500_ST_ACCEL_LOW, MPU6500_ST_ACCEL_HIGH, aDiff[0], "acc X") &&
+      mpu6500EvaluateSelfTest(MPU6500_ST_ACCEL_LOW, MPU6500_ST_ACCEL_HIGH, aDiff[1], "acc Y") &&
+      mpu6500EvaluateSelfTest(MPU6500_ST_ACCEL_LOW, MPU6500_ST_ACCEL_HIGH, aDiff[2], "acc Z"))
+  {
+    return true;
+  }
+  else
+  {
+    return false;
+  }
+}
+
+/** Evaluate the values from a MPU6500 self test.
+ * @param low The low limit of the self test
+ * @param high The high limit of the self test
+ * @param value The value to compare with.
+ * @param string A pointer to a string describing the value.
+ * @return True if self test within low - high limit, false otherwise
+ */
+bool mpu6500EvaluateSelfTest(float low, float high, float value, char* string)
+{
+  if (value < low || value > high)
+  {
+    DEBUG_PRINT("Self test %s [FAIL]. low: %0.2f, high: %0.2f, measured: %0.2f\n",
+                string, low, high, value);
+    return false;
+  }
+  return true;
+}
+
+// SMPLRT_DIV register
+
+/** Get gyroscope output rate divider.
+ * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero
+ * Motion detection, and Free Fall detection are all based on the Sample Rate.
+ * The Sample Rate is generated by dividing the gyroscope output rate by
+ * SMPLRT_DIV:
+ *
+ * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
+ *
+ * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or
+ * 7), and 1kHz when the DLPF is enabled (see Register 26).
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * For a diagram of the gyroscope and accelerometer signal paths, see Section 8
+ * of the MPU-6000/MPU-6500 Product Specification document.
+ *
+ * @return Current sample rate
+ * @see MPU6500_RA_SMPLRT_DIV
+ */
+uint8_t mpu6500GetRate()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_SMPLRT_DIV, buffer);
+  return buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see MPU6500_RA_SMPLRT_DIV
+ */
+void mpu6500SetRate(uint8_t rate)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_SMPLRT_DIV, rate);
+}
+
+// CONFIG register
+
+/** Get external FSYNC configuration.
+ * Configures the external Frame Synchronization (FSYNC) pin sampling. An
+ * external signal connected to the FSYNC pin can be sampled by configuring
+ * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short
+ * strobes may be captured. The latched FSYNC signal will be sampled at the
+ * Sampling Rate, as defined in register 25. After sampling, the latch will
+ * reset to the current FSYNC signal state.
+ *
+ * The sampled value will be reported in place of the least significant bit in
+ * a sensor data register determined by the value of EXT_SYNC_SET according to
+ * the following table.
+ *
+ * <pre>
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0            | Input disabled
+ * 1            | TEMP_OUT_L[0]
+ * 2            | GYRO_XOUT_L[0]
+ * 3            | GYRO_YOUT_L[0]
+ * 4            | GYRO_ZOUT_L[0]
+ * 5            | ACCEL_XOUT_L[0]
+ * 6            | ACCEL_YOUT_L[0]
+ * 7            | ACCEL_ZOUT_L[0]
+ * </pre>
+ *
+ * @return FSYNC configuration value
+ */
+uint8_t mpu6500GetExternalFrameSync()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_CONFIG, MPU6500_CFG_EXT_SYNC_SET_BIT,
+      MPU6500_CFG_EXT_SYNC_SET_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set external FSYNC configuration.
+ * @see getExternalFrameSync()
+ * @see MPU6500_RA_CONFIG
+ * @param sync New FSYNC configuration value
+ */
+void mpu6500SetExternalFrameSync(uint8_t sync)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_CONFIG, MPU6500_CFG_EXT_SYNC_SET_BIT,
+      MPU6500_CFG_EXT_SYNC_SET_LENGTH, sync);
+}
+/** Get digital low-pass filter configuration.
+ * The DLPF_CFG parameter sets the digital low pass filter configuration. It
+ * also determines the internal sampling rate used by the device as shown in
+ * the table below.
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * <pre>
+ *          |   ACCELEROMETER    |           GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
+ * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
+ * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
+ * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
+ * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
+ * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
+ * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
+ * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
+ * </pre>
+ *
+ * @return DLFP configuration
+ * @see MPU6500_RA_CONFIG
+ * @see MPU6500_CFG_DLPF_CFG_BIT
+ * @see MPU6500_CFG_DLPF_CFG_LENGTH
+ */
+uint8_t mpu6500GetDLPFMode()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_CONFIG, MPU6500_CFG_DLPF_CFG_BIT,
+      MPU6500_CFG_DLPF_CFG_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set digital low-pass filter configuration.
+ * @param mode New DLFP configuration setting
+ * @see getDLPFBandwidth()
+ * @see MPU6500_DLPF_BW_256
+ * @see MPU6500_RA_CONFIG
+ * @see MPU6500_CFG_DLPF_CFG_BIT
+ * @see MPU6500_CFG_DLPF_CFG_LENGTH
+ */
+void mpu6500SetDLPFMode(uint8_t mode)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_CONFIG, MPU6500_CFG_DLPF_CFG_BIT,
+      MPU6500_CFG_DLPF_CFG_LENGTH, mode);
+}
+
+// GYRO_CONFIG register
+
+/** Get full-scale gyroscope range id.
+ * The FS_SEL parameter allows setting the full-scale range of the gyro sensors,
+ * as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * </pre>
+ *
+ * @return Current full-scale gyroscope range setting
+ * @see MPU6500_GYRO_FS_250
+ * @see MPU6500_RA_GYRO_CONFIG
+ * @see MPU6500_GCONFIG_FS_SEL_BIT
+ * @see MPU6500_GCONFIG_FS_SEL_LENGTH
+ */
+uint8_t mpu6500GetFullScaleGyroRangeId()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, MPU6500_GCONFIG_FS_SEL_BIT,
+      MPU6500_GCONFIG_FS_SEL_LENGTH, buffer);
+  return buffer[0];
+}
+
+/** Get full-scale gyroscope degrees per LSB.
+ *
+ * @return float of current full-scale gyroscope setting as degrees per LSB
+ * @see MPU6500_GYRO_FS_250
+ * @see MPU6500_RA_GYRO_CONFIG
+ * @see MPU6500_GCONFIG_FS_SEL_BIT
+ * @see MPU6500_GCONFIG_FS_SEL_LENGTH
+ */
+float mpu6500GetFullScaleGyroDPL()
+{
+  int32_t rangeId;
+  float range;
+
+  rangeId = mpu6500GetFullScaleGyroRangeId();
+  switch (rangeId)
+  {
+    case MPU6500_GYRO_FS_250:
+      range = MPU6500_DEG_PER_LSB_250;
+      break;
+    case MPU6500_GYRO_FS_500:
+      range = MPU6500_DEG_PER_LSB_500;
+      break;
+    case MPU6500_GYRO_FS_1000:
+      range = MPU6500_DEG_PER_LSB_1000;
+      break;
+    case MPU6500_GYRO_FS_2000:
+      range = MPU6500_DEG_PER_LSB_2000;
+      break;
+    default:
+      range = MPU6500_DEG_PER_LSB_1000;
+      break;
+  }
+
+  return range;
+}
+
+/** Set full-scale gyroscope range.
+ * @param range New full-scale gyroscope range value
+ * @see getFullScaleRange()
+ * @see MPU6500_GYRO_FS_250
+ * @see MPU6500_RA_GYRO_CONFIG
+ * @see MPU6500_GCONFIG_FS_SEL_BIT
+ * @see MPU6500_GCONFIG_FS_SEL_LENGTH
+ */
+void mpu6500SetFullScaleGyroRange(uint8_t range)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, MPU6500_GCONFIG_FS_SEL_BIT,
+      MPU6500_GCONFIG_FS_SEL_LENGTH, range);
+}
+
+void mpu6500SetGyroXSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, MPU6500_GCONFIG_XG_ST_BIT, enabled);
+}
+
+void mpu6500SetGyroYSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, MPU6500_GCONFIG_YG_ST_BIT, enabled);
+}
+
+void mpu6500SetGyroZSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_GYRO_CONFIG, MPU6500_GCONFIG_ZG_ST_BIT, enabled);
+}
+
+// ACCEL_CONFIG register
+
+/** Get self-test enabled setting for accelerometer X axis.
+ * @return Self-test enabled value
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+bool mpu6500GetAccelXSelfTest()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_XA_ST_BIT, buffer);
+  return buffer[0];
+}
+/** Get self-test enabled setting for accelerometer X axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+void mpu6500SetAccelXSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_XA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @return Self-test enabled value
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+bool mpu6500GetAccelYSelfTest()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_YA_ST_BIT, buffer);
+  return buffer[0];
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+void mpu6500SetAccelYSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_YA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Z axis.
+ * @return Self-test enabled value
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+bool mpu6500GetAccelZSelfTest()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_ZA_ST_BIT, buffer);
+  return buffer[0];
+}
+/** Set self-test enabled value for accelerometer Z axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+void mpu6500SetAccelZSelfTest(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_ZA_ST_BIT, enabled);
+}
+/** Get full-scale accelerometer range.
+ * The FS_SEL parameter allows setting the full-scale range of the accelerometer
+ * sensors, as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * </pre>
+ *
+ * @return Current full-scale accelerometer range setting
+ * @see MPU6500_ACCEL_FS_2
+ * @see MPU6500_RA_ACCEL_CONFIG
+ * @see MPU6500_ACONFIG_AFS_SEL_BIT
+ * @see MPU6500_ACONFIG_AFS_SEL_LENGTH
+ */
+uint8_t mpu6500GetFullScaleAccelRangeId()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_AFS_SEL_BIT,
+      MPU6500_ACONFIG_AFS_SEL_LENGTH, buffer);
+  return buffer[0];
+}
+
+/** Get full-scale accelerometer G per LSB.
+ *
+ * @return float of current full-scale accelerometer setting as G per LSB
+ * @see MPU6500_ACCEL_FS_2
+ * @see MPU6500_RA_ACCEL_CONFIG
+ * @see MPU6500_ACONFIG_AFS_SEL_BIT
+ * @see MPU6500_ACONFIG_AFS_SEL_LENGTH
+ */
+float mpu6500GetFullScaleAccelGPL()
+{
+  int32_t rangeId;
+  float range;
+
+  rangeId = mpu6500GetFullScaleAccelRangeId();
+  switch (rangeId)
+  {
+    case MPU6500_ACCEL_FS_2:
+      range = MPU6500_G_PER_LSB_2;
+      break;
+    case MPU6500_ACCEL_FS_4:
+      range = MPU6500_G_PER_LSB_4;
+      break;
+    case MPU6500_ACCEL_FS_8:
+      range = MPU6500_G_PER_LSB_8;
+      break;
+    case MPU6500_ACCEL_FS_16:
+      range = MPU6500_G_PER_LSB_16;
+      break;
+    default:
+      range = MPU6500_DEG_PER_LSB_1000;
+      break;
+  }
+
+  return range;
+}
+
+/** Set full-scale accelerometer range.
+ * @param range New full-scale accelerometer range setting
+ * @see getFullScaleAccelRange()
+ */
+void mpu6500SetFullScaleAccelRange(uint8_t range)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_AFS_SEL_BIT,
+      MPU6500_ACONFIG_AFS_SEL_LENGTH, range);
+}
+
+/** Set accelerometer digital low pass filter.
+ * @param range DLPF setting
+ * @see MPU6500_ACCEL_DLPF_BW_460
+ * @see MPU6500_ACCEL_DLPF_BW_184
+ * @see MPU6500_ACCEL_DLPF_BW_92
+ * @see MPU6500_ACCEL_DLPF_BW_41
+ * @see MPU6500_ACCEL_DLPF_BW_20
+ * @see MPU6500_ACCEL_DLPF_BW_10
+ * @see MPU6500_ACCEL_DLPF_BW_5
+ */
+void mpu6500SetAccelDLPF(uint8_t range)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG_2, MPU6500_ACONFIG2_DLPF_BIT,
+      MPU6500_ACONFIG2_DLPF_LENGTH, range);
+}
+
+/** Get the high-pass filter configuration.
+ * The DHPF is a filter module in the path leading to motion detectors (Free
+ * Fall, Motion threshold, and Zero Motion). The high pass filter output is not
+ * available to the data registers (see Figure in Section 8 of the MPU-6000/
+ * MPU-6500 Product Specification document).
+ *
+ * The high pass filter has three modes:
+ *
+ * <pre>
+ *    Reset: The filter output settles to zero within one sample. This
+ *           effectively disables the high pass filter. This mode may be toggled
+ *           to quickly settle the filter.
+ *
+ *    On:    The high pass filter will pass signals above the cut off frequency.
+ *
+ *    Hold:  When triggered, the filter holds the present sample. The filter
+ *           output will be the difference between the input sample and the held
+ *           sample.
+ * </pre>
+ *
+ * <pre>
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0         | Reset       | None
+ * 1         | On          | 5Hz
+ * 2         | On          | 2.5Hz
+ * 3         | On          | 1.25Hz
+ * 4         | On          | 0.63Hz
+ * 7         | Hold        | None
+ * </pre>
+ *
+ * @return Current high-pass filter configuration
+ * @see MPU6500_DHPF_RESET
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+uint8_t mpu6500GetDHPFMode()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_ACCEL_HPF_BIT,
+      MPU6500_ACONFIG_ACCEL_HPF_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set the high-pass filter configuration.
+ * @param bandwidth New high-pass filter configuration
+ * @see setDHPFMode()
+ * @see MPU6500_DHPF_RESET
+ * @see MPU6500_RA_ACCEL_CONFIG
+ */
+void mpu6500SetDHPFMode(uint8_t bandwidth)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_ACCEL_CONFIG, MPU6500_ACONFIG_ACCEL_HPF_BIT,
+      MPU6500_ACONFIG_ACCEL_HPF_LENGTH, bandwidth);
+}
+
+// FIFO_EN register
+
+/** Get temperature FIFO enabled value.
+ * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and
+ * 66) to be written into the FIFO buffer.
+ * @return Current temperature FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetTempFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_TEMP_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set temperature FIFO enabled value.
+ * @param enabled New temperature FIFO enabled value
+ * @see getTempFIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetTempFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_TEMP_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope X-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and
+ * 68) to be written into the FIFO buffer.
+ * @return Current gyroscope X-axis FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetXGyroFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_XG_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set gyroscope X-axis FIFO enabled value.
+ * @param enabled New gyroscope X-axis FIFO enabled value
+ * @see getXGyroFIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetXGyroFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_XG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Y-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and
+ * 70) to be written into the FIFO buffer.
+ * @return Current gyroscope Y-axis FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetYGyroFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_YG_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set gyroscope Y-axis FIFO enabled value.
+ * @param enabled New gyroscope Y-axis FIFO enabled value
+ * @see getYGyroFIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetYGyroFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_YG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Z-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and
+ * 72) to be written into the FIFO buffer.
+ * @return Current gyroscope Z-axis FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetZGyroFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_ZG_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set gyroscope Z-axis FIFO enabled value.
+ * @param enabled New gyroscope Z-axis FIFO enabled value
+ * @see getZGyroFIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetZGyroFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_ZG_FIFO_EN_BIT, enabled);
+}
+/** Get accelerometer FIFO enabled value.
+ * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H,
+ * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be
+ * written into the FIFO buffer.
+ * @return Current accelerometer FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetAccelFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_ACCEL_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set accelerometer FIFO enabled value.
+ * @param enabled New accelerometer FIFO enabled value
+ * @see getAccelFIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetAccelFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_ACCEL_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 2 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 2 to be written into the FIFO buffer.
+ * @return Current Slave 2 FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetSlave2FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_SLV2_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 2 FIFO enabled value.
+ * @param enabled New Slave 2 FIFO enabled value
+ * @see getSlave2FIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetSlave2FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_SLV2_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 1 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 1 to be written into the FIFO buffer.
+ * @return Current Slave 1 FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetSlave1FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_SLV1_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 1 FIFO enabled value.
+ * @param enabled New Slave 1 FIFO enabled value
+ * @see getSlave1FIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetSlave1FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_SLV1_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 0 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 0 to be written into the FIFO buffer.
+ * @return Current Slave 0 FIFO enabled value
+ * @see MPU6500_RA_FIFO_EN
+ */
+bool mpu6500GetSlave0FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_SLV0_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 0 FIFO enabled value.
+ * @param enabled New Slave 0 FIFO enabled value
+ * @see getSlave0FIFOEnabled()
+ * @see MPU6500_RA_FIFO_EN
+ */
+void mpu6500SetSlave0FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_FIFO_EN, MPU6500_SLV0_FIFO_EN_BIT, enabled);
+}
+
+// I2C_MST_CTRL register
+
+/** Get multi-master enabled value.
+ * Multi-master capability allows multiple I2C masters to operate on the same
+ * bus. In circuits where multi-master capability is required, set MULT_MST_EN
+ * to 1. This will increase current drawn by approximately 30uA.
+ *
+ * In circuits where multi-master capability is required, the state of the I2C
+ * bus must always be monitored by each separate I2C Master. Before an I2C
+ * Master can assume arbitration of the bus, it must first confirm that no other
+ * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the
+ * MPU-60X0's bus arbitration detection logic is turned on, enabling it to
+ * detect when the bus is available.
+ *
+ * @return Current multi-master enabled value
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+bool mpu6500GetMultiMasterEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_MULT_MST_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set multi-master enabled value.
+ * @param enabled New multi-master enabled value
+ * @see getMultiMasterEnabled()
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+void mpu6500SetMultiMasterEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_MULT_MST_EN_BIT, enabled);
+}
+/** Get wait-for-external-sensor-data enabled value.
+ * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be
+ * delayed until External Sensor data from the Slave Devices are loaded into the
+ * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor
+ * data (i.e. from gyro and accel) and external sensor data have been loaded to
+ * their respective data registers (i.e. the data is synced) when the Data Ready
+ * interrupt is triggered.
+ *
+ * @return Current wait-for-external-sensor-data enabled value
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+bool mpu6500GetWaitForExternalSensorEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_WAIT_FOR_ES_BIT, buffer);
+  return buffer[0];
+}
+/** Set wait-for-external-sensor-data enabled value.
+ * @param enabled New wait-for-external-sensor-data enabled value
+ * @see getWaitForExternalSensorEnabled()
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+void mpu6500SetWaitForExternalSensorEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_WAIT_FOR_ES_BIT, enabled);
+}
+/** Get Slave 3 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 3 to be written into the FIFO buffer.
+ * @return Current Slave 3 FIFO enabled value
+ * @see MPU6500_RA_MST_CTRL
+ */
+bool mpu6500GetSlave3FIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_SLV_3_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set Slave 3 FIFO enabled value.
+ * @param enabled New Slave 3 FIFO enabled value
+ * @see getSlave3FIFOEnabled()
+ * @see MPU6500_RA_MST_CTRL
+ */
+void mpu6500SetSlave3FIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_SLV_3_FIFO_EN_BIT, enabled);
+}
+/** Get slave read/write transition enabled value.
+ * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave
+ * read to the next slave read. If the bit equals 0, there will be a restart
+ * between reads. If the bit equals 1, there will be a stop followed by a start
+ * of the following read. When a write transaction follows a read transaction,
+ * the stop followed by a start of the successive write will be always used.
+ *
+ * @return Current slave read/write transition enabled value
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+bool mpu6500GetSlaveReadWriteTransitionEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_I2C_MST_P_NSR_BIT, buffer);
+  return buffer[0];
+}
+/** Set slave read/write transition enabled value.
+ * @param enabled New slave read/write transition enabled value
+ * @see getSlaveReadWriteTransitionEnabled()
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+void mpu6500SetSlaveReadWriteTransitionEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_I2C_MST_P_NSR_BIT, enabled);
+}
+/** Get I2C master clock speed.
+ * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the
+ * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to
+ * the following table:
+ *
+ * <pre>
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0           | 348kHz                 | 23
+ * 1           | 333kHz                 | 24
+ * 2           | 320kHz                 | 25
+ * 3           | 308kHz                 | 26
+ * 4           | 296kHz                 | 27
+ * 5           | 286kHz                 | 28
+ * 6           | 276kHz                 | 29
+ * 7           | 267kHz                 | 30
+ * 8           | 258kHz                 | 31
+ * 9           | 500kHz                 | 16
+ * 10          | 471kHz                 | 17
+ * 11          | 444kHz                 | 18
+ * 12          | 421kHz                 | 19
+ * 13          | 400kHz                 | 20
+ * 14          | 381kHz                 | 21
+ * 15          | 364kHz                 | 22
+ * </pre>
+ *
+ * @return Current I2C master clock speed
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+uint8_t mpu6500GetMasterClockSpeed()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_I2C_MST_CLK_BIT,
+      MPU6500_I2C_MST_CLK_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set I2C master clock speed.
+ * @reparam speed Current I2C master clock speed
+ * @see MPU6500_RA_I2C_MST_CTRL
+ */
+void mpu6500SetMasterClockSpeed(uint8_t speed)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_I2C_MST_CTRL, MPU6500_I2C_MST_CLK_BIT,
+      MPU6500_I2C_MST_CLK_LENGTH, speed);
+}
+
+// I2C_SLV* registers (Slave 0-3)
+
+/** Get the I2C address of the specified slave (0-3).
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * In read mode, the result of the read is placed in the lowest available 
+ * EXT_SENS_DATA register. For further information regarding the allocation of
+ * read results, please refer to the EXT_SENS_DATA register description
+ * (Registers 73 - 96).
+ *
+ * The MPU-6500 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions (getSlave4* and setSlave4*).
+ *
+ * I2C data transactions are performed at the Sample Rate, as defined in
+ * Register 25. The user is responsible for ensuring that I2C data transactions
+ * to and from each enabled Slave can be completed within a single period of the
+ * Sample Rate.
+ *
+ * The I2C slave access rate can be reduced relative to the Sample Rate. This
+ * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a
+ * slave's access rate is reduced relative to the Sample Rate is determined by
+ * I2C_MST_DELAY_CTRL (Register 103).
+ *
+ * The processing order for the slaves is fixed. The sequence followed for
+ * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a
+ * particular Slave is disabled it will be skipped.
+ *
+ * Each slave can either be accessed at the sample rate or at a reduced sample
+ * rate. In a case where some slaves are accessed at the Sample Rate and some
+ * slaves are accessed at the reduced rate, the sequence of accessing the slaves
+ * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will
+ * be skipped if their access rate dictates that they should not be accessed
+ * during that particular cycle. For further information regarding the reduced
+ * access rate, please refer to Register 52. Whether a slave is accessed at the
+ * Sample Rate or at the reduced rate is determined by the Delay Enable bits in
+ * Register 103.
+ *
+ * @param num Slave number (0-3)
+ * @return Current address for specified slave
+ * @see MPU6500_RA_I2C_SLV0_ADDR
+ */
+uint8_t mpu6500GetSlaveAddress(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_ADDR + num * 3, buffer);
+  return buffer[0];
+}
+/** Set the I2C address of the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param address New address for specified slave
+ * @see getSlaveAddress()
+ * @see MPU6500_RA_I2C_SLV0_ADDR
+ */
+void mpu6500SetSlaveAddress(uint8_t num, uint8_t address)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_ADDR + num * 3, address);
+}
+/** Get the active internal register for the specified slave (0-3).
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * The MPU-6500 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions.
+ *
+ * @param num Slave number (0-3)
+ * @return Current active register for specified slave
+ * @see MPU6500_RA_I2C_SLV0_REG
+ */
+uint8_t mpu6500GetSlaveRegister(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_REG + num * 3, buffer);
+  return buffer[0];
+}
+/** Set the active internal register for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param reg New active register for specified slave
+ * @see getSlaveRegister()
+ * @see MPU6500_RA_I2C_SLV0_REG
+ */
+void mpu6500SetSlaveRegister(uint8_t num, uint8_t reg)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_REG + num * 3, reg);
+}
+/** Get the enabled value for the specified slave (0-3).
+ * When set to 1, this bit enables Slave 0 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 0 from data transfer operations.
+ * @param num Slave number (0-3)
+ * @return Current enabled value for specified slave
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+bool mpu6500GetSlaveEnabled(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set the enabled value for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New enabled value for specified slave
+ * @see getSlaveEnabled()
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+void mpu6500SetSlaveEnabled(uint8_t num, bool enabled)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_EN_BIT,
+      enabled);
+}
+/** Get word pair byte-swapping enabled for the specified slave (0-3).
+ * When set to 1, this bit enables byte swapping. When byte swapping is enabled,
+ * the high and low bytes of a word pair are swapped. Please refer to
+ * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0,
+ * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA
+ * registers in the order they were transferred.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair byte-swapping enabled value for specified slave
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+bool mpu6500GetSlaveWordByteSwap(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_BYTE_SW_BIT,
+      buffer);
+  return buffer[0];
+}
+/** Set word pair byte-swapping enabled for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair byte-swapping enabled value for specified slave
+ * @see getSlaveWordByteSwap()
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+void mpu6500SetSlaveWordByteSwap(uint8_t num, bool enabled)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_BYTE_SW_BIT,
+      enabled);
+}
+/** Get write mode for the specified slave (0-3).
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @param num Slave number (0-3)
+ * @return Current write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+bool mpu6500GetSlaveWriteMode(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_REG_DIS_BIT,
+      buffer);
+  return buffer[0];
+}
+/** Set write mode for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param mode New write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see getSlaveWriteMode()
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+void mpu6500SetSlaveWriteMode(uint8_t num, bool mode)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_REG_DIS_BIT,
+      mode);
+}
+/** Get word pair grouping order offset for the specified slave (0-3).
+ * This sets specifies the grouping order of word pairs received from registers.
+ * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even,
+ * then odd register addresses) are paired to form a word. When set to 1, bytes
+ * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even
+ * register addresses) are paired to form a word.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair grouping order offset for specified slave
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+bool mpu6500GetSlaveWordGroupOffset(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_GRP_BIT, buffer);
+  return buffer[0];
+}
+/** Set word pair grouping order offset for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair grouping order offset for specified slave
+ * @see getSlaveWordGroupOffset()
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+void mpu6500SetSlaveWordGroupOffset(uint8_t num, bool enabled)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_GRP_BIT,
+      enabled);
+}
+/** Get number of bytes to read for the specified slave (0-3).
+ * Specifies the number of bytes transferred to and from Slave 0. Clearing this
+ * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN.
+ * @param num Slave number (0-3)
+ * @return Number of bytes to read for specified slave
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+uint8_t mpu6500GetSlaveDataLength(uint8_t num)
+{
+  if (num > 3)
+    return 0;
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_LEN_BIT,
+      MPU6500_I2C_SLV_LEN_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set number of bytes to read for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param length Number of bytes to read for specified slave
+ * @see getSlaveDataLength()
+ * @see MPU6500_RA_I2C_SLV0_CTRL
+ */
+void mpu6500SetSlaveDataLength(uint8_t num, uint8_t length)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_CTRL + num * 3, MPU6500_I2C_SLV_LEN_BIT,
+      MPU6500_I2C_SLV_LEN_LENGTH, length);
+}
+
+// I2C_SLV* registers (Slave 4)
+
+/** Get the I2C address of Slave 4.
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * @return Current address for Slave 4
+ * @see getSlaveAddress()
+ * @see MPU6500_RA_I2C_SLV4_ADDR
+ */
+uint8_t mpu6500GetSlave4Address()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_ADDR, buffer);
+  return buffer[0];
+}
+/** Set the I2C address of Slave 4.
+ * @param address New address for Slave 4
+ * @see getSlave4Address()
+ * @see MPU6500_RA_I2C_SLV4_ADDR
+ */
+void mpu6500SetSlave4Address(uint8_t address)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_ADDR, address);
+}
+/** Get the active internal register for the Slave 4.
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * @return Current active register for Slave 4
+ * @see MPU6500_RA_I2C_SLV4_REG
+ */
+uint8_t mpu6500GetSlave4Register()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_REG, buffer);
+  return buffer[0];
+}
+/** Set the active internal register for Slave 4.
+ * @param reg New active register for Slave 4
+ * @see getSlave4Register()
+ * @see MPU6500_RA_I2C_SLV4_REG
+ */
+void mpu6500SetSlave4Register(uint8_t reg)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_REG, reg);
+}
+/** Set new byte to write to Slave 4.
+ * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW
+ * is set 1 (set to read), this register has no effect.
+ * @param data New byte to write to Slave 4
+ * @see MPU6500_RA_I2C_SLV4_DO
+ */
+void mpu6500SetSlave4OutputByte(uint8_t data)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_DO, data);
+}
+/** Get the enabled value for the Slave 4.
+ * When set to 1, this bit enables Slave 4 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 4 from data transfer operations.
+ * @return Current enabled value for Slave 4
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+bool mpu6500GetSlave4Enabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set the enabled value for Slave 4.
+ * @param enabled New enabled value for Slave 4
+ * @see getSlave4Enabled()
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+void mpu6500SetSlave4Enabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_EN_BIT, enabled);
+}
+/** Get the enabled value for Slave 4 transaction interrupts.
+ * When set to 1, this bit enables the generation of an interrupt signal upon
+ * completion of a Slave 4 transaction. When cleared to 0, this bit disables the
+ * generation of an interrupt signal upon completion of a Slave 4 transaction.
+ * The interrupt status can be observed in Register 54.
+ *
+ * @return Current enabled value for Slave 4 transaction interrupts.
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+bool mpu6500GetSlave4InterruptEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_INT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set the enabled value for Slave 4 transaction interrupts.
+ * @param enabled New enabled value for Slave 4 transaction interrupts.
+ * @see getSlave4InterruptEnabled()
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+void mpu6500SetSlave4InterruptEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_INT_EN_BIT, enabled);
+}
+/** Get write mode for Slave 4.
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+bool mpu6500GetSlave4WriteMode()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_REG_DIS_BIT, buffer);
+  return buffer[0];
+}
+/** Set write mode for the Slave 4.
+ * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see getSlave4WriteMode()
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+void mpu6500SetSlave4WriteMode(bool mode)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_REG_DIS_BIT, mode);
+}
+/** Get Slave 4 master delay value.
+ * This configures the reduced access rate of I2C slaves relative to the Sample
+ * Rate. When a slave's access rate is decreased relative to the Sample Rate,
+ * the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and
+ * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to
+ * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For
+ * further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @return Current Slave 4 master delay value
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+uint8_t mpu6500GetSlave4MasterDelay()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_MST_DLY_BIT,
+      MPU6500_I2C_SLV4_MST_DLY_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set Slave 4 master delay value.
+ * @param delay New Slave 4 master delay value
+ * @see getSlave4MasterDelay()
+ * @see MPU6500_RA_I2C_SLV4_CTRL
+ */
+void mpu6500SetSlave4MasterDelay(uint8_t delay)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_CTRL, MPU6500_I2C_SLV4_MST_DLY_BIT,
+      MPU6500_I2C_SLV4_MST_DLY_LENGTH, delay);
+}
+/** Get last available byte read from Slave 4.
+ * This register stores the data read from Slave 4. This field is populated
+ * after a read transaction.
+ * @return Last available byte read from to Slave 4
+ * @see MPU6500_RA_I2C_SLV4_DI
+ */
+uint8_t mpu6500GetSlate4InputByte()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV4_DI, buffer);
+  return buffer[0];
+}
+
+// I2C_MST_STATUS register
+
+/** Get FSYNC interrupt status.
+ * This bit reflects the status of the FSYNC interrupt from an external device
+ * into the MPU-60X0. This is used as a way to pass an external interrupt
+ * through the MPU-60X0 to the host application processor. When set to 1, this
+ * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG
+ * (Register 55).
+ * @return FSYNC interrupt status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetPassthroughStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_PASS_THROUGH_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 4 transaction done status.
+ * Automatically sets to 1 when a Slave 4 transaction has completed. This
+ * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register
+ * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the
+ * I2C_SLV4_CTRL register (Register 52).
+ * @return Slave 4 transaction done status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetSlave4IsDone()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_I2C_SLV4_DONE_BIT, buffer);
+  return buffer[0];
+}
+/** Get master arbitration lost status.
+ * This bit automatically sets to 1 when the I2C Master has lost arbitration of
+ * the auxiliary I2C bus (an error condition). This triggers an interrupt if the
+ * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Master arbitration lost status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetLostArbitration()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_I2C_LOST_ARB_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 4 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 4 NACK interrupt status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetSlave4Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_I2C_SLV4_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 3 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 3 NACK interrupt status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetSlave3Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_I2C_SLV3_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 2 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 2 NACK interrupt status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetSlave2Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_I2C_SLV2_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 1 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 1 NACK interrupt status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetSlave1Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_I2C_SLV1_NACK_BIT, buffer);
+  return buffer[0];
+}
+/** Get Slave 0 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 0 NACK interrupt status
+ * @see MPU6500_RA_I2C_MST_STATUS
+ */
+bool mpu6500GetSlave0Nack()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_STATUS, MPU6500_MST_I2C_SLV0_NACK_BIT, buffer);
+  return buffer[0];
+}
+
+// INT_PIN_CFG register
+
+/** Get interrupt logic level mode.
+ * Will be set 0 for active-high, 1 for active-low.
+ * @return Current interrupt mode (0=active-high, 1=active-low)
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_INT_LEVEL_BIT
+ */
+bool mpu6500GetInterruptMode()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_INT_LEVEL_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt logic level mode.
+ * @param mode New interrupt mode (0=active-high, 1=active-low)
+ * @see getInterruptMode()
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_INT_LEVEL_BIT
+ */
+void mpu6500SetInterruptMode(bool mode)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_INT_LEVEL_BIT, mode);
+}
+/** Get interrupt drive mode.
+ * Will be set 0 for push-pull, 1 for open-drain.
+ * @return Current interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_INT_OPEN_BIT
+ */
+bool mpu6500GetInterruptDrive()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_INT_OPEN_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt drive mode.
+ * @param drive New interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see getInterruptDrive()
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_INT_OPEN_BIT
+ */
+void mpu6500SetInterruptDrive(bool drive)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_INT_OPEN_BIT, drive);
+}
+/** Get interrupt latch mode.
+ * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared.
+ * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_LATCH_INT_EN_BIT
+ */
+bool mpu6500GetInterruptLatch()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_LATCH_INT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt latch mode.
+ * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see getInterruptLatch()
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_LATCH_INT_EN_BIT
+ */
+void mpu6500SetInterruptLatch(bool latch)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_LATCH_INT_EN_BIT, latch);
+}
+/** Get interrupt latch clear mode.
+ * Will be set 0 for status-read-only, 1 for any-register-read.
+ * @return Current latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_INT_RD_CLEAR_BIT
+ */
+bool mpu6500GetInterruptLatchClear()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_INT_RD_CLEAR_BIT, buffer);
+  return buffer[0];
+}
+/** Set interrupt latch clear mode.
+ * @param clear New latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see getInterruptLatchClear()
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_INT_RD_CLEAR_BIT
+ */
+void mpu6500SetInterruptLatchClear(bool clear)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_INT_RD_CLEAR_BIT, clear);
+}
+/** Get FSYNC interrupt logic level mode.
+ * @return Current FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+bool mpu6500GetFSyncInterruptLevel()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_FSYNC_INT_LEVEL_BIT, buffer);
+  return buffer[0];
+}
+/** Set FSYNC interrupt logic level mode.
+ * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+void mpu6500SetFSyncInterruptLevel(bool level)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_FSYNC_INT_LEVEL_BIT, level);
+}
+/** Get FSYNC pin interrupt enabled setting.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled setting
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_FSYNC_INT_EN_BIT
+ */
+bool mpu6500GetFSyncInterruptEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_FSYNC_INT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set FSYNC pin interrupt enabled setting.
+ * @param enabled New FSYNC pin interrupt enabled setting
+ * @see getFSyncInterruptEnabled()
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_FSYNC_INT_EN_BIT
+ */
+void mpu6500SetFSyncInterruptEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_FSYNC_INT_EN_BIT, enabled);
+}
+/** Get I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @return Current I2C bypass enabled status
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_I2C_BYPASS_EN_BIT
+ */
+bool mpu6500GetI2CBypassEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_I2C_BYPASS_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @param enabled New I2C bypass enabled status
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_I2C_BYPASS_EN_BIT
+ */
+void mpu6500SetI2CBypassEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_I2C_BYPASS_EN_BIT, enabled);
+}
+/** Get reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @return Current reference clock output enabled status
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_CLKOUT_EN_BIT
+ */
+bool mpu6500GetClockOutputEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_CLKOUT_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @param enabled New reference clock output enabled status
+ * @see MPU6500_RA_INT_PIN_CFG
+ * @see MPU6500_INTCFG_CLKOUT_EN_BIT
+ */
+void mpu6500SetClockOutputEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_PIN_CFG, MPU6500_INTCFG_CLKOUT_EN_BIT, enabled);
+}
+
+// INT_ENABLE register
+
+/** Get full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit will be
+ * set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_FF_BIT
+ **/
+uint8_t mpu6500GetIntEnabled()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, buffer);
+  return buffer[0];
+}
+/** Set full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit should be
+ * set 0 for disabled, 1 for enabled.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_FF_BIT
+ **/
+void mpu6500SetIntEnabled(uint8_t enabled)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, enabled);
+}
+/** Get Free Fall interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_FF_BIT
+ **/
+bool mpu6500GetIntFreefallEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_FF_BIT, buffer);
+  return buffer[0];
+}
+/** Set Free Fall interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_FF_BIT
+ **/
+void mpu6500SetIntFreefallEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_FF_BIT, enabled);
+}
+/** Get Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_MOT_BIT
+ **/
+bool mpu6500GetIntMotionEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_MOT_BIT, buffer);
+  return buffer[0];
+}
+/** Set Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntMotionEnabled()
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_MOT_BIT
+ **/
+void mpu6500SetIntMotionEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_MOT_BIT, enabled);
+}
+/** Get Zero Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_ZMOT_BIT
+ **/
+bool mpu6500GetIntZeroMotionEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_ZMOT_BIT, buffer);
+  return buffer[0];
+}
+/** Set Zero Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntZeroMotionEnabled()
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_ZMOT_BIT
+ **/
+void mpu6500SetIntZeroMotionEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_ZMOT_BIT, enabled);
+}
+/** Get FIFO Buffer Overflow interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+bool mpu6500GetIntFIFOBufferOverflowEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+  return buffer[0];
+}
+/** Set FIFO Buffer Overflow interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFIFOBufferOverflowEnabled()
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+void mpu6500SetIntFIFOBufferOverflowEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_FIFO_OFLOW_BIT, enabled);
+}
+/** Get I2C Master interrupt enabled status.
+ * This enables any of the I2C Master interrupt sources to generate an
+ * interrupt. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_I2C_MST_INT_BIT
+ **/
+bool mpu6500GetIntI2CMasterEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_I2C_MST_INT_BIT, buffer);
+  return buffer[0];
+}
+/** Set I2C Master interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntI2CMasterEnabled()
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_I2C_MST_INT_BIT
+ **/
+void mpu6500SetIntI2CMasterEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_I2C_MST_INT_BIT, enabled);
+}
+/** Get Data Ready interrupt enabled setting.
+ * This event occurs each time a write operation to all of the sensor registers
+ * has been completed. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6500_RA_INT_ENABLE
+ * @see MPU6500_INTERRUPT_DATA_RDY_BIT
+ */
+bool mpu6500GetIntDataReadyEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_DATA_RDY_BIT, buffer);
+  return buffer[0];
+}
+/** Set Data Ready interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntDataReadyEnabled()
+ * @see MPU6500_RA_INT_CFG
+ * @see MPU6500_INTERRUPT_DATA_RDY_BIT
+ */
+void mpu6500SetIntDataReadyEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_DATA_RDY_BIT, enabled);
+}
+
+// INT_STATUS register
+
+/** Get full set of interrupt status bits.
+ * These bits clear to 0 after the register has been read. Very useful
+ * for getting multiple INT statuses, since each single bit read clears
+ * all of them because it has to read the whole byte.
+ * @return Current interrupt status
+ * @see MPU6500_RA_INT_STATUS
+ */
+uint8_t mpu6500GetIntStatus()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_INT_STATUS, buffer);
+  return buffer[0];
+}
+/** Get Free Fall interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6500_RA_INT_STATUS
+ * @see MPU6500_INTERRUPT_FF_BIT
+ */
+bool mpu6500GetIntFreefallStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_FF_BIT, buffer);
+  return buffer[0];
+}
+/** Get Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Motion Detection interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6500_RA_INT_STATUS
+ * @see MPU6500_INTERRUPT_MOT_BIT
+ */
+bool mpu6500GetIntMotionStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_MOT_BIT, buffer);
+  return buffer[0];
+}
+/** Get Zero Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Zero Motion Detection interrupt has
+ * been generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6500_RA_INT_STATUS
+ * @see MPU6500_INTERRUPT_ZMOT_BIT
+ */
+bool mpu6500GetIntZeroMotionStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_ZMOT_BIT, buffer);
+  return buffer[0];
+}
+/** Get FIFO Buffer Overflow interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6500_RA_INT_STATUS
+ * @see MPU6500_INTERRUPT_FIFO_OFLOW_BIT
+ */
+bool mpu6500GetIntFIFOBufferOverflowStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+  return buffer[0];
+}
+/** Get I2C Master interrupt status.
+ * This bit automatically sets to 1 when an I2C Master interrupt has been
+ * generated. For a list of I2C Master interrupts, please refer to Register 54.
+ * The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6500_RA_INT_STATUS
+ * @see MPU6500_INTERRUPT_I2C_MST_INT_BIT
+ */
+bool mpu6500GetIntI2CMasterStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_I2C_MST_INT_BIT, buffer);
+  return buffer[0];
+}
+/** Get Data Ready interrupt status.
+ * This bit automatically sets to 1 when a Data Ready interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6500_RA_INT_STATUS
+ * @see MPU6500_INTERRUPT_DATA_RDY_BIT
+ */
+bool mpu6500GetIntDataReadyStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_DATA_RDY_BIT, buffer);
+  return buffer[0];
+}
+
+// ACCEL_*OUT_* registers
+
+/** Get raw 9-axis motion sensor readings (accel/gyro/compass).
+ * FUNCTION NOT FULLY IMPLEMENTED YET.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @param mx 16-bit signed integer container for magnetometer X-axis value
+ * @param my 16-bit signed integer container for magnetometer Y-axis value
+ * @param mz 16-bit signed integer container for magnetometer Z-axis value
+ * @see getMotion6()
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6500_RA_ACCEL_XOUT_H
+ */
+void mpu6500GetMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz,
+    int16_t* mx, int16_t* my, int16_t* mz)
+{
+  mpu6500GetMotion6(ax, ay, az, gx, gy, gz);
+  // TODO: magnetometer integration
+}
+/** Get raw 6-axis motion sensor readings (accel/gyro).
+ * Retrieves all currently available motion sensor values.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6500_RA_ACCEL_XOUT_H
+ */
+void mpu6500GetMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_ACCEL_XOUT_H, 14, buffer);
+  *ax = (((int16_t) buffer[0]) << 8) | buffer[1];
+  *ay = (((int16_t) buffer[2]) << 8) | buffer[3];
+  *az = (((int16_t) buffer[4]) << 8) | buffer[5];
+  *gx = (((int16_t) buffer[8]) << 8) | buffer[9];
+  *gy = (((int16_t) buffer[10]) << 8) | buffer[11];
+  *gz = (((int16_t) buffer[12]) << 8) | buffer[13];
+}
+/** Get 3-axis accelerometer readings.
+ * These registers store the most recent accelerometer measurements.
+ * Accelerometer measurements are written to these registers at the Sample Rate
+ * as defined in Register 25.
+ *
+ * The accelerometer measurement registers, along with the temperature
+ * measurement registers, gyroscope measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ *
+ * The data within the accelerometer sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS
+ * (Register 28). For each full scale setting, the accelerometers' sensitivity
+ * per LSB in ACCEL_xOUT is shown in the table below:
+ *
+ * <pre>
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0       | +/- 2g           | 8192 LSB/mg
+ * 1       | +/- 4g           | 4096 LSB/mg
+ * 2       | +/- 8g           | 2048 LSB/mg
+ * 3       | +/- 16g          | 1024 LSB/mg
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis acceleration
+ * @param y 16-bit signed integer container for Y-axis acceleration
+ * @param z 16-bit signed integer container for Z-axis acceleration
+ * @see MPU6500_RA_GYRO_XOUT_H
+ */
+void mpu6500GetAcceleration(int16_t* x, int16_t* y, int16_t* z)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_ACCEL_XOUT_H, 6, buffer);
+  *x = (((int16_t) buffer[0]) << 8) | buffer[1];
+  *y = (((int16_t) buffer[2]) << 8) | buffer[3];
+  *z = (((int16_t) buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis accelerometer reading.
+ * @return X-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6500_RA_ACCEL_XOUT_H
+ */
+int16_t mpu6500GetAccelerationX()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_ACCEL_XOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis accelerometer reading.
+ * @return Y-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6500_RA_ACCEL_YOUT_H
+ */
+int16_t mpu6500GetAccelerationY()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_ACCEL_YOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis accelerometer reading.
+ * @return Z-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6500_RA_ACCEL_ZOUT_H
+ */
+int16_t mpu6500GetAccelerationZ()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_ACCEL_ZOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// TEMP_OUT_* registers
+
+/** Get current internal temperature.
+ * @return Temperature reading in 16-bit 2's complement format
+ * @see MPU6500_RA_TEMP_OUT_H
+ */
+int16_t mpu6500GetTemperature()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_TEMP_OUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// GYRO_*OUT_* registers
+
+/** Get 3-axis gyroscope readings.
+ * These gyroscope measurement registers, along with the accelerometer
+ * measurement registers, temperature measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ * The data within the gyroscope sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL
+ * (Register 27). For each full scale setting, the gyroscopes' sensitivity per
+ * LSB in GYRO_xOUT is shown in the table below:
+ *
+ * <pre>
+ * FS_SEL | Full Scale Range   | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
+ * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
+ * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis rotation
+ * @param y 16-bit signed integer container for Y-axis rotation
+ * @param z 16-bit signed integer container for Z-axis rotation
+ * @see getMotion6()
+ * @see MPU6500_RA_GYRO_XOUT_H
+ */
+void mpu6500GetRotation(int16_t* x, int16_t* y, int16_t* z)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_GYRO_XOUT_H, 6, buffer);
+  *x = (((int16_t) buffer[0]) << 8) | buffer[1];
+  *y = (((int16_t) buffer[2]) << 8) | buffer[3];
+  *z = (((int16_t) buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis gyroscope reading.
+ * @return X-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6500_RA_GYRO_XOUT_H
+ */
+int16_t mpu6500GetRotationX()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_GYRO_XOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis gyroscope reading.
+ * @return Y-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6500_RA_GYRO_YOUT_H
+ */
+int16_t mpu6500GetRotationY()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_GYRO_YOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis gyroscope reading.
+ * @return Z-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6500_RA_GYRO_ZOUT_H
+ */
+int16_t mpu6500GetRotationZ()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_GYRO_ZOUT_H, 2, buffer);
+  return (((int16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// EXT_SENS_DATA_* registers
+
+/** Read single byte from external sensor data register.
+ * These registers store data read from external sensors by the Slave 0, 1, 2,
+ * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in
+ * I2C_SLV4_DI (Register 53).
+ *
+ * External sensor data is written to these registers at the Sample Rate as
+ * defined in Register 25. This access rate can be reduced by using the Slave
+ * Delay Enable registers (Register 103).
+ *
+ * External sensor data registers, along with the gyroscope measurement
+ * registers, accelerometer measurement registers, and temperature measurement
+ * registers, are composed of two sets of registers: an internal register set
+ * and a user-facing read register set.
+ *
+ * The data within the external sensors' internal register set is always updated
+ * at the Sample Rate (or the reduced access rate) whenever the serial interface
+ * is idle. This guarantees that a burst read of sensor registers will read
+ * measurements from the same sampling instant. Note that if burst reads are not
+ * used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Data is placed in these external sensor data registers according to
+ * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39,
+ * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from
+ * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as
+ * defined in Register 25) or delayed rate (if specified in Register 52 and
+ * 103). During each Sample cycle, slave reads are performed in order of Slave
+ * number. If all slaves are enabled with more than zero bytes to be read, the
+ * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3.
+ *
+ * Each enabled slave will have EXT_SENS_DATA registers associated with it by
+ * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from
+ * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may
+ * change the higher numbered slaves' associated registers. Furthermore, if
+ * fewer total bytes are being read from the external sensors as a result of
+ * such a change, then the data remaining in the registers which no longer have
+ * an associated slave device (i.e. high numbered registers) will remain in
+ * these previously allocated registers unless reset.
+ *
+ * If the sum of the read lengths of all SLVx transactions exceed the number of
+ * available EXT_SENS_DATA registers, the excess bytes will be dropped. There
+ * are 24 EXT_SENS_DATA registers and hence the total read lengths between all
+ * the slaves cannot be greater than 24 or some bytes will be lost.
+ *
+ * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further
+ * information regarding the characteristics of Slave 4, please refer to
+ * Registers 49 to 53.
+ *
+ * EXAMPLE:
+ * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and
+ * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that
+ * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00
+ * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05
+ * will be associated with Slave 1. If Slave 2 is enabled as well, registers
+ * starting from EXT_SENS_DATA_06 will be allocated to Slave 2.
+ *
+ * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then
+ * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3
+ * instead.
+ *
+ * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE:
+ * If a slave is disabled at any time, the space initially allocated to the
+ * slave in the EXT_SENS_DATA register, will remain associated with that slave.
+ * This is to avoid dynamic adjustment of the register allocation.
+ *
+ * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all
+ * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106).
+ *
+ * This above is also true if one of the slaves gets NACKed and stops
+ * functioning.
+ *
+ * @param position Starting position (0-23)
+ * @return Byte read from register
+ */
+uint8_t mpu6500GetExternalSensorByte(int position)
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_EXT_SENS_DATA_00 + position, buffer);
+  return buffer[0];
+}
+/** Read word (2 bytes) from external sensor data registers.
+ * @param position Starting position (0-21)
+ * @return Word read from register
+ * @see getExternalSensorByte()
+ */
+uint16_t mpu6500GetExternalSensorWord(int position)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_EXT_SENS_DATA_00 + position, 2, buffer);
+  return (((uint16_t) buffer[0]) << 8) | buffer[1];
+}
+/** Read double word (4 bytes) from external sensor data registers.
+ * @param position Starting position (0-20)
+ * @return Double word read from registers
+ * @see getExternalSensorByte()
+ */
+uint32_t mpu6500GetExternalSensorDWord(int position)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_EXT_SENS_DATA_00 + position, 4, buffer);
+  return (((uint32_t) buffer[0]) << 24) | (((uint32_t) buffer[1]) << 16)
+      | (((uint16_t) buffer[2]) << 8) | buffer[3];
+}
+
+// MOT_DETECT_STATUS register
+
+/** Get X-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6500_RA_MOT_DETECT_STATUS
+ * @see MPU6500_MOTION_MOT_XNEG_BIT
+ */
+bool mpu6500GetXNegMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_STATUS, MPU6500_MOTION_MOT_XNEG_BIT, buffer);
+  return buffer[0];
+}
+/** Get X-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6500_RA_MOT_DETECT_STATUS
+ * @see MPU6500_MOTION_MOT_XPOS_BIT
+ */
+bool mpu6500GetXPosMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_STATUS, MPU6500_MOTION_MOT_XPOS_BIT, buffer);
+  return buffer[0];
+}
+/** Get Y-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6500_RA_MOT_DETECT_STATUS
+ * @see MPU6500_MOTION_MOT_YNEG_BIT
+ */
+bool mpu6500GetYNegMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_STATUS, MPU6500_MOTION_MOT_YNEG_BIT, buffer);
+  return buffer[0];
+}
+/** Get Y-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6500_RA_MOT_DETECT_STATUS
+ * @see MPU6500_MOTION_MOT_YPOS_BIT
+ */
+bool mpu6500GetYPosMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_STATUS, MPU6500_MOTION_MOT_YPOS_BIT, buffer);
+  return buffer[0];
+}
+/** Get Z-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6500_RA_MOT_DETECT_STATUS
+ * @see MPU6500_MOTION_MOT_ZNEG_BIT
+ */
+bool mpu6500GetZNegMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_STATUS, MPU6500_MOTION_MOT_ZNEG_BIT, buffer);
+  return buffer[0];
+}
+/** Get Z-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6500_RA_MOT_DETECT_STATUS
+ * @see MPU6500_MOTION_MOT_ZPOS_BIT
+ */
+bool mpu6500GetZPosMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_STATUS, MPU6500_MOTION_MOT_ZPOS_BIT, buffer);
+  return buffer[0];
+}
+/** Get zero motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6500_RA_MOT_DETECT_STATUS
+ * @see MPU6500_MOTION_MOT_ZRMOT_BIT
+ */
+bool mpu6500GetZeroMotionDetected()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_STATUS, MPU6500_MOTION_MOT_ZRMOT_BIT, buffer);
+  return buffer[0];
+}
+
+// I2C_SLV*_DO register
+
+/** Write byte to Data Output container for specified slave.
+ * This register holds the output data written into Slave when Slave is set to
+ * write mode. For further information regarding Slave control, please
+ * refer to Registers 37 to 39 and immediately following.
+ * @param num Slave number (0-3)
+ * @param data Byte to write
+ * @see MPU6500_RA_I2C_SLV0_DO
+ */
+void mpu6500SetSlaveOutputByte(uint8_t num, uint8_t data)
+{
+  if (num > 3)
+    return;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_I2C_SLV0_DO + num, data);
+}
+
+// I2C_MST_DELAY_CTRL register
+
+/** Get external data shadow delay enabled status.
+ * This register is used to specify the timing of external sensor data
+ * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external
+ * sensor data is delayed until all data has been received.
+ * @return Current external data shadow delay enabled status.
+ * @see MPU6500_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6500_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+bool mpu6500GetExternalShadowDelayEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_DELAY_CTRL, MPU6500_DELAYCTRL_DELAY_ES_SHADOW_BIT,
+      buffer);
+  return buffer[0];
+}
+/** Set external data shadow delay enabled status.
+ * @param enabled New external data shadow delay enabled status.
+ * @see getExternalShadowDelayEnabled()
+ * @see MPU6500_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6500_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+void mpu6500SetExternalShadowDelayEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_DELAY_CTRL,
+      MPU6500_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled);
+}
+/** Get slave delay enabled status.
+ * When a particular slave delay is enabled, the rate of access for the that
+ * slave device is reduced. When a slave's access rate is decreased relative to
+ * the Sample Rate, the slave is accessed every:
+ *
+ *     1 / (1 + I2C_MST_DLY) Samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register  * 25)
+ * and DLPF_CFG (register 26).
+ *
+ * For further information regarding I2C_MST_DLY, please refer to register 52.
+ * For further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @param num Slave number (0-4)
+ * @return Current slave delay enabled status.
+ * @see MPU6500_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6500_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+bool mpu6500GetSlaveDelayEnabled(uint8_t num)
+{
+  // MPU6500_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc.
+  if (num > 4)
+    return 0;
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_DELAY_CTRL, num, buffer);
+  return buffer[0];
+}
+/** Set slave delay enabled status.
+ * @param num Slave number (0-4)
+ * @param enabled New slave delay enabled status.
+ * @see MPU6500_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6500_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+void mpu6500SetSlaveDelayEnabled(uint8_t num, bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_I2C_MST_DELAY_CTRL, num, enabled);
+}
+
+// SIGNAL_PATH_RESET register
+
+/** Reset gyroscope signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6500_RA_SIGNAL_PATH_RESET
+ * @see MPU6500_PATHRESET_GYRO_RESET_BIT
+ */
+void mpu6500ResetGyroscopePath()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_SIGNAL_PATH_RESET, MPU6500_PATHRESET_GYRO_RESET_BIT, 1);
+}
+/** Reset accelerometer signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6500_RA_SIGNAL_PATH_RESET
+ * @see MPU6500_PATHRESET_ACCEL_RESET_BIT
+ */
+void mpu6500ResetAccelerometerPath()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_SIGNAL_PATH_RESET, MPU6500_PATHRESET_ACCEL_RESET_BIT, 1);
+}
+/** Reset temperature sensor signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6500_RA_SIGNAL_PATH_RESET
+ * @see MPU6500_PATHRESET_TEMP_RESET_BIT
+ */
+void mpu6500ResetTemperaturePath()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_SIGNAL_PATH_RESET, MPU6500_PATHRESET_TEMP_RESET_BIT, 1);
+}
+
+// MOT_DETECT_CTRL register
+
+/** Get accelerometer power-on delay.
+ * The accelerometer data path provides samples to the sensor registers, Motion
+ * detection, Zero Motion detection, and Free Fall detection modules. The
+ * signal path contains filters which must be flushed on wake-up with new
+ * samples before the detection modules begin operations. The default wake-up
+ * delay, of 4ms can be lengthened by up to 3ms. This additional delay is
+ * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select
+ * any value above zero unless instructed otherwise by InvenSense. Please refer
+ * to Section 8 of the MPU-6000/MPU-6500 Product Specification document for
+ * further information regarding the detection modules.
+ * @return Current accelerometer power-on delay
+ * @see MPU6500_RA_MOT_DETECT_CTRL
+ * @see MPU6500_DETECT_ACCEL_ON_DELAY_BIT
+ */
+uint8_t mpu6500GetAccelerometerPowerOnDelay()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_CTRL, MPU6500_DETECT_ACCEL_ON_DELAY_BIT,
+      MPU6500_DETECT_ACCEL_ON_DELAY_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set accelerometer power-on delay.
+ * @param delay New accelerometer power-on delay (0-3)
+ * @see getAccelerometerPowerOnDelay()
+ * @see MPU6500_RA_MOT_DETECT_CTRL
+ * @see MPU6500_DETECT_ACCEL_ON_DELAY_BIT
+ */
+void mpu6500SetAccelerometerPowerOnDelay(uint8_t delay)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_CTRL, MPU6500_DETECT_ACCEL_ON_DELAY_BIT,
+      MPU6500_DETECT_ACCEL_ON_DELAY_LENGTH, delay);
+}
+/** Get Free Fall detection counter decrement configuration.
+ * Detection is registered by the Free Fall detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring FF_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * </pre>
+ *
+ * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Free Fall detection,
+ * please refer to Registers 29 to 32.
+ *
+ * @return Current decrement configuration
+ * @see MPU6500_RA_MOT_DETECT_CTRL
+ * @see MPU6500_DETECT_FF_COUNT_BIT
+ */
+uint8_t mpu6500GetFreefallDetectionCounterDecrement()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_CTRL, MPU6500_DETECT_FF_COUNT_BIT,
+      MPU6500_DETECT_FF_COUNT_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set Free Fall detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getFreefallDetectionCounterDecrement()
+ * @see MPU6500_RA_MOT_DETECT_CTRL
+ * @see MPU6500_DETECT_FF_COUNT_BIT
+ */
+void mpu6500SetFreefallDetectionCounterDecrement(uint8_t decrement)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_CTRL, MPU6500_DETECT_FF_COUNT_BIT,
+      MPU6500_DETECT_FF_COUNT_LENGTH, decrement);
+}
+/** Get Motion detection counter decrement configuration.
+ * Detection is registered by the Motion detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring MOT_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * </pre>
+ *
+ * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Motion detection,
+ * please refer to Registers 29 to 32.
+ *
+ */
+uint8_t mpu6500GetMotionDetectionCounterDecrement()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_CTRL, MPU6500_DETECT_MOT_COUNT_BIT,
+      MPU6500_DETECT_MOT_COUNT_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set Motion detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getMotionDetectionCounterDecrement()
+ * @see MPU6500_RA_MOT_DETECT_CTRL
+ * @see MPU6500_DETECT_MOT_COUNT_BIT
+ */
+void mpu6500SetMotionDetectionCounterDecrement(uint8_t decrement)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_MOT_DETECT_CTRL, MPU6500_DETECT_MOT_COUNT_BIT,
+      MPU6500_DETECT_MOT_COUNT_LENGTH, decrement);
+}
+
+// USER_CTRL register
+
+/** Get FIFO enabled status.
+ * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer
+ * cannot be written to or read from while disabled. The FIFO buffer's state
+ * does not change unless the MPU-60X0 is power cycled.
+ * @return Current FIFO enabled status
+ * @see MPU6500_RA_USER_CTRL
+ * @see MPU6500_USERCTRL_FIFO_EN_BIT
+ */
+bool mpu6500GetFIFOEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_FIFO_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set FIFO enabled status.
+ * @param enabled New FIFO enabled status
+ * @see getFIFOEnabled()
+ * @see MPU6500_RA_USER_CTRL
+ * @see MPU6500_USERCTRL_FIFO_EN_BIT
+ */
+void mpu6500SetFIFOEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_FIFO_EN_BIT, enabled);
+}
+/** Get I2C Master Mode enabled status.
+ * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the
+ * external sensor slave devices on the auxiliary I2C bus. When this bit is
+ * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically
+ * driven by the primary I2C bus (SDA and SCL). This is a precondition to
+ * enabling Bypass Mode. For further information regarding Bypass Mode, please
+ * refer to Register 55.
+ * @return Current I2C Master Mode enabled status
+ * @see MPU6500_RA_USER_CTRL
+ * @see MPU6500_USERCTRL_I2C_MST_EN_BIT
+ */
+bool mpu6500GetI2CMasterModeEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_I2C_MST_EN_BIT, buffer);
+  return buffer[0];
+}
+/** Set I2C Master Mode enabled status.
+ * @param enabled New I2C Master Mode enabled status
+ * @see getI2CMasterModeEnabled()
+ * @see MPU6500_RA_USER_CTRL
+ * @see MPU6500_USERCTRL_I2C_MST_EN_BIT
+ */
+void mpu6500SetI2CMasterModeEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_I2C_MST_EN_BIT, enabled);
+}
+/** Switch from I2C to SPI mode (MPU-6000 only)
+ * If this is set, the primary SPI interface will be enabled in place of the
+ * disabled primary I2C interface.
+ */
+void mpu6500SwitchSPIEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_I2C_IF_DIS_BIT, enabled);
+}
+/** Reset the FIFO.
+ * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This
+ * bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6500_RA_USER_CTRL
+ * @see MPU6500_USERCTRL_FIFO_RESET_BIT
+ */
+void mpu6500ResetFIFO()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_FIFO_RESET_BIT, 1);
+}
+/** Reset the I2C Master.
+ * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0.
+ * This bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6500_RA_USER_CTRL
+ * @see MPU6500_USERCTRL_I2C_MST_RESET_BIT
+ */
+void mpu6500ResetI2CMaster()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_I2C_MST_RESET_BIT, 1);
+}
+/** Reset all sensor registers and signal paths.
+ * When set to 1, this bit resets the signal paths for all sensors (gyroscopes,
+ * accelerometers, and temperature sensor). This operation will also clear the
+ * sensor registers. This bit automatically clears to 0 after the reset has been
+ * triggered.
+ *
+ * When resetting only the signal path (and not the sensor registers), please
+ * use Register 104, SIGNAL_PATH_RESET.
+ *
+ * @see MPU6500_RA_USER_CTRL
+ * @see MPU6500_USERCTRL_SIG_COND_RESET_BIT
+ */
+void mpu6500ResetSensors()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_SIG_COND_RESET_BIT, 1);
+}
+
+// PWR_MGMT_1 register
+
+/** Trigger a full device reset.
+ * A small delay of ~50ms may be desirable after triggering a reset.
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_DEVICE_RESET_BIT
+ */
+void mpu6500Reset()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_DEVICE_RESET_BIT, 1);
+}
+/** Get sleep mode status.
+ * Setting the SLEEP bit in the register puts the device into very low power
+ * sleep mode. In this mode, only the serial interface and internal registers
+ * remain active, allowing for a very low standby current. Clearing this bit
+ * puts the device back into normal mode. To save power, the individual standby
+ * selections for each of the gyros should be used if any gyro axis is not used
+ * by the application.
+ * @return Current sleep mode enabled status
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_SLEEP_BIT
+ */
+bool mpu6500GetSleepEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_SLEEP_BIT, buffer);
+  return buffer[0];
+}
+/** Set sleep mode status.
+ * @param enabled New sleep mode enabled status
+ * @see getSleepEnabled()
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_SLEEP_BIT
+ */
+void mpu6500SetSleepEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_SLEEP_BIT, enabled);
+}
+/** Get wake cycle enabled status.
+ * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle
+ * between sleep mode and waking up to take a single sample of data from active
+ * sensors at a rate determined by LP_WAKE_CTRL (register 108).
+ * @return Current sleep mode enabled status
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_CYCLE_BIT
+ */
+bool mpu6500GetWakeCycleEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_CYCLE_BIT, buffer);
+  return buffer[0];
+}
+/** Set wake cycle enabled status.
+ * @param enabled New sleep mode enabled status
+ * @see getWakeCycleEnabled()
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_CYCLE_BIT
+ */
+void mpu6500SetWakeCycleEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_CYCLE_BIT, enabled);
+}
+/** Get temperature sensor enabled status.
+ * Control the usage of the internal temperature sensor.
+ *
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @return Current temperature sensor enabled status
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_TEMP_DIS_BIT
+ */
+bool mpu6500GetTempSensorEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_TEMP_DIS_BIT, buffer);
+  return buffer[0] == 0; // 1 is actually disabled here
+}
+/** Set temperature sensor enabled status.
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @param enabled New temperature sensor enabled status
+ * @see getTempSensorEnabled()
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_TEMP_DIS_BIT
+ */
+void mpu6500SetTempSensorEnabled(bool enabled)
+{
+  // 1 is actually disabled here
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_TEMP_DIS_BIT, !enabled);
+}
+/** Get clock source setting.
+ * @return Current clock source setting
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_CLKSEL_BIT
+ * @see MPU6500_PWR1_CLKSEL_LENGTH
+ */
+uint8_t mpu6500GetClockSource()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_CLKSEL_BIT,
+      MPU6500_PWR1_CLKSEL_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set clock source setting.
+ * An internal 8MHz oscillator, gyroscope based clock, or external sources can
+ * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator
+ * or an external source is chosen as the clock source, the MPU-60X0 can operate
+ * in low power modes with the gyroscopes disabled.
+ *
+ * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator.
+ * However, it is highly recommended that the device be configured to use one of
+ * the gyroscopes (or an external clock source) as the clock reference for
+ * improved stability. The clock source can be selected according to the following table:
+ *
+ * <pre>
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0       | Internal oscillator
+ * 1       | PLL with X Gyro reference
+ * 2       | PLL with Y Gyro reference
+ * 3       | PLL with Z Gyro reference
+ * 4       | PLL with external 32.768kHz reference
+ * 5       | PLL with external 19.2MHz reference
+ * 6       | Reserved
+ * 7       | Stops the clock and keeps the timing generator in reset
+ * </pre>
+ *
+ * @param source New clock source setting
+ * @see getClockSource()
+ * @see MPU6500_RA_PWR_MGMT_1
+ * @see MPU6500_PWR1_CLKSEL_BIT
+ * @see MPU6500_PWR1_CLKSEL_LENGTH
+ */
+void mpu6500SetClockSource(uint8_t source)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_1, MPU6500_PWR1_CLKSEL_BIT,
+      MPU6500_PWR1_CLKSEL_LENGTH, source);
+}
+
+// PWR_MGMT_2 register
+
+/** Get wake frequency in Accel-Only Low Power Mode.
+ * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting
+ * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode,
+ * the device will power off all devices except for the primary I2C interface,
+ * waking only the accelerometer at fixed intervals to take a single
+ * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL
+ * as shown below:
+ *
+ * <pre>
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * <pre>
+ *
+ * For further information regarding the MPU-60X0's power modes, please refer to
+ * Register 107.
+ *
+ * @return Current wake frequency
+ * @see MPU6500_RA_PWR_MGMT_2
+ */
+uint8_t mpu6500GetWakeFrequency()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_LP_WAKE_CTRL_BIT,
+      MPU6500_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+  return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU6500_RA_PWR_MGMT_2
+ */
+void mpu6500SetWakeFrequency(uint8_t frequency)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_LP_WAKE_CTRL_BIT,
+      MPU6500_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
+}
+
+/** Get X-axis accelerometer standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_XA_BIT
+ */
+bool mpu6500GetStandbyXAccelEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_XA_BIT, buffer);
+  return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_XA_BIT
+ */
+void mpu6500SetStandbyXAccelEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_XA_BIT, enabled);
+}
+/** Get Y-axis accelerometer standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_YA_BIT
+ */
+bool mpu6500GetStandbyYAccelEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_YA_BIT, buffer);
+  return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_YA_BIT
+ */
+void mpu6500SetStandbyYAccelEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_YA_BIT, enabled);
+}
+/** Get Z-axis accelerometer standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_ZA_BIT
+ */
+bool mpu6500GetStandbyZAccelEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_ZA_BIT, buffer);
+  return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_ZA_BIT
+ */
+void mpu6500SetStandbyZAccelEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_ZA_BIT, enabled);
+}
+/** Get X-axis gyroscope standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_XG_BIT
+ */
+bool mpu6500GetStandbyXGyroEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_XG_BIT, buffer);
+  return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_XG_BIT
+ */
+void mpu6500SetStandbyXGyroEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_XG_BIT, enabled);
+}
+/** Get Y-axis gyroscope standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_YG_BIT
+ */
+bool mpu6500GetStandbyYGyroEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_YG_BIT, buffer);
+  return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_YG_BIT
+ */
+void mpu6500SetStandbyYGyroEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_YG_BIT, enabled);
+}
+/** Get Z-axis gyroscope standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_ZG_BIT
+ */
+bool mpu6500GetStandbyZGyroEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_ZG_BIT, buffer);
+  return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU6500_RA_PWR_MGMT_2
+ * @see MPU6500_PWR2_STBY_ZG_BIT
+ */
+void mpu6500SetStandbyZGyroEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_PWR_MGMT_2, MPU6500_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t mpu6500GetFIFOCount()
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_FIFO_COUNTH, 2, buffer);
+  return (((uint16_t) buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t mpu6500GetFIFOByte()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_FIFO_R_W, buffer);
+  return buffer[0];
+}
+void mpu6500GetFIFOBytes(uint8_t *data, uint8_t length)
+{
+  i2cdevRead(I2Cx, devAddr, MPU6500_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU6500_RA_FIFO_R_W
+ */
+void mpu6500SetFIFOByte(uint8_t data)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_FIFO_R_W, data);
+}
+
+// WHO_AM_I register
+
+/** Get Device ID.
+ * This register is used to verify the identity of the device (0b110100).
+ * @return Device ID (should be 0x68, 104 dec, 150 oct)
+ * @see MPU6500_RA_WHO_AM_I
+ * @see MPU6500_WHO_AM_I_BIT
+ * @see MPU6500_WHO_AM_I_LENGTH
+ */
+uint8_t mpu6500GetDeviceID()
+{
+  i2cdevReadBits(I2Cx, devAddr, MPU6500_RA_WHO_AM_I, MPU6500_WHO_AM_I_BIT, MPU6500_WHO_AM_I_LENGTH,
+      buffer);
+  return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU6500_RA_WHO_AM_I
+ * @see MPU6500_WHO_AM_I_BIT
+ * @see MPU6500_WHO_AM_I_LENGTH
+ */
+void mpu6500SetDeviceID(uint8_t id)
+{
+  i2cdevWriteBits(I2Cx, devAddr, MPU6500_RA_WHO_AM_I, MPU6500_WHO_AM_I_BIT, MPU6500_WHO_AM_I_LENGTH,
+      id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_USR* registers
+
+// INT_ENABLE register (DMP functions)
+
+bool mpu6500GetIntPLLReadyEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+  return buffer[0];
+}
+void mpu6500SetIntPLLReadyEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool mpu6500GetIntDMPEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_DMP_INT_BIT, buffer);
+  return buffer[0];
+}
+void mpu6500SetIntDMPEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, MPU6500_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool mpu6500GetDMPInt5Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_DMP_INT_STATUS, MPU6500_DMPINT_5_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6500GetDMPInt4Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_DMP_INT_STATUS, MPU6500_DMPINT_4_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6500GetDMPInt3Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_DMP_INT_STATUS, MPU6500_DMPINT_3_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6500GetDMPInt2Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_DMP_INT_STATUS, MPU6500_DMPINT_2_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6500GetDMPInt1Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_DMP_INT_STATUS, MPU6500_DMPINT_1_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6500GetDMPInt0Status()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_DMP_INT_STATUS, MPU6500_DMPINT_0_BIT, buffer);
+  return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool mpu6500GetIntPLLReadyStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+  return buffer[0];
+}
+bool mpu6500GetIntDMPStatus()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_INT_STATUS, MPU6500_INTERRUPT_DMP_INT_BIT, buffer);
+  return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool mpu6500GetDMPEnabled()
+{
+  i2cdevReadBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_DMP_EN_BIT, buffer);
+  return buffer[0];
+}
+void mpu6500SetDMPEnabled(bool enabled)
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_DMP_EN_BIT, enabled);
+}
+void mpu6500ResetDMP()
+{
+  i2cdevWriteBit(I2Cx, devAddr, MPU6500_RA_USER_CTRL, MPU6500_USERCTRL_DMP_RESET_BIT, 1);
+}
+
+// BANK_SEL register
+
+void mpu6500SetMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank)
+{
+  bank &= 0x1F;
+  if (userBank)
+    bank |= 0x20;
+  if (prefetchEnabled)
+    bank |= 0x40;
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void mpu6500SetMemoryStartAddress(uint8_t address)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t mpu6500ReadMemoryByte()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_MEM_R_W, buffer);
+  return buffer[0];
+}
+void mpu6500WriteMemoryByte(uint8_t data)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_MEM_R_W, data);
+}
+void mpu6500ReadMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address)
+{
+  mpu6500SetMemoryBank(bank, true, true);
+  mpu6500SetMemoryStartAddress(address);
+  uint8_t chunkSize;
+  uint16_t i;
+
+  for (i = 0; i < dataSize;)
+  {
+    // determine correct chunk size according to bank position and data size
+    chunkSize = MPU6500_DMP_MEMORY_CHUNK_SIZE;
+
+    // make sure we don't go past the data size
+    if (i + chunkSize > dataSize)
+      chunkSize = dataSize - i;
+
+    // make sure this chunk doesn't go past the bank boundary (256 bytes)
+    if (chunkSize > 256 - address)
+      chunkSize = 256 - address;
+
+    // read the chunk of data as specified
+    i2cdevRead(I2Cx, devAddr, MPU6500_RA_MEM_R_W, chunkSize, data + i);
+
+    // increase byte index by [chunkSize]
+    i += chunkSize;
+
+    // uint8_t automatically wraps to 0 at 256
+    address += chunkSize;
+
+    // if we aren't done, update bank (if necessary) and address
+    if (i < dataSize)
+    {
+      if (address == 0)
+        bank++;
+      mpu6500SetMemoryBank(bank, true, true);
+      mpu6500SetMemoryStartAddress(address);
+    }
+  }
+}
+bool mpu6500WriteMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address,
+    bool verify)
+{
+  static uint8_t verifyBuffer[MPU6500_DMP_MEMORY_CHUNK_SIZE];
+  uint8_t chunkSize;
+  uint8_t *progBuffer;
+  uint16_t i;
+
+  mpu6500SetMemoryBank(bank, true, true);
+  mpu6500SetMemoryStartAddress(address);
+
+  for (i = 0; i < dataSize;)
+  {
+    // determine correct chunk size according to bank position and data size
+    chunkSize = MPU6500_DMP_MEMORY_CHUNK_SIZE;
+
+    // make sure we don't go past the data size
+    if (i + chunkSize > dataSize)
+      chunkSize = dataSize - i;
+
+    // make sure this chunk doesn't go past the bank boundary (256 bytes)
+    if (chunkSize > 256 - address)
+      chunkSize = 256 - address;
+
+    // write the chunk of data as specified
+    progBuffer = (uint8_t *) data + i;
+
+    i2cdevWrite(I2Cx, devAddr, MPU6500_RA_MEM_R_W, chunkSize, progBuffer);
+
+    // verify data if needed
+    if (verify)
+    {
+      uint32_t j;
+      mpu6500SetMemoryBank(bank, true, true);
+      mpu6500SetMemoryStartAddress(address);
+      i2cdevRead(I2Cx, devAddr, MPU6500_RA_MEM_R_W, chunkSize, verifyBuffer);
+
+      for (j = 0; j < chunkSize; j++)
+      {
+        if (progBuffer[j] != verifyBuffer[j])
+        {
+          /*Serial.print("Block write verification error, bank ");
+           Serial.print(bank, DEC);
+           Serial.print(", address ");
+           Serial.print(address, DEC);
+           Serial.print("!\nExpected:");
+           for (j = 0; j < chunkSize; j++) {
+           Serial.print(" 0x");
+           if (progBuffer[j] < 16) Serial.print("0");
+           Serial.print(progBuffer[j], HEX);
+           }
+           Serial.print("\nReceived:");
+           for (uint8_t j = 0; j < chunkSize; j++) {
+           Serial.print(" 0x");
+           if (verifyBuffer[i + j] < 16) Serial.print("0");
+           Serial.print(verifyBuffer[i + j], HEX);
+           }
+           Serial.print("\n");*/
+          return false;
+        }
+      }
+    }
+
+    // increase byte index by [chunkSize]
+    i += chunkSize;
+
+    // uint8_t automatically wraps to 0 at 256
+    address += chunkSize;
+
+    // if we aren't done, update bank (if necessary) and address
+    if (i < dataSize)
+    {
+      if (address == 0)
+        bank++;
+      mpu6500SetMemoryBank(bank, true, true);
+      mpu6500SetMemoryStartAddress(address);
+    }
+  }
+  return true;
+}
+bool mpu6500WriteProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank,
+    uint8_t address, bool verify)
+{
+  return mpu6500WriteMemoryBlock(data, dataSize, bank, address, verify);
+}
+#define MPU6500_DMP_CONFIG_BLOCK_SIZE 6
+bool mpu6500WriteDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
+{
+  uint8_t *progBuffer, success, special;
+  uint16_t i;
+
+  // config set data is a long string of blocks with the following structure:
+  // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+  uint8_t bank=0;
+  uint8_t offset=0;
+  uint8_t length=0;
+  for (i = 0; i < dataSize;)
+  {
+    bank = data[i++];
+    offset = data[i++];
+    length = data[i++];
+  }
+
+  // write data or perform special action
+  if (length > 0)
+  {
+    // regular block of data to write
+    /*Serial.print("Writing config block to bank ");
+     Serial.print(bank);
+     Serial.print(", offset ");
+     Serial.print(offset);
+     Serial.print(", length=");
+     Serial.println(length);*/
+    progBuffer = (uint8_t *) data + i;
+    success = mpu6500WriteMemoryBlock(progBuffer, length, bank, offset, true);
+    i += length;
+  }
+  else
+  {
+    // special instruction
+    // NOTE: this kind of behavior (what and when to do certain things)
+    // is totally undocumented. This code is in here based on observed
+    // behavior only, and exactly why (or even whether) it has to be here
+    // is anybody's guess for now.
+    special = data[i++];
+    /*Serial.print("Special command code ");
+     Serial.print(special, HEX);
+     Serial.println(" found...");*/
+    if (special == 0x01)
+    {
+      // enable DMP-related interrupts
+      mpu6500SetIntZeroMotionEnabled(true);
+      mpu6500SetIntFIFOBufferOverflowEnabled(true);
+      mpu6500SetIntDMPEnabled(true);
+      //i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_INT_ENABLE, 0x32);
+      success = true;
+    }
+    else
+    {
+      // unknown special command
+      success = false;
+    }
+  }
+
+  if (!success)
+  {
+    return false; // uh oh
+  }
+  return true;
+}
+
+bool mpu6500WriteProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
+{
+  return mpu6500WriteDMPConfigurationSet(data, dataSize);
+}
+
+// DMP_CFG_1 register
+
+uint8_t mpu6500GetDMPConfig1()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_DMP_CFG_1, buffer);
+  return buffer[0];
+}
+void mpu6500SetDMPConfig1(uint8_t config)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t mpu6500GetDMPConfig2()
+{
+  i2cdevReadByte(I2Cx, devAddr, MPU6500_RA_DMP_CFG_2, buffer);
+  return buffer[0];
+}
+void mpu6500SetDMPConfig2(uint8_t config)
+{
+  i2cdevWriteByte(I2Cx, devAddr, MPU6500_RA_DMP_CFG_2, config);
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/ms5611.c b/crazyflie-firmware-src/src/drivers/src/ms5611.c
new file mode 100644
index 0000000000000000000000000000000000000000..041152f8c07a58d736d8ca923691e262a5344a0b
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/ms5611.c
@@ -0,0 +1,403 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011 Fabio Varesano <fvaresano@yahoo.it>
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file ms5611.c
+ * Driver for the ms5611 pressure sensor from measurement specialties.
+ * Datasheet at http://www.meas-spec.com/downloads/MS5611-01BA03.pdf
+ *
+ */
+#define DEBUG_MODULE "MS5611"
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "ms5611.h"
+#include "i2cdev.h"
+#include "debug.h"
+#include "eprintf.h"
+
+#include "math.h"
+
+#define EXTRA_PRECISION      5 // trick to add more precision to the pressure and temp readings
+#define CONVERSION_TIME_MS   10 // conversion time in milliseconds. 10 is minimum
+#define PRESSURE_PER_TEMP 5 // Length of reading cycle: 1x temp, rest pressure. Good values: 1-10
+#define FIX_TEMP 25         // Fixed Temperature. ASL is a function of pressure and temperature, but as the temperature changes so much (blow a little towards the flie and watch it drop 5 degrees) it corrupts the ASL estimates.
+                            // TLDR: Adjusting for temp changes does more harm than good.
+
+typedef struct
+{
+  uint16_t psens;
+  uint16_t off;
+  uint16_t tcs;
+  uint16_t tco;
+  uint16_t tref;
+  uint16_t tsens;
+} CalReg;
+
+static uint8_t devAddr;
+static I2C_Dev *I2Cx;
+static bool isInit;
+
+static CalReg   calReg;
+static uint32_t lastPresConv;
+static uint32_t lastTempConv;
+static int32_t  tempCache;
+
+static uint8_t readState=0;
+static uint32_t lastConv=0;
+static int32_t tempDeltaT;
+
+bool ms5611Init(I2C_Dev *i2cPort)
+{
+  if (isInit)
+    return true;
+
+  I2Cx = i2cPort;
+  devAddr = MS5611_ADDR_CSB_LOW;
+
+  ms5611Reset(); // reset the device to populate its internal PROM registers
+  vTaskDelay(M2T(5));
+  if (ms5611ReadPROM() == false) // reads the PROM into object variables for later use
+  {
+    return false;
+  }
+
+  isInit = true;
+
+  return true;
+}
+
+bool ms5611SelfTest(void)
+{
+  bool testStatus = true;
+  int32_t rawPress;
+  int32_t rawTemp;
+  int32_t deltaT;
+  float pressure;
+  float temperature;
+
+  if (!isInit)
+    return false;
+
+  ms5611StartConversion(MS5611_D1 + MS5611_OSR_4096);
+  vTaskDelay(M2T(CONVERSION_TIME_MS));
+  rawPress = ms5611GetConversion(MS5611_D1 + MS5611_OSR_4096);
+
+  ms5611StartConversion(MS5611_D2 + MS5611_OSR_4096);
+  vTaskDelay(M2T(CONVERSION_TIME_MS));
+  rawTemp = ms5611GetConversion(MS5611_D2 + MS5611_OSR_4096);
+
+  deltaT = ms5611CalcDeltaTemp(rawTemp);
+  temperature = ms5611CalcTemp(deltaT);
+  pressure = ms5611CalcPressure(rawPress, deltaT);
+
+  if (ms5611EvaluateSelfTest(MS5611_ST_PRESS_MIN, MS5611_ST_PRESS_MAX, pressure, "pressure") &&
+      ms5611EvaluateSelfTest(MS5611_ST_TEMP_MIN, MS5611_ST_TEMP_MAX, temperature, "temperature"))
+  {
+    DEBUG_PRINT("Self test [OK].\n");
+  }
+  else
+  {
+   testStatus = false;
+  }
+
+  return testStatus;
+}
+
+bool ms5611EvaluateSelfTest(float min, float max, float value, char* string)
+{
+  if (value < min || value > max)
+  {
+    DEBUG_PRINT("Self test %s [FAIL]. low: %0.2f, high: %0.2f, measured: %0.2f\n",
+                string, min, max, value);
+    return false;
+  }
+  return true;
+}
+
+float ms5611GetPressure(uint8_t osr)
+{
+  // see datasheet page 7 for formulas
+  int32_t rawPress = ms5611RawPressure(osr);
+  int64_t dT = (int64_t)ms5611GetDeltaTemp(osr);
+  if (dT == 0)
+  {
+    return 0;
+  }
+  int64_t off = (((int64_t)calReg.off) << 16) + ((calReg.tco * dT) >> 7);
+  int64_t sens = (((int64_t)calReg.psens) << 15) + ((calReg.tcs * dT) >> 8);
+  if (rawPress != 0)
+  {
+    return ((((rawPress * sens) >> 21) - off) >> (15 - EXTRA_PRECISION))
+        / ((1 << EXTRA_PRECISION) * 100.0);
+  }
+  else
+  {
+    return 0;
+  }
+}
+
+float ms5611CalcPressure(int32_t rawPress, int32_t dT)
+{
+  int64_t off;
+  int64_t sens;
+
+  if (rawPress == 0 || dT == 0)
+  {
+    return 0;
+  }
+
+  off = (((int64_t)calReg.off) << 16) + ((calReg.tco * (int64_t)dT) >> 7);
+  sens = (((int64_t)calReg.psens) << 15) + ((calReg.tcs * (int64_t)dT) >> 8);
+
+  return ((((rawPress * sens) >> 21) - off) >> (15 - EXTRA_PRECISION))
+          / ((1 << EXTRA_PRECISION) * 100.0);
+}
+
+float ms5611GetTemperature(uint8_t osr)
+{
+  // see datasheet page 7 for formulas
+  int32_t dT;
+
+  dT = ms5611GetDeltaTemp(osr);
+  if (dT != 0)
+  {
+    return ms5611CalcTemp(dT);
+  }
+  else
+  {
+    return 0;
+  }
+}
+
+int32_t ms5611GetDeltaTemp(uint8_t osr)
+{
+  int32_t rawTemp = ms5611RawTemperature(osr);
+  if (rawTemp != 0)
+  {
+    return ms5611CalcDeltaTemp(rawTemp);
+  }
+  else
+  {
+    return 0;
+  }
+}
+
+float ms5611CalcTemp(int32_t deltaT)
+{
+  if (deltaT == 0)
+  {
+    return 0;
+  }
+  else
+  {
+    return (float)(((1 << EXTRA_PRECISION) * 2000)
+            + (((int64_t)deltaT * calReg.tsens) >> (23 - EXTRA_PRECISION)))
+            / ((1 << EXTRA_PRECISION)* 100.0);
+  }
+}
+
+int32_t ms5611CalcDeltaTemp(int32_t rawTemp)
+{
+  if (rawTemp == 0)
+  {
+    return 0;
+  }
+  else
+  {
+    return rawTemp - (((int32_t)calReg.tref) << 8);
+  }
+}
+
+int32_t ms5611RawPressure(uint8_t osr)
+{
+  uint32_t now = xTaskGetTickCount();
+  if (lastPresConv != 0 && (now - lastPresConv) >= CONVERSION_TIME_MS)
+  {
+    lastPresConv = 0;
+    return ms5611GetConversion(MS5611_D1 + osr);
+  }
+  else
+  {
+    if (lastPresConv == 0 && lastTempConv == 0)
+    {
+      ms5611StartConversion(MS5611_D1 + osr);
+      lastPresConv = now;
+    }
+    return 0;
+  }
+}
+
+int32_t ms5611RawTemperature(uint8_t osr)
+{
+  uint32_t now = xTaskGetTickCount();
+  if (lastTempConv != 0 && (now - lastTempConv) >= CONVERSION_TIME_MS)
+  {
+    lastTempConv = 0;
+    tempCache = ms5611GetConversion(MS5611_D2 + osr);
+    return tempCache;
+  }
+  else
+  {
+    if (lastTempConv == 0 && lastPresConv == 0)
+    {
+      ms5611StartConversion(MS5611_D2 + osr);
+      lastTempConv = now;
+    }
+    return tempCache;
+  }
+}
+
+// see page 11 of the datasheet
+void ms5611StartConversion(uint8_t command)
+{
+  // initialize pressure conversion
+  i2cdevWriteByte(I2Cx, devAddr, I2CDEV_NO_MEM_ADDR, command);
+}
+
+int32_t ms5611GetConversion(uint8_t command)
+{
+  int32_t conversion = 0;
+  uint8_t buffer[MS5611_D1D2_SIZE];
+
+  // start read sequence
+  i2cdevWriteByte(I2Cx, devAddr, I2CDEV_NO_MEM_ADDR, 0);
+  // Read conversion
+  i2cdevRead(I2Cx, devAddr, I2CDEV_NO_MEM_ADDR, MS5611_D1D2_SIZE, buffer);
+  conversion = ((int32_t)buffer[0] << 16) |
+               ((int32_t)buffer[1] << 8) | buffer[2];
+
+  return conversion;
+}
+
+/**
+ * Reads factory calibration and store it into object variables.
+ */
+bool ms5611ReadPROM()
+{
+  uint8_t buffer[MS5611_PROM_REG_SIZE];
+  uint16_t* pCalRegU16 = (uint16_t*)&calReg;
+  int32_t i = 0;
+  bool status = false;
+
+  for (i = 0; i < MS5611_PROM_REG_COUNT; i++)
+  {
+    // start read sequence
+    status = i2cdevWriteByte(I2Cx, devAddr, I2CDEV_NO_MEM_ADDR,
+                             MS5611_PROM_BASE_ADDR + (i * MS5611_PROM_REG_SIZE));
+    // Read conversion
+    if (status)
+    {
+      status = i2cdevRead(I2Cx, devAddr, I2CDEV_NO_MEM_ADDR, MS5611_PROM_REG_SIZE, buffer);
+      pCalRegU16[i] = ((uint16_t)buffer[0] << 8) | buffer[1];
+    }
+  }
+
+  return status;
+}
+
+/**
+ * Send a reset command to the device. With the reset command the device
+ * populates its internal registers with the values read from the PROM.
+ */
+void ms5611Reset()
+{
+  i2cdevWriteByte(I2Cx, devAddr, I2CDEV_NO_MEM_ADDR, MS5611_RESET);
+}
+
+
+
+
+/**
+ * Gets pressure, temperature and above sea level altitude estimate (asl).
+ * Best called at 100hz. For every PRESSURE_PER_TEMP-1 pressure readings temp is read once.
+ * Effective 50-90hz baro update and 50-10hz temperature update if called at 100hz.
+ */
+void ms5611GetData(float* pressure, float* temperature, float* asl)
+{
+    int32_t tempPressureRaw, tempTemperatureRaw;
+    static float savedPress, savedTemp;
+
+    // Dont reader faster than we can
+    uint32_t now = xTaskGetTickCount();
+    if ((now - lastConv) < CONVERSION_TIME_MS)
+    {
+      *pressure = savedPress;
+      *temperature = savedTemp;
+      return;
+    }
+    lastConv = now;
+
+    if (readState == 0)
+    {
+        // read temp
+        ++readState;
+        tempTemperatureRaw = ms5611GetConversion(MS5611_D2 + MS5611_OSR_DEFAULT);
+        tempDeltaT = ms5611CalcDeltaTemp(tempTemperatureRaw);
+        *temperature = ms5611CalcTemp(tempDeltaT);
+        savedTemp = *temperature;
+        *pressure = savedPress;
+        // cmd to read pressure
+        ms5611StartConversion(MS5611_D1 + MS5611_OSR_DEFAULT);
+    }
+    else
+    {
+        // read pressure
+        ++readState;
+        tempPressureRaw = ms5611GetConversion(MS5611_D1 + MS5611_OSR_DEFAULT);
+        *pressure = ms5611CalcPressure(tempPressureRaw, tempDeltaT);
+        savedPress = *pressure;
+        *asl = ms5611PressureToAltitude(pressure);
+        *temperature = savedTemp;
+        if (readState == PRESSURE_PER_TEMP){
+            // cmd to read temp
+            ms5611StartConversion(MS5611_D2 + MS5611_OSR_DEFAULT);
+            readState = 0;
+        }
+        else
+        {
+            // cmd to read pressure
+            ms5611StartConversion(MS5611_D1 + MS5611_OSR_DEFAULT);
+        }
+    }
+}
+
+//TODO: pretty expensive function. Rather smooth the pressure estimates and only call this when needed
+
+/**
+ * Converts pressure to altitude above sea level (ASL) in meters
+ */
+float ms5611PressureToAltitude(float* pressure/*, float* ground_pressure, float* ground_temp*/)
+{
+    if (*pressure > 0)
+    {
+        //return (1.f - pow(*pressure / CONST_SEA_PRESSURE, CONST_PF)) * CONST_PF2;
+        //return ((pow((1015.7 / *pressure), CONST_PF) - 1.0) * (25. + 273.15)) / 0.0065;
+        return ((pow((1015.7 / *pressure), CONST_PF) - 1.0) * (FIX_TEMP + 273.15)) / 0.0065;
+    }
+    else
+    {
+        return 0;
+    }
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/nrf24l01.c b/crazyflie-firmware-src/src/drivers/src/nrf24l01.c
new file mode 100644
index 0000000000000000000000000000000000000000..c50d3fa5c30fa6b3ed9381c92fd961da2b3ccb21
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/nrf24l01.c
@@ -0,0 +1,435 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nrf24l01.c: nRF24L01(-p) PRX mode low level driver
+ */
+
+/* TODO:
+ *  - Separate the SPI and GPIO driver from here.
+ *  - Handle PTX mode
+ */
+#define DEBUG_MODULE "NRF"
+
+#include "nrf24l01.h"
+
+#include <stdbool.h>
+#include <string.h>
+
+#include "cfassert.h"
+
+/* ST includes */
+#include "stm32fxxx.h"
+
+#include "debug.h"
+#include "exti.h"
+
+#include "nRF24L01reg.h"
+
+/* Defines for the SPI and GPIO pins used to drive the SPI Flash */
+#define RADIO_GPIO_CS             GPIO_Pin_12
+#define RADIO_GPIO_CS_PORT        GPIOB
+#define RADIO_GPIO_CS_PERIF       RCC_APB2Periph_GPIOB
+
+#define RADIO_GPIO_CLK            GPIO_Pin_8
+#define RADIO_GPIO_CLK_PORT       GPIOA
+#define RADIO_GPIO_CLK_PERIF      RCC_APB2Periph_GPIOA
+
+#define RADIO_GPIO_CE             GPIO_Pin_10
+#define RADIO_GPIO_CE_PORT        GPIOA
+#define RADIO_GPIO_CE_PERIF       RCC_APB2Periph_GPIOA
+
+#define RADIO_GPIO_IRQ            GPIO_Pin_9
+#define RADIO_GPIO_IRQ_PORT       GPIOA
+#define RADIO_GPIO_IRQ_PERIF      RCC_APB2Periph_GPIOA
+#define RADIO_GPIO_IRQ_SRC_PORT   GPIO_PortSourceGPIOA
+#define RADIO_GPIO_IRQ_SRC        GPIO_PinSource9
+#define RADIO_GPIO_IRQ_LINE       EXTI_Line9
+
+#define RADIO_SPI                 SPI2
+#define RADIO_SPI_CLK             RCC_APB1Periph_SPI2
+#define RADIO_GPIO_SPI_PORT       GPIOB
+#define RADIO_GPIO_SPI_CLK        RCC_APB2Periph_GPIOB
+#define RADIO_GPIO_SPI_SCK        GPIO_Pin_13
+#define RADIO_GPIO_SPI_MISO       GPIO_Pin_14
+#define RADIO_GPIO_SPI_MOSI       GPIO_Pin_15
+
+#define DUMMY_BYTE    0xA5
+
+/* nRF24L SPI commands */
+#define CMD_R_REG              0x00
+#define CMD_W_REG              0x20
+#define CMD_R_RX_PAYLOAD       0x61
+#define CMD_W_TX_PAYLOAD       0xA0
+#define CMD_FLUSH_TX           0xE1
+#define CMD_FLUSH_RX           0xE2
+#define CMD_REUSE_TX_PL        0xE3
+#define CMD_ACTIVATE           0x50
+#define CMD_RX_PL_WID          0x60
+#define CMD_W_ACK_PAYLOAD(P)  (0xA8|(P&0x0F))
+#define CMD_W_PAYLOAD_NO_ACK   0xD0
+#define CMD_NOP                0xFF
+
+/* Usefull macro */
+#define RADIO_EN_CS() GPIO_ResetBits(RADIO_GPIO_CS_PORT, RADIO_GPIO_CS)
+#define RADIO_DIS_CS() GPIO_SetBits(RADIO_GPIO_CS_PORT, RADIO_GPIO_CS)
+#define RADIO_DIS_CE() GPIO_ResetBits(RADIO_GPIO_CE_PORT, RADIO_GPIO_CE)
+#define RADIO_EN_CE() GPIO_SetBits(RADIO_GPIO_CE_PORT, RADIO_GPIO_CE)
+#define ACTIVATE_DATA   0x73
+
+/* Private variables */
+static bool isInit;
+static void (*interruptCb)(void) = NULL;
+
+/***********************
+ * SPI private methods *
+ ***********************/
+static char spiSendByte(char byte)
+{
+  /* Loop while DR register in not emplty */
+  while (SPI_I2S_GetFlagStatus(RADIO_SPI, SPI_I2S_FLAG_TXE) == RESET);
+
+  /* Send byte through the SPI1 peripheral */
+  SPI_I2S_SendData(RADIO_SPI, byte);
+
+  /* Wait to receive a byte */
+  while (SPI_I2S_GetFlagStatus(RADIO_SPI, SPI_I2S_FLAG_RXNE) == RESET);
+
+  /* Return the byte read from the SPI bus */
+  return SPI_I2S_ReceiveData(RADIO_SPI);
+}
+
+static char spiReceiveByte()
+{
+  return spiSendByte(DUMMY_BYTE);
+}
+
+/****************************************************************
+ * nRF SPI commands, Every commands return the status byte      *
+ ****************************************************************/
+
+/* Read len bytes from a nRF24L register. 5 Bytes max */
+unsigned char nrfReadReg(unsigned char address, char *buffer, int len)
+{
+  unsigned char status;
+  int i;
+
+  RADIO_EN_CS();
+
+  /* Send the read command with the address */
+  status = spiSendByte( CMD_R_REG | (address&0x1F) );
+  /* Read LEN bytes */
+  for(i=0; i<len; i++)
+    buffer[i]=spiReceiveByte();
+
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+/* Write len bytes a nRF24L register. 5 Bytes max */
+unsigned char nrfWriteReg(unsigned char address, char *buffer, int len)
+{
+  unsigned char status;
+  int i;
+
+  RADIO_EN_CS();
+
+  /* Send the write command with the address */
+  status = spiSendByte( CMD_W_REG | (address&0x1F) );
+  /* Write LEN bytes */
+  for(i=0; i<len; i++)
+    spiSendByte(buffer[i]);
+
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+/* Write only one byte (useful for most of the reg.) */
+unsigned char nrfWrite1Reg(unsigned char address, char byte)
+{
+  return nrfWriteReg(address, &byte, 1);
+}
+
+/* Read only one byte (useful for most of the reg.) */
+unsigned char nrfRead1Reg(unsigned char address) {
+  char byte;
+
+  nrfReadReg(address, &byte, 1);
+
+  return byte;
+}
+
+/* Sent the NOP command. Used to get the status byte */
+unsigned char nrfNop()
+{
+  unsigned char status;
+
+  RADIO_EN_CS();
+  status = spiSendByte(CMD_NOP);
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+unsigned char nrfFlushRx()
+{
+  unsigned char status;
+
+  RADIO_EN_CS();
+  status = spiSendByte(CMD_FLUSH_RX);
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+unsigned char nrfFlushTx()
+{
+  unsigned char status;
+
+  RADIO_EN_CS();
+  status = spiSendByte(CMD_FLUSH_TX);
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+// Return the payload length
+unsigned char nrfRxLength(unsigned int pipe)
+{
+  unsigned char length;
+
+  RADIO_EN_CS();
+  spiSendByte(CMD_RX_PL_WID);
+  length = spiReceiveByte();
+  RADIO_DIS_CS();
+
+  return length;
+}
+
+unsigned char nrfActivate()
+{
+  unsigned char status;
+  
+  RADIO_EN_CS();
+  status = spiSendByte(CMD_ACTIVATE);
+  spiSendByte(ACTIVATE_DATA);
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+// Write the ack payload of the pipe 0
+unsigned char nrfWriteAck(unsigned int pipe, char *buffer, int len)
+{
+  unsigned char status;
+  int i;
+
+  ASSERT(pipe<6);
+
+  RADIO_EN_CS();
+
+  /* Send the read command with the address */
+  status = spiSendByte(CMD_W_ACK_PAYLOAD(pipe));
+  /* Read LEN bytes */
+  for(i=0; i<len; i++)
+    spiSendByte(buffer[i]);
+
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+// Read the RX payload
+unsigned char nrfReadRX(char *buffer, int len)
+{
+  unsigned char status;
+  int i;
+
+  RADIO_EN_CS();
+
+  /* Send the read command with the address */
+  status = spiSendByte(CMD_R_RX_PAYLOAD);
+  /* Read LEN bytes */
+  for(i=0; i<len; i++)
+    buffer[i]=spiReceiveByte();
+
+  RADIO_DIS_CS();
+
+  return status;
+}
+
+/* Interrupt service routine, call the interrupt callback */
+void __attribute__((used)) EXTI9_Callback(void)
+{
+  if (interruptCb)
+  {
+    interruptCb();
+  }
+}
+
+void nrfSetInterruptCallback(void (*cb)(void))
+{
+  interruptCb = cb;
+}
+
+void nrfSetChannel(unsigned int channel)
+{
+  if (channel<126)
+    nrfWrite1Reg(REG_RF_CH, channel);
+}
+
+void nrfSetDatarate(int datarate)
+{
+  switch(datarate)
+  {
+    case RADIO_RATE_250K:
+      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_250K);
+      break;
+    case RADIO_RATE_1M:
+      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_1M);
+      break;
+    case RADIO_RATE_2M:
+      nrfWrite1Reg(REG_RF_SETUP, VAL_RF_SETUP_2M);
+      break;
+  }  
+}
+
+void nrfSetAddress(unsigned int pipe, char* address)
+{
+  int len = 5;
+
+  ASSERT(pipe<6);
+
+  if (pipe > 1)
+    len = 1;
+
+  nrfWriteReg(REG_RX_ADDR_P0 + pipe, address, len);
+}
+
+void nrfSetEnable(bool enable)
+{
+  if (enable)
+  {
+    RADIO_EN_CE();
+  } 
+  else
+  {
+    RADIO_DIS_CE();
+  }
+}
+
+unsigned char nrfGetStatus()
+{
+  return nrfNop();
+}
+
+/* Initialisation */
+void nrfInit(void)
+{
+  SPI_InitTypeDef  SPI_InitStructure;
+  EXTI_InitTypeDef EXTI_InitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  if (isInit)
+    return;
+
+  /* Enable SPI and GPIO clocks */
+  RCC_APB2PeriphClockCmd(RADIO_GPIO_SPI_CLK | RADIO_GPIO_CS_PERIF | 
+                         RADIO_GPIO_CE_PERIF | RADIO_GPIO_IRQ_PERIF, ENABLE);
+
+  /* Enable SPI and GPIO clocks */
+  RCC_APB1PeriphClockCmd(RADIO_SPI_CLK, ENABLE);
+
+  /* Configure main clock */
+  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_CLK;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_Init(RADIO_GPIO_CLK_PORT, &GPIO_InitStructure);
+
+  /* Configure SPI pins: SCK, MISO and MOSI */
+  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_SPI_SCK |  RADIO_GPIO_SPI_MOSI;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_Init(RADIO_GPIO_SPI_PORT, &GPIO_InitStructure);
+
+  //* Configure MISO */
+  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_SPI_MISO;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+  GPIO_Init(RADIO_GPIO_SPI_PORT, &GPIO_InitStructure);
+
+  /* Configure I/O for the Chip select */
+  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_CS;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+  GPIO_Init(RADIO_GPIO_CS_PORT, &GPIO_InitStructure);
+
+  /* Configure the interruption (EXTI Source) */
+  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_IRQ;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+  GPIO_Init(RADIO_GPIO_IRQ_PORT, &GPIO_InitStructure);
+
+  GPIO_EXTILineConfig(RADIO_GPIO_IRQ_SRC_PORT, RADIO_GPIO_IRQ_SRC);
+  EXTI_InitStructure.EXTI_Line = RADIO_GPIO_IRQ_LINE;
+  EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+  EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling;
+  EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+  EXTI_Init(&EXTI_InitStructure);
+
+  // Clock the radio with 16MHz
+  RCC_MCOConfig(RCC_MCO_HSE);
+
+  /* disable the chip select */
+  RADIO_DIS_CS();
+
+  /* Configure I/O for the Chip Enable */
+  GPIO_InitStructure.GPIO_Pin = RADIO_GPIO_CE;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+  GPIO_Init(RADIO_GPIO_CE_PORT, &GPIO_InitStructure);
+
+  /* disable the chip enable */
+  RADIO_DIS_CE();
+
+  /* SPI configuration */
+  SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+  SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+  SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+  SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low;
+  SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge;
+  SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+  SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
+  SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+  SPI_InitStructure.SPI_CRCPolynomial = 7;
+  SPI_Init(RADIO_SPI, &SPI_InitStructure);
+
+  /* Enable the SPI  */
+  SPI_Cmd(RADIO_SPI, ENABLE);
+  
+  isInit = true;
+}
+
+bool nrfTest(void)
+{
+  //TODO implement real tests!
+  return isInit & extiTest();
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/nvic.c b/crazyflie-firmware-src/src/drivers/src/nvic.c
new file mode 100644
index 0000000000000000000000000000000000000000..aa815ee11c2377fa7300bde4309cabb5f6e55c2b
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/nvic.c
@@ -0,0 +1,221 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nvic.c - Contains all Cortex-M3 processor exceptions handlers
+ */
+#include "exti.h"
+#include "led.h"
+#include "i2cdev.h"
+#include "ws2812.h"
+#include "motors.h"
+#include "cfassert.h"
+
+#ifdef PLATFORM_CF1
+#include "uart.h"
+#define UART_PRINT    uartPrintf
+#else
+#include "uart1.h"
+#define UART_PRINT    uart1Printf
+#endif
+
+#define DONT_DISCARD __attribute__((used))
+
+void nvicInit(void)
+{
+  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4);
+}
+
+/**
+ * @brief  This function handles SysTick Handler.
+ */
+extern void tickFreeRTOS(void);
+
+void DONT_DISCARD SysTick_Handler(void)
+{
+    tickFreeRTOS();
+}
+
+#ifdef NVIC_NOT_USED_BY_FREERTOS
+
+/**
+  * @brief  This function handles SVCall exception.
+  */
+void DONT_DISCARD SVC_Handler(void)
+{
+}
+
+/**
+ * @brief  This function handles PendSV_Handler exception.
+ */
+void DONT_DISCARD PendSV_Handler(void)
+{
+}
+#endif
+
+/**
+  * @brief  This function handles NMI exception.
+  */
+void DONT_DISCARD NMI_Handler(void)
+{
+}
+
+/**
+ * @brief  This function handles Hard Fault exception.
+ */
+void DONT_DISCARD HardFault_Handler(void)
+{
+  //http://www.st.com/mcu/forums-cat-6778-23.html
+  //****************************************************
+  //To test this application, you can use this snippet anywhere:
+  // //Let's crash the MCU!
+  // asm (" MOVS r0, #1 \n"
+  // " LDM r0,{r1-r2} \n"
+  // " BX LR; \n");
+  asm( "TST LR, #4 \n"
+  "ITE EQ \n"
+  "MRSEQ R0, MSP \n"
+  "MRSNE R0, PSP \n"
+  "B printHardFault");
+}
+
+void DONT_DISCARD printHardFault(uint32_t* hardfaultArgs)
+{
+  unsigned int stacked_r0;
+  unsigned int stacked_r1;
+  unsigned int stacked_r2;
+  unsigned int stacked_r3;
+  unsigned int stacked_r12;
+  unsigned int stacked_lr;
+  unsigned int stacked_pc;
+  unsigned int stacked_psr;
+
+  stacked_r0 = ((unsigned long) hardfaultArgs[0]);
+  stacked_r1 = ((unsigned long) hardfaultArgs[1]);
+  stacked_r2 = ((unsigned long) hardfaultArgs[2]);
+  stacked_r3 = ((unsigned long) hardfaultArgs[3]);
+
+  stacked_r12 = ((unsigned long) hardfaultArgs[4]);
+  stacked_lr = ((unsigned long) hardfaultArgs[5]);
+  stacked_pc = ((unsigned long) hardfaultArgs[6]);
+  stacked_psr = ((unsigned long) hardfaultArgs[7]);
+
+
+  UART_PRINT("[Hard fault handler]\n");
+  UART_PRINT("R0 = %x\n", stacked_r0);
+  UART_PRINT("R1 = %x\n", stacked_r1);
+  UART_PRINT("R2 = %x\n", stacked_r2);
+  UART_PRINT("R3 = %x\n", stacked_r3);
+  UART_PRINT("R12 = %x\n", stacked_r12);
+  UART_PRINT("LR = %x\n", stacked_lr);
+  UART_PRINT("PC = %x\n", stacked_pc);
+  UART_PRINT("PSR = %x\n", stacked_psr);
+  UART_PRINT("BFAR = %x\n", (*((volatile unsigned int *)(0xE000ED38))));
+  UART_PRINT("CFSR = %x\n", (*((volatile unsigned int *)(0xE000ED28))));
+  UART_PRINT("HFSR = %x\n", (*((volatile unsigned int *)(0xE000ED2C))));
+  UART_PRINT("DFSR = %x\n", (*((volatile unsigned int *)(0xE000ED30))));
+  UART_PRINT("AFSR = %x\n", (*((volatile unsigned int *)(0xE000ED3C))));
+
+  motorsSetRatio(MOTOR_M1, 0);
+  motorsSetRatio(MOTOR_M2, 0);
+  motorsSetRatio(MOTOR_M3, 0);
+  motorsSetRatio(MOTOR_M4, 0);
+
+  ledClearAll();
+  ledSet(ERR_LED1, 1);
+  ledSet(ERR_LED2, 1);
+
+  storeAssertSnapshotData(__FILE__, __LINE__);
+  while (1)
+  {}
+}
+/**
+ * @brief  This function handles Memory Manage exception.
+ */
+void DONT_DISCARD MemManage_Handler(void)
+{
+  /* Go to infinite loop when Memory Manage exception occurs */
+  motorsSetRatio(MOTOR_M1, 0);
+  motorsSetRatio(MOTOR_M2, 0);
+  motorsSetRatio(MOTOR_M3, 0);
+  motorsSetRatio(MOTOR_M4, 0);
+
+  ledClearAll();
+  ledSet(ERR_LED1, 1);
+  ledSet(ERR_LED2, 1);
+
+  storeAssertSnapshotData(__FILE__, __LINE__);
+  while (1)
+  {}
+}
+
+/**
+ * @brief  This function handles Bus Fault exception.
+ */
+void DONT_DISCARD BusFault_Handler(void)
+{
+  /* Go to infinite loop when Bus Fault exception occurs */
+  motorsSetRatio(MOTOR_M1, 0);
+  motorsSetRatio(MOTOR_M2, 0);
+  motorsSetRatio(MOTOR_M3, 0);
+  motorsSetRatio(MOTOR_M4, 0);
+
+  ledClearAll();
+  ledSet(ERR_LED1, 1);
+  ledSet(ERR_LED2, 1);
+
+  storeAssertSnapshotData(__FILE__, __LINE__);
+  while (1)
+  {}
+}
+
+/**
+ * @brief  This function handles Usage Fault exception.
+ */
+void DONT_DISCARD UsageFault_Handler(void)
+{
+  /* Go to infinite loop when Usage Fault exception occurs */
+  motorsSetRatio(MOTOR_M1, 0);
+  motorsSetRatio(MOTOR_M2, 0);
+  motorsSetRatio(MOTOR_M3, 0);
+  motorsSetRatio(MOTOR_M4, 0);
+
+  ledClearAll();
+  ledSet(ERR_LED1, 1);
+  ledSet(ERR_LED2, 1);
+
+  storeAssertSnapshotData(__FILE__, __LINE__);
+  while (1)
+  {}
+}
+
+/**
+ * @brief  This function handles Debug Monitor exception.
+ */
+void DONT_DISCARD DebugMon_Handler(void)
+{
+}
+
+void DONT_DISCARD DMA1_Stream5_IRQHandler(void)
+{
+  ws2812DmaIsr();
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/piezo.c b/crazyflie-firmware-src/src/drivers/src/piezo.c
new file mode 100644
index 0000000000000000000000000000000000000000..6193e4fc6893db92b24002aa1ade3ca4784442c7
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/piezo.c
@@ -0,0 +1,147 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * piezo.c - Piezo/Buzzer driver
+ *
+ * This code mainly interfacing the PWM peripheral lib of ST.
+ */
+
+#include <stdbool.h>
+
+/* ST includes */
+#include "stm32fxxx.h"
+
+#include "piezo.h"
+
+//FreeRTOS includes
+#include "FreeRTOS.h"
+#include "task.h"
+
+// HW defines
+#define PIEZO_TIM_PERIF       RCC_APB1Periph_TIM5
+#define PIEZO_TIM             TIM5
+#define PIEZO_TIM_DBG         DBGMCU_TIM2_STOP
+#define PIEZO_TIM_SETCOMPARE  TIM_SetCompare2
+#define PIEZO_TIM_GETCAPTURE  TIM_GetCapture2
+
+#define PIEZO_GPIO_POS_PERIF         RCC_AHB1Periph_GPIOA
+#define PIEZO_GPIO_POS_PORT          GPIOA
+#define PIEZO_GPIO_POS_PIN           GPIO_Pin_2 // TIM5_CH3
+#define PIEZO_GPIO_AF_POS_PIN        GPIO_PinSource2
+#define PIEZO_GPIO_AF_POS            GPIO_AF_TIM5
+
+#define PIEZO_GPIO_NEG_PERIF         RCC_AHB1Periph_GPIOA
+#define PIEZO_GPIO_NEG_PORT          GPIOA
+#define PIEZO_GPIO_NEG_PIN           GPIO_Pin_3 // TIM5_CH4
+#define PIEZO_GPIO_AF_NEG_PIN        GPIO_PinSource3
+#define PIEZO_GPIO_AF_NEG            GPIO_AF_TIM5
+
+#define PIEZO_PWM_BITS      (8)
+#define PIEZO_PWM_PERIOD    ((1<<PIEZO_PWM_BITS) - 1)
+#define PIEZO_PWM_PRESCALE  (0)
+
+/* This should be calculated.. */
+#define PIEZO_BASE_FREQ (329500)
+
+static bool isInit = false;
+
+/* Public functions */
+
+void piezoInit()
+{
+  if (isInit)
+    return;
+
+  //Init structures
+  GPIO_InitTypeDef GPIO_InitStructure;
+  TIM_TimeBaseInitTypeDef  TIM_TimeBaseStructure;
+  TIM_OCInitTypeDef  TIM_OCInitStructure;
+
+  //Clock the gpio and the timers
+  RCC_AHB1PeriphClockCmd(PIEZO_GPIO_POS_PERIF | PIEZO_GPIO_NEG_PERIF, ENABLE);
+  RCC_APB1PeriphClockCmd(PIEZO_TIM_PERIF, ENABLE);
+
+  // Configure the GPIO for the timer output
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_DOWN;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
+  GPIO_InitStructure.GPIO_Pin = PIEZO_GPIO_POS_PIN;
+  GPIO_Init(PIEZO_GPIO_POS_PORT, &GPIO_InitStructure);
+  GPIO_InitStructure.GPIO_Pin = PIEZO_GPIO_NEG_PIN;
+  GPIO_Init(PIEZO_GPIO_NEG_PORT, &GPIO_InitStructure);
+
+  //Map timers to alternate functions
+  GPIO_PinAFConfig(PIEZO_GPIO_POS_PORT, PIEZO_GPIO_AF_POS_PIN, PIEZO_GPIO_AF_POS);
+  GPIO_PinAFConfig(PIEZO_GPIO_NEG_PORT, PIEZO_GPIO_AF_NEG_PIN, PIEZO_GPIO_AF_NEG);
+
+  //Timer configuration
+  TIM_TimeBaseStructure.TIM_Period = PIEZO_PWM_PERIOD;
+  TIM_TimeBaseStructure.TIM_Prescaler = PIEZO_PWM_PRESCALE;
+  TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+  TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+  TIM_TimeBaseInit(PIEZO_TIM, &TIM_TimeBaseStructure);
+
+  // PWM channels configuration
+  TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+  TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+  TIM_OCInitStructure.TIM_Pulse = 0;
+  TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low;
+  TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
+
+  // Configure OC3
+  TIM_OC3Init(PIEZO_TIM, &TIM_OCInitStructure);
+  TIM_OC3PreloadConfig(PIEZO_TIM, TIM_OCPreload_Enable);
+
+  // Configure OC4 inverted
+  TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+  TIM_OC4Init(PIEZO_TIM, &TIM_OCInitStructure);
+  TIM_OC4PreloadConfig(PIEZO_TIM, TIM_OCPreload_Enable);
+
+  //Enable the timer PWM outputs
+  TIM_CtrlPWMOutputs(PIEZO_TIM, ENABLE);
+  TIM_SetCompare3(PIEZO_TIM, 0x00);
+  TIM_SetCompare4(PIEZO_TIM, 0x00);
+
+  //Enable the timer
+  TIM_Cmd(PIEZO_TIM, ENABLE);
+
+  isInit = true;
+}
+
+bool piezoTest(void)
+{
+  return isInit;
+}
+
+void piezoSetRatio(uint8_t ratio)
+{
+  TIM_SetCompare3(PIEZO_TIM, ratio);
+  TIM_SetCompare4(PIEZO_TIM, ratio);
+}
+
+void piezoSetFreq(uint16_t freq)
+{
+  TIM_PrescalerConfig(PIEZO_TIM, (PIEZO_BASE_FREQ/freq), TIM_PSCReloadMode_Update);
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/swd.c b/crazyflie-firmware-src/src/drivers/src/swd.c
new file mode 100644
index 0000000000000000000000000000000000000000..6d1feb767473996901350cbac4c776b4e8024c30
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/swd.c
@@ -0,0 +1,204 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * swd.c - Low level SWD functionality
+ */
+#include <stdbool.h>
+
+#include "stm32fxxx.h"
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "swd.h"
+
+static bool isInit = false;
+
+#define SWD_SPI                           SPI2
+#define SWD_SPI_CLK                       RCC_APB1Periph_SPI2
+#define SWD_SPI_CLK_INIT                  RCC_APB1PeriphClockCmd
+
+#define SWD_SPI_SCK_PIN                   GPIO_Pin_13
+#define SWD_SPI_SCK_GPIO_PORT             GPIOB
+#define SWD_SPI_SCK_GPIO_CLK              RCC_AHB1Periph_GPIOB
+#define SWD_SPI_SCK_SOURCE                GPIO_PinSource13
+#define SWD_SPI_SCK_AF                    GPIO_AF_SPI2
+
+#define SWD_SPI_MISO_PIN                  GPIO_Pin_15
+#define SWD_SPI_MISO_GPIO_PORT            GPIOB
+#define SWD_SPI_MISO_GPIO_CLK             RCC_AHB1Periph_GPIOB
+#define SWD_SPI_MISO_SOURCE               GPIO_PinSource15
+#define SWD_SPI_MISO_AF                   GPIO_AF_SPI2
+
+
+static void initGPIO(void) {
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  SWD_SPI_CLK_INIT(SWD_SPI_CLK, ENABLE);
+
+  RCC_AHB1PeriphClockCmd(SWD_SPI_SCK_GPIO_CLK | SWD_SPI_MISO_GPIO_CLK, ENABLE);
+
+  GPIO_PinAFConfig(SWD_SPI_SCK_GPIO_PORT, SWD_SPI_SCK_SOURCE, SWD_SPI_SCK_AF);
+  GPIO_PinAFConfig(SWD_SPI_MISO_GPIO_PORT, SWD_SPI_MISO_SOURCE, SWD_SPI_MISO_AF);
+
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_DOWN;
+
+  GPIO_InitStructure.GPIO_Pin = SWD_SPI_SCK_PIN;
+  GPIO_Init(SWD_SPI_SCK_GPIO_PORT, &GPIO_InitStructure);
+
+  /* In bi-directional mode only MISO is used */
+  GPIO_InitStructure.GPIO_Pin =  SWD_SPI_MISO_PIN;
+  GPIO_Init(SWD_SPI_MISO_GPIO_PORT, &GPIO_InitStructure);
+
+}
+
+static void initSPI(void) {
+
+  SPI_InitTypeDef  SPI_InitStructure;
+
+  initGPIO();
+
+  /* Set up SPI in bi-directional mode */
+  SPI_InitStructure.SPI_Direction = SPI_Direction_1Line_Tx;
+  SPI_InitStructure.SPI_Mode = SPI_Mode_Master;
+  SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b;
+  SPI_InitStructure.SPI_CPOL = SPI_CPOL_High;
+  SPI_InitStructure.SPI_CPHA = SPI_CPHA_2Edge;
+  SPI_InitStructure.SPI_NSS = SPI_NSS_Soft;
+  SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256;
+
+  SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB;
+  SPI_InitStructure.SPI_CRCPolynomial = 7;
+  SPI_Init(SWD_SPI, &SPI_InitStructure);
+
+  SPI_Cmd(SWD_SPI, ENABLE);
+}
+
+//Initialize the green led pin as output
+void swdInit()
+{
+  if(isInit)
+    return;
+
+  initSPI();
+
+  isInit = true;
+}
+
+/* Code for debugging and testing, should be removed later */
+
+uint8_t tx_data[35];
+uint8_t rx_data[35];
+
+uint32_t counter = 0;
+uint16_t number_of_txd_bytes = 0;
+uint32_t transfer_size = 35;
+
+uint8_t header = 0xA5;
+uint8_t idx = 0;
+
+bool swdTest(void) {
+  // Start = 1
+  // DP access = 0
+  // Read access = 1
+  // DP reg = 00 (IDCODE)
+  // Parity = odd bits -> 1
+  // Stop = 0
+  // Park = 1 (not 0!)
+
+  // First at least fifty ones, then the sequence below to switch from JTAG to SWD and then at least 50 ones again.
+  // The the SWD is reset and ready to use. Note that once this is done the nRF will only go into simulated off mode since
+  // a debugger is connected.
+  // 111...01111001 11100111...111
+
+  // The command for reading IDCODE is
+  /// 10100101
+
+  // Should read out (and does):0x0BB11477 (according to OpenOCD)
+  //T ACK |------------DATA--------------|P
+  //? 100 111011100010100010001101110100001
+
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+#if 0
+  tx_data[idx++] = 0x9E;
+  tx_data[idx++] = 0xE7;
+#else
+  tx_data[idx++] = 0x79;
+  tx_data[idx++] = 0xE7;
+#endif
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFF;
+  tx_data[idx++] = 0xFC;
+  tx_data[idx++] = header;
+  // Rest is 0x00
+
+  /* As long as the SPI is enabled in bi-di mode the clock is enabled. So
+   * we write data as normal, but when reading there's no need to output any
+   * data to trigger the clock. Direction needs to be set accordingly.
+   */
+
+  while(number_of_txd_bytes < transfer_size)
+  {
+    if (number_of_txd_bytes < idx)
+    {
+      SPI_BiDirectionalLineConfig(SWD_SPI, SPI_Direction_Tx);
+
+      /*!< Loop while DR register in not emplty */
+      while (SPI_I2S_GetFlagStatus(SWD_SPI, SPI_I2S_FLAG_TXE) == RESET);
+
+      SPI_I2S_SendData(SWD_SPI, tx_data[number_of_txd_bytes]);
+
+      // Make sure that we have sent data in case next loop will be RX, the
+      // mode is switched before we manage to send the data!
+      while (SPI_I2S_GetFlagStatus(SWD_SPI, SPI_I2S_FLAG_BSY) == SET);
+    }
+    else
+    {
+      SPI_BiDirectionalLineConfig(SWD_SPI, SPI_Direction_Rx);
+      while (SPI_I2S_GetFlagStatus(SWD_SPI, SPI_I2S_FLAG_RXNE) == RESET);
+
+      /*!< Return the byte read from the SPI bus */
+      rx_data[number_of_txd_bytes] = (uint8_t) SPI_I2S_ReceiveData(SWD_SPI);
+    }
+    number_of_txd_bytes++;
+  }
+  SPI_Cmd(SWD_SPI, DISABLE);
+  return isInit;
+}
+
diff --git a/crazyflie-firmware-src/src/drivers/src/uart1.c b/crazyflie-firmware-src/src/drivers/src/uart1.c
new file mode 100644
index 0000000000000000000000000000000000000000..206540c9f19fc01fc95ce51a399e33b8a1459cad
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/uart1.c
@@ -0,0 +1,152 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart1.c - uart1 driver
+ */
+#include <string.h>
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "queue.h"
+
+/*ST includes */
+#include "stm32fxxx.h"
+
+#include "config.h"
+#include "nvic.h"
+#include "uart1.h"
+#include "cfassert.h"
+#include "config.h"
+#include "nvicconf.h"
+
+
+static xQueueHandle uart1queue;
+static bool isInit = false;
+
+void uart1Init(const uint32_t baudrate)
+{
+
+  USART_InitTypeDef USART_InitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  /* Enable GPIO and USART clock */
+  RCC_AHB1PeriphClockCmd(UART1_GPIO_PERIF, ENABLE);
+  ENABLE_UART1_RCC(UART1_PERIF, ENABLE);
+
+  /* Configure USART Rx as input floating */
+  GPIO_InitStructure.GPIO_Pin   = UART1_GPIO_RX_PIN;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
+  GPIO_Init(UART1_GPIO_PORT, &GPIO_InitStructure);
+
+  /* Configure USART Tx as alternate function */
+  GPIO_InitStructure.GPIO_Pin   = UART1_GPIO_TX_PIN;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF;
+  GPIO_Init(UART1_GPIO_PORT, &GPIO_InitStructure);
+
+  //Map uart to alternate functions
+  GPIO_PinAFConfig(UART1_GPIO_PORT, UART1_GPIO_AF_TX_PIN, UART1_GPIO_AF_TX);
+  GPIO_PinAFConfig(UART1_GPIO_PORT, UART1_GPIO_AF_RX_PIN, UART1_GPIO_AF_RX);
+
+  USART_InitStructure.USART_BaudRate            = baudrate;
+  USART_InitStructure.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
+  USART_InitStructure.USART_WordLength          = USART_WordLength_8b;
+  USART_InitStructure.USART_StopBits            = USART_StopBits_1;
+  USART_InitStructure.USART_Parity              = USART_Parity_No ;
+  USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+  USART_Init(UART1_TYPE, &USART_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannel = UART1_IRQ;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_MID_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  uart1queue = xQueueCreate(64, sizeof(uint8_t));
+
+  USART_ITConfig(UART1_TYPE, USART_IT_RXNE, ENABLE);
+
+  //Enable UART
+  USART_Cmd(UART1_TYPE, ENABLE);
+  
+  USART_ITConfig(UART1_TYPE, USART_IT_RXNE, ENABLE);
+
+  isInit = true;
+}
+
+bool uart1Test(void)
+{
+  return isInit;
+}
+
+bool uart1GetDataWithTimout(uint8_t *c)
+{
+  if (xQueueReceive(uart1queue, c, UART1_DATA_TIMEOUT_TICKS) == pdTRUE)
+  {
+    return true;
+  }
+
+  *c = 0;
+  return false;
+}
+
+void uart1SendData(uint32_t size, uint8_t* data)
+{
+  uint32_t i;
+
+  if (!isInit)
+    return;
+
+  for(i = 0; i < size; i++)
+  {
+    while (!(UART1_TYPE->SR & USART_FLAG_TXE));
+    UART1_TYPE->DR = (data[i] & 0x00FF);
+  }
+}
+
+int uart1Putchar(int ch)
+{
+    uart1SendData(1, (uint8_t *)&ch);
+    
+    return (unsigned char)ch;
+}
+
+void uart1Getchar(char * ch)
+{
+  xQueueReceive(uart1queue, ch, portMAX_DELAY);
+}
+
+void __attribute__((used)) USART3_IRQHandler(void)
+{
+  uint8_t rxData;
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+
+  if (USART_GetITStatus(UART1_TYPE, USART_IT_RXNE))
+  {
+    rxData = USART_ReceiveData(UART1_TYPE) & 0x00FF;
+    xQueueSendFromISR(uart1queue, &rxData, &xHigherPriorityTaskWoken);
+  }
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/uart2.c b/crazyflie-firmware-src/src/drivers/src/uart2.c
new file mode 100644
index 0000000000000000000000000000000000000000..f719896494531854ba3deb3770c0e9865eba1807
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/uart2.c
@@ -0,0 +1,104 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart2.c - uart2 driver
+ */
+#include <string.h>
+
+/*ST includes */
+#include "stm32fxxx.h"
+
+#include "config.h"
+#include "uart2.h"
+#include "cfassert.h"
+#include "config.h"
+
+
+static bool isInit = false;
+
+void uart2Init(const uint32_t baudrate)
+{
+
+  USART_InitTypeDef USART_InitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  /* Enable GPIO and USART clock */
+  RCC_AHB1PeriphClockCmd(UART2_GPIO_PERIF, ENABLE);
+  ENABLE_UART2_RCC(UART2_PERIF, ENABLE);
+
+  /* Configure USART Rx as input floating */
+  GPIO_InitStructure.GPIO_Pin   = UART2_GPIO_RX_PIN;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
+  GPIO_Init(UART2_GPIO_PORT, &GPIO_InitStructure);
+
+  /* Configure USART Tx as alternate function */
+  GPIO_InitStructure.GPIO_Pin   = UART2_GPIO_TX_PIN;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF;
+  GPIO_Init(UART2_GPIO_PORT, &GPIO_InitStructure);
+
+  //Map uart to alternate functions
+  GPIO_PinAFConfig(UART2_GPIO_PORT, UART2_GPIO_AF_TX_PIN, UART2_GPIO_AF_TX);
+  GPIO_PinAFConfig(UART2_GPIO_PORT, UART2_GPIO_AF_RX_PIN, UART2_GPIO_AF_RX);
+
+  USART_InitStructure.USART_BaudRate            = baudrate;
+  USART_InitStructure.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
+  USART_InitStructure.USART_WordLength          = USART_WordLength_8b;
+  USART_InitStructure.USART_StopBits            = USART_StopBits_1;
+  USART_InitStructure.USART_Parity              = USART_Parity_No ;
+  USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+  USART_Init(UART2_TYPE, &USART_InitStructure);
+
+  //Enable UART
+  USART_Cmd(UART2_TYPE, ENABLE);
+  
+  isInit = true;
+}
+
+bool uart2Test(void)
+{
+  return isInit;
+}
+
+void uart2SendData(uint32_t size, uint8_t* data)
+{
+  uint32_t i;
+
+  if (!isInit)
+    return;
+
+  for(i = 0; i < size; i++)
+  {
+    while (!(UART2_TYPE->SR & USART_FLAG_TXE));
+    UART2_TYPE->DR = (data[i] & 0x00FF);
+  }
+}
+
+int uart2Putchar(int ch)
+{
+    uart2SendData(1, (uint8_t *)&ch);
+    
+    return (unsigned char)ch;
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/uart_syslink.c b/crazyflie-firmware-src/src/drivers/src/uart_syslink.c
new file mode 100644
index 0000000000000000000000000000000000000000..0fb17921a8c52eeeeae12a84fe0453d8d9a9bd5a
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/uart_syslink.c
@@ -0,0 +1,384 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart_syslink.c - Uart syslink to nRF51 and raw access functions
+ */
+#include <stdint.h>
+#include <string.h>
+
+/*ST includes */
+#include "stm32fxxx.h"
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+#include "queue.h"
+
+#include "config.h"
+#include "uart_syslink.h"
+#include "crtp.h"
+#include "cfassert.h"
+#include "nvicconf.h"
+#include "config.h"
+#include "queuemonitor.h"
+
+
+#define UARTSLK_DATA_TIMEOUT_MS 1000
+#define UARTSLK_DATA_TIMEOUT_TICKS (UARTSLK_DATA_TIMEOUT_MS / portTICK_RATE_MS)
+#define CCR_ENABLE_SET  ((uint32_t)0x00000001)
+
+static bool isInit = false;
+
+static xSemaphoreHandle waitUntilSendDone;
+static xSemaphoreHandle uartBusy;
+static xQueueHandle uartslkDataDelivery;
+
+static uint8_t dmaBuffer[64];
+static uint8_t *outDataIsr;
+static uint8_t dataIndexIsr;
+static uint8_t dataSizeIsr;
+static bool    isUartDmaInitialized;
+static DMA_InitTypeDef DMA_InitStructureShare;
+static uint32_t initialDMACount;
+static uint32_t remainingDMACount;
+static bool     dmaIsPaused;
+
+static void uartslkPauseDma();
+static void uartslkResumeDma();
+
+/**
+  * Configures the UART DMA. Mainly used for FreeRTOS trace
+  * data transfer.
+  */
+void uartslkDmaInit(void)
+{
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE);
+
+  // USART TX DMA Channel Config
+  DMA_InitStructureShare.DMA_PeripheralBaseAddr = (uint32_t)&UARTSLK_TYPE->DR;
+  DMA_InitStructureShare.DMA_Memory0BaseAddr = (uint32_t)dmaBuffer;
+  DMA_InitStructureShare.DMA_MemoryInc = DMA_MemoryInc_Enable;
+  DMA_InitStructureShare.DMA_MemoryBurst = DMA_MemoryBurst_Single;
+  DMA_InitStructureShare.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+  DMA_InitStructureShare.DMA_BufferSize = 0;
+  DMA_InitStructureShare.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+  DMA_InitStructureShare.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+  DMA_InitStructureShare.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+  DMA_InitStructureShare.DMA_DIR = DMA_DIR_MemoryToPeripheral;
+  DMA_InitStructureShare.DMA_Mode = DMA_Mode_Normal;
+  DMA_InitStructureShare.DMA_Priority = DMA_Priority_High;
+  DMA_InitStructureShare.DMA_FIFOMode = DMA_FIFOMode_Disable;
+  DMA_InitStructureShare.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
+  DMA_InitStructureShare.DMA_Channel = UARTSLK_DMA_CH;
+
+  NVIC_InitStructure.NVIC_IRQChannel = UARTSLK_DMA_IRQ;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  isUartDmaInitialized = true;
+}
+
+void uartslkInit(void)
+{
+  // initialize the FreeRTOS structures first, to prevent null pointers in interrupts
+  waitUntilSendDone = xSemaphoreCreateBinary(); // initialized as blocking
+  uartBusy = xSemaphoreCreateBinary(); // initialized as blocking
+  xSemaphoreGive(uartBusy); // but we give it because the uart isn't busy at initialization
+
+  uartslkDataDelivery = xQueueCreate(1024, sizeof(uint8_t));
+  DEBUG_QUEUE_MONITOR_REGISTER(uartslkDataDelivery);
+
+  USART_InitTypeDef USART_InitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+  EXTI_InitTypeDef extiInit;
+
+  /* Enable GPIO and USART clock */
+  RCC_AHB1PeriphClockCmd(UARTSLK_GPIO_PERIF, ENABLE);
+  ENABLE_UARTSLK_RCC(UARTSLK_PERIF, ENABLE);
+
+  /* Configure USART Rx as input floating */
+  GPIO_InitStructure.GPIO_Pin   = UARTSLK_GPIO_RX_PIN;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
+  GPIO_Init(UARTSLK_GPIO_PORT, &GPIO_InitStructure);
+
+  /* Configure USART Tx as alternate function */
+  GPIO_InitStructure.GPIO_Pin   = UARTSLK_GPIO_TX_PIN;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF;
+  GPIO_Init(UARTSLK_GPIO_PORT, &GPIO_InitStructure);
+
+  //Map uartslk to alternate functions
+  GPIO_PinAFConfig(UARTSLK_GPIO_PORT, UARTSLK_GPIO_AF_TX_PIN, UARTSLK_GPIO_AF_TX);
+  GPIO_PinAFConfig(UARTSLK_GPIO_PORT, UARTSLK_GPIO_AF_RX_PIN, UARTSLK_GPIO_AF_RX);
+
+#if defined(UARTSLK_OUTPUT_TRACE_DATA) || defined(ADC_OUTPUT_RAW_DATA) || defined(IMU_OUTPUT_RAW_DATA_ON_UART)
+  USART_InitStructure.USART_BaudRate            = 2000000;
+  USART_InitStructure.USART_Mode                = USART_Mode_Tx;
+#else
+  USART_InitStructure.USART_BaudRate            = 1000000;
+  USART_InitStructure.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
+#endif
+  USART_InitStructure.USART_WordLength          = USART_WordLength_8b;
+  USART_InitStructure.USART_StopBits            = USART_StopBits_1;
+  USART_InitStructure.USART_Parity              = USART_Parity_No ;
+  USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+  USART_Init(UARTSLK_TYPE, &USART_InitStructure);
+
+  uartslkDmaInit();
+
+  // Configure Rx buffer not empty interrupt
+  NVIC_InitStructure.NVIC_IRQChannel = UARTSLK_IRQ;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_SYSLINK_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  USART_ITConfig(UARTSLK_TYPE, USART_IT_RXNE, ENABLE);
+
+  //Setting up TXEN pin (NRF flow control)
+  RCC_AHB1PeriphClockCmd(UARTSLK_TXEN_PERIF, ENABLE);
+
+  bzero(&GPIO_InitStructure, sizeof(GPIO_InitStructure));
+  GPIO_InitStructure.GPIO_Pin = UARTSLK_TXEN_PIN;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
+  GPIO_Init(UARTSLK_TXEN_PORT, &GPIO_InitStructure);
+
+  extiInit.EXTI_Line = UARTSLK_TXEN_EXTI;
+  extiInit.EXTI_Mode = EXTI_Mode_Interrupt;
+  extiInit.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
+  extiInit.EXTI_LineCmd = ENABLE;
+  EXTI_Init(&extiInit);
+  EXTI_ClearITPendingBit(UARTSLK_TXEN_EXTI);
+
+  NVIC_EnableIRQ(EXTI4_IRQn);
+
+  //Enable UART
+  USART_Cmd(UARTSLK_TYPE, ENABLE);
+  isInit = true;
+}
+
+bool uartslkTest(void)
+{
+  return isInit;
+}
+
+bool uartslkGetDataWithTimout(uint8_t *c)
+{
+  if (xQueueReceive(uartslkDataDelivery, c, UARTSLK_DATA_TIMEOUT_TICKS) == pdTRUE)
+  {
+    return true;
+  }
+
+  *c = 0;
+  return false;
+}
+
+void uartslkSendData(uint32_t size, uint8_t* data)
+{
+  uint32_t i;
+
+  if (!isInit)
+    return;
+
+  for(i = 0; i < size; i++)
+  {
+#ifdef UARTSLK_SPINLOOP_FLOWCTRL
+    while(GPIO_ReadInputDataBit(UARTSLK_TXEN_PORT, UARTSLK_TXEN_PIN) == Bit_SET);
+#endif
+    while (!(UARTSLK_TYPE->SR & USART_FLAG_TXE));
+    UARTSLK_TYPE->DR = (data[i] & 0x00FF);
+  }
+}
+
+void uartslkSendDataIsrBlocking(uint32_t size, uint8_t* data)
+{
+  xSemaphoreTake(uartBusy, portMAX_DELAY);
+  outDataIsr = data;
+  dataSizeIsr = size;
+  dataIndexIsr = 1;
+  uartslkSendData(1, &data[0]);
+  USART_ITConfig(UARTSLK_TYPE, USART_IT_TXE, ENABLE);
+  xSemaphoreTake(waitUntilSendDone, portMAX_DELAY);
+  outDataIsr = 0;
+  xSemaphoreGive(uartBusy);
+}
+
+int uartslkPutchar(int ch)
+{
+    uartslkSendData(1, (uint8_t *)&ch);
+    
+    return (unsigned char)ch;
+}
+
+void uartslkSendDataDmaBlocking(uint32_t size, uint8_t* data)
+{
+  if (isUartDmaInitialized)
+  {
+    xSemaphoreTake(uartBusy, portMAX_DELAY);
+    // Wait for DMA to be free
+    while(DMA_GetCmdStatus(UARTSLK_DMA_STREAM) != DISABLE);
+    //Copy data in DMA buffer
+    memcpy(dmaBuffer, data, size);
+    DMA_InitStructureShare.DMA_BufferSize = size;
+    initialDMACount = size;
+    // Init new DMA stream
+    DMA_Init(UARTSLK_DMA_STREAM, &DMA_InitStructureShare);
+    // Enable the Transfer Complete interrupt
+    DMA_ITConfig(UARTSLK_DMA_STREAM, DMA_IT_TC, ENABLE);
+    /* Enable USART DMA TX Requests */
+    USART_DMACmd(UARTSLK_TYPE, USART_DMAReq_Tx, ENABLE);
+    /* Clear transfer complete */
+    USART_ClearFlag(UARTSLK_TYPE, USART_FLAG_TC);
+    /* Enable DMA USART TX Stream */
+    DMA_Cmd(UARTSLK_DMA_STREAM, ENABLE);
+    xSemaphoreTake(waitUntilSendDone, portMAX_DELAY);
+    xSemaphoreGive(uartBusy);
+  }
+}
+
+static void uartslkPauseDma()
+{
+  if (DMA_GetCmdStatus(UARTSLK_DMA_STREAM) == ENABLE)
+  {
+    // Disable transfer complete interrupt
+    DMA_ITConfig(UARTSLK_DMA_STREAM, DMA_IT_TC, DISABLE);
+    // Disable stream to pause it
+    DMA_Cmd(UARTSLK_DMA_STREAM, DISABLE);
+    // Wait for it to be disabled
+    while(DMA_GetCmdStatus(UARTSLK_DMA_STREAM) != DISABLE);
+    // Disable transfer complete
+    DMA_ClearITPendingBit(UARTSLK_DMA_STREAM, UARTSLK_DMA_FLAG_TCIF);
+    // Read remaining data count
+    remainingDMACount = DMA_GetCurrDataCounter(UARTSLK_DMA_STREAM);
+    dmaIsPaused = true;
+  }
+}
+
+static void uartslkResumeDma()
+{
+  if (dmaIsPaused)
+  {
+    // Update DMA counter
+    DMA_SetCurrDataCounter(UARTSLK_DMA_STREAM, remainingDMACount);
+    // Update memory read address
+    UARTSLK_DMA_STREAM->M0AR = (uint32_t)&dmaBuffer[initialDMACount - remainingDMACount];
+    // Enable the Transfer Complete interrupt
+    DMA_ITConfig(UARTSLK_DMA_STREAM, DMA_IT_TC, ENABLE);
+    /* Clear transfer complete */
+    USART_ClearFlag(UARTSLK_TYPE, USART_FLAG_TC);
+    /* Enable DMA USART TX Stream */
+    DMA_Cmd(UARTSLK_DMA_STREAM, ENABLE);
+    dmaIsPaused = false;
+  }
+}
+
+void uartslkDmaIsr(void)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+
+  // Stop and cleanup DMA stream
+  DMA_ITConfig(UARTSLK_DMA_STREAM, DMA_IT_TC, DISABLE);
+  DMA_ClearITPendingBit(UARTSLK_DMA_STREAM, UARTSLK_DMA_FLAG_TCIF);
+  USART_DMACmd(UARTSLK_TYPE, USART_DMAReq_Tx, DISABLE);
+  DMA_Cmd(UARTSLK_DMA_STREAM, DISABLE);
+
+  remainingDMACount = 0;
+  xSemaphoreGiveFromISR(waitUntilSendDone, &xHigherPriorityTaskWoken);
+}
+
+void uartslkIsr(void)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+
+  // the following if statement replaces:
+  //   if (USART_GetITStatus(UARTSLK_TYPE, USART_IT_RXNE) == SET)
+  // we do this check as fast as possible to minimize the chance of an overrun,
+  // which occasionally cause problems and cause packet loss at high CPU usage
+  if ((UARTSLK_TYPE->SR & (1<<5)) != 0) // if the RXNE interrupt has occurred
+  {
+    uint8_t rxDataInterrupt = (uint8_t)(UARTSLK_TYPE->DR & 0xFF);
+    xQueueSendFromISR(uartslkDataDelivery, &rxDataInterrupt, &xHigherPriorityTaskWoken);
+  }
+  else if (USART_GetITStatus(UARTSLK_TYPE, USART_IT_TXE) == SET)
+  {
+    if (outDataIsr && (dataIndexIsr < dataSizeIsr))
+    {
+      USART_SendData(UARTSLK_TYPE, outDataIsr[dataIndexIsr] & 0x00FF);
+      dataIndexIsr++;
+    }
+    else
+    {
+      USART_ITConfig(UARTSLK_TYPE, USART_IT_TXE, DISABLE);
+      xSemaphoreGiveFromISR(waitUntilSendDone, &xHigherPriorityTaskWoken);
+    }
+  }
+  else
+  {
+    /** if we get here, the error is most likely caused by an overrun!
+     * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun error)
+     * - and IDLE (Idle line detected) pending bits are cleared by software sequence:
+     * - reading USART_SR register followed reading the USART_DR register.
+     */
+    asm volatile ("" : "=m" (UARTSLK_TYPE->SR) : "r" (UARTSLK_TYPE->SR)); // force non-optimizable reads
+    asm volatile ("" : "=m" (UARTSLK_TYPE->DR) : "r" (UARTSLK_TYPE->DR)); // of these two registers
+  }
+}
+
+void uartslkTxenFlowctrlIsr()
+{
+  EXTI_ClearFlag(UARTSLK_TXEN_EXTI);
+  if (GPIO_ReadInputDataBit(UARTSLK_TXEN_PORT, UARTSLK_TXEN_PIN) == Bit_SET)
+  {
+    uartslkPauseDma();
+    //ledSet(LED_GREEN_R, 1);
+  }
+  else
+  {
+    uartslkResumeDma();
+    //ledSet(LED_GREEN_R, 0);
+  }
+}
+
+void __attribute__((used)) EXTI4_Callback(void)
+{
+  uartslkTxenFlowctrlIsr();
+}
+
+void __attribute__((used)) USART6_IRQHandler(void)
+{
+  uartslkIsr();
+}
+
+void __attribute__((used)) DMA2_Stream7_IRQHandler(void)
+{
+  uartslkDmaIsr();
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/watchdog.c b/crazyflie-firmware-src/src/drivers/src/watchdog.c
new file mode 100644
index 0000000000000000000000000000000000000000..46cf084b9782ce1208f5182346a406a90ba75607
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/watchdog.c
@@ -0,0 +1,79 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * @file watchdog.c - Implementaion of hardware watchdog
+ *
+ */
+#define DEBUG_MODULE "SYS"
+
+#include "debug.h"
+
+#include "watchdog.h"
+#include "cfassert.h"
+
+
+bool watchdogNormalStartTest(void)
+{
+  bool wasNormalStart = true;
+
+	if (RCC_GetFlagStatus(RCC_FLAG_IWDGRST)) {
+		RCC_ClearFlag();
+		wasNormalStart = false;
+		DEBUG_PRINT("The system resumed after watchdog timeout [WARNING]\n");
+		printAssertSnapshotData();
+	}
+
+	return wasNormalStart;
+}
+
+
+void watchdogInit(void)
+{
+  IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
+
+  // The watchdog uses the LSI oscillator for checking the timeout. The LSI
+  // oscillator frequency is not very exact and the range is fairly large
+  // and also differs between the Crazyflie 1.0 and 2.0:
+  //                 MIN  TYP  MAX
+  // Crazyflie 1.0   30   40   60   (in kHz)
+  // Crazyflie 2.0   17   32   47   (in kHz)
+  //
+  IWDG_SetPrescaler(IWDG_Prescaler_32);
+  // Divide the clock with 32 which gives
+  // an interval of 17kHz/32 (CF2 min) to 60kHz/32 (CF1 max) =>
+  // 1875 Hz to 531 Hz for the watchdog timer.
+  //
+  // The goal timeout is >100 ms, but it's acceptable
+  // that the max timeout is a bit higher. Scaling the
+  // reload counter for the fastest LSI then gives a
+  // timeout of 100ms, which in turn gives a timeout
+  // of 353ms for the slowest LSI. So the watchdog timeout
+  // will be between 100ms and 353ms on all platforms.
+  //
+  // At prescaler 32 each bit is 1 ms this gives:
+  // 1875 Hz * 0.1 s / 1 => 188
+  IWDG_SetReload(188);
+
+  watchdogReset();
+  IWDG_Enable();
+}
diff --git a/crazyflie-firmware-src/src/drivers/src/ws2812_cf2.c b/crazyflie-firmware-src/src/drivers/src/ws2812_cf2.c
new file mode 100644
index 0000000000000000000000000000000000000000..6d5d52129246163e2fae82a8a2ab3f793884627d
--- /dev/null
+++ b/crazyflie-firmware-src/src/drivers/src/ws2812_cf2.c
@@ -0,0 +1,243 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2014 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * ws2812.c: Neopixel LED driver
+ * Mostly from Elia's electonic blog: http://eliaselectronics.com/driving-a-ws2812-rgb-led-with-an-stm32/
+ */
+
+#include <string.h>
+
+// ST lib includes
+#include "stm32fxxx.h"
+
+#include "nvicconf.h"
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+
+//#define TIM1_CCR1_Address 0x40012C34	// physical memory address of Timer 3 CCR1 register
+
+static TIM_TimeBaseInitTypeDef  TIM_TimeBaseStructure;
+static TIM_OCInitTypeDef  TIM_OCInitStructure;
+static GPIO_InitTypeDef GPIO_InitStructure;
+static DMA_InitTypeDef DMA_InitStructure;
+static NVIC_InitTypeDef NVIC_InitStructure;
+
+static xSemaphoreHandle allLedDone = NULL;
+
+// The minimum is to have 2 leds (1 per half buffer) in the buffer, this
+// consume 42Bytes and will trigger the DMA interrupt at ~2KHz.
+// Putting 2 there will divide by 2 the interrupt frequency but will also
+// double the memory consumption (no free lunch ;-)
+#define LED_PER_HALF 1
+
+#define TIMING_ONE  75
+#define TIMING_ZERO 29
+
+static union {
+    uint16_t buffer[2*LED_PER_HALF*24];
+    struct {
+      uint16_t begin[LED_PER_HALF*24];
+      uint16_t end[LED_PER_HALF*24];
+    } __attribute__((packed));
+} led_dma;
+
+void ws2812Init(void)
+{
+	uint16_t PrescalerValue;
+
+  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
+	/* GPIOB Configuration: TIM3 Channel 1 as alternate function push-pull */
+  // Configure the GPIO PB4 for the timer output
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_NOPULL;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+  GPIO_InitStructure.GPIO_PuPd  = GPIO_PuPd_DOWN;
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  //Map timer to alternate functions
+  GPIO_PinAFConfig(GPIOB, GPIO_PinSource5, GPIO_AF_TIM3);
+
+	/* Compute the prescaler value */
+	PrescalerValue = 0;
+	/* Time base configuration */
+	TIM_TimeBaseStructure.TIM_Period = (105 - 1); // 800kHz
+	TIM_TimeBaseStructure.TIM_Prescaler = PrescalerValue;
+	TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+	TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+	TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
+
+	/* PWM1 Mode configuration: Channel1 */
+	TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+  TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+	TIM_OCInitStructure.TIM_Pulse = 0;
+	TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+	TIM_OC2Init(TIM3, &TIM_OCInitStructure);
+
+//  TIM_Cmd(TIM3, ENABLE);                      // Go!!!
+	TIM_OC2PreloadConfig(TIM3, TIM_OCPreload_Enable);
+	TIM_CtrlPWMOutputs(TIM3, ENABLE);           // enable Timer 3
+
+	/* configure DMA */
+	/* DMA clock enable */
+	RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE);
+
+	/* DMA1 Channel2 Config */
+	DMA_DeInit(DMA1_Stream5);
+
+  // USART TX DMA Channel Config
+  DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR2;
+  DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)led_dma.buffer;    // this is the buffer memory
+  DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+  DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
+  DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+  DMA_InitStructure.DMA_BufferSize = 0;
+  DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+  DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+  DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+  DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
+  DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+  DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
+  DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable;
+  DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
+  DMA_InitStructure.DMA_Channel = DMA_Channel_5;
+	DMA_Init(DMA1_Stream5, &DMA_InitStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannel = DMA1_Stream5_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_LOW_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  DMA_ITConfig(DMA1_Stream5, DMA_IT_TC, ENABLE);
+  DMA_ITConfig(DMA1_Stream5, DMA_IT_HT, ENABLE);
+
+	/* TIM3 CC2 DMA Request enable */
+	TIM_DMACmd(TIM3, TIM_DMA_CC2, ENABLE);
+
+	vSemaphoreCreateBinary(allLedDone);
+
+}
+
+static void fillLed(uint16_t *buffer, uint8_t *color)
+{
+    int i;
+
+    for(i=0; i<8; i++) // GREEN data
+	{
+	    buffer[i] = ((color[1]<<i) & 0x0080) ? TIMING_ONE:TIMING_ZERO;
+	}
+	for(i=0; i<8; i++) // RED
+	{
+	    buffer[8+i] = ((color[0]<<i) & 0x0080) ? TIMING_ONE:TIMING_ZERO;
+	}
+	for(i=0; i<8; i++) // BLUE
+	{
+	    buffer[16+i] = ((color[2]<<i) & 0x0080) ? TIMING_ONE:TIMING_ZERO;
+	}
+}
+
+static int current_led = 0;
+static int total_led = 0;
+static uint8_t (*color_led)[3] = NULL;
+
+void ws2812Send(uint8_t (*color)[3], int len)
+{
+    int i;
+	if(len<1) return;
+
+	//Wait for previous transfer to be finished
+	xSemaphoreTake(allLedDone, portMAX_DELAY);
+
+	// Set interrupt context ...
+	current_led = 0;
+	total_led = len;
+	color_led = color;
+
+    for(i=0; (i<LED_PER_HALF) && (current_led<total_led+2); i++, current_led++) {
+        if (current_led<total_led)
+            fillLed(led_dma.begin+(24*i), color_led[current_led]);
+        else
+            bzero(led_dma.begin+(24*i), sizeof(led_dma.begin));
+    }
+
+    for(i=0; (i<LED_PER_HALF) && (current_led<total_led+2); i++, current_led++) {
+        if (current_led<total_led)
+            fillLed(led_dma.end+(24*i), color_led[current_led]);
+        else
+            bzero(led_dma.end+(24*i), sizeof(led_dma.end));
+    }
+
+	DMA1_Stream5->NDTR = sizeof(led_dma.buffer) / sizeof(led_dma.buffer[0]); // load number of bytes to be transferred
+	DMA_Cmd(DMA1_Stream5, ENABLE); 			// enable DMA channel 2
+	TIM_Cmd(TIM3, ENABLE);                      // Go!!!
+}
+
+void ws2812DmaIsr(void)
+{
+    portBASE_TYPE xHigherPriorityTaskWoken;
+    uint16_t * buffer;
+    int i;
+
+    if (total_led == 0)
+    {
+      TIM_Cmd(TIM3, DISABLE);
+    	DMA_Cmd(DMA1_Stream5, DISABLE);
+    }
+
+    if (DMA_GetITStatus(DMA1_Stream5, DMA_IT_HTIF5))
+    {
+      DMA_ClearITPendingBit(DMA1_Stream5, DMA_IT_HTIF5);
+      buffer = led_dma.begin;
+    }
+
+    if (DMA_GetITStatus(DMA1_Stream5, DMA_IT_TCIF5))
+    {
+      DMA_ClearITPendingBit(DMA1_Stream5, DMA_IT_TCIF5);
+      buffer = led_dma.end;
+    }
+
+    for(i=0; (i<LED_PER_HALF) && (current_led<total_led+2); i++, current_led++) {
+      if (current_led<total_led)
+          fillLed(buffer+(24*i), color_led[current_led]);
+      else
+          bzero(buffer+(24*i), sizeof(led_dma.end));
+    }
+
+    if (current_led >= total_led+2) {
+      xSemaphoreGiveFromISR(allLedDone, &xHigherPriorityTaskWoken);
+
+	    TIM_Cmd(TIM3, DISABLE); 					// disable Timer 3
+	    DMA_Cmd(DMA1_Stream5, DISABLE); 			// disable DMA stream4
+
+	    total_led = 0;
+    }
+}
diff --git a/crazyflie-firmware-src/src/hal/interface/buzzer.h b/crazyflie-firmware-src/src/hal/interface/buzzer.h
new file mode 100644
index 0000000000000000000000000000000000000000..07331ad18f4336f069e46335c80c57f2b2171176
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/buzzer.h
@@ -0,0 +1,65 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * buzzdeck.h - Functions for interfacing with decks with buzzers
+ */
+#ifndef __BUZZER_H__
+#define __BUZZER_H__
+ 
+#include <stdint.h>
+#include <stdbool.h>
+
+/** Functionpointers used to control the buzzer */
+struct buzzerControl
+{
+  void (*off)();
+  void (*on)(uint32_t freq);
+};
+
+/**
+ * Initilize the buzzer sub-system.
+ */
+void buzzerInit();
+
+/**
+ * Test the buzzer sub-system.
+ */
+bool buzzerTest();
+
+/**
+ * Turn the buzzer off.
+ */
+void buzzerOff();
+
+/**
+ * Turn the buzzer on and set it to a specific frequency (if supported).
+ */
+void buzzerOn(uint32_t freq);
+
+/**
+ * Set function pointers for controlling the buzzer hardware.
+ */
+void buzzerSetControl(struct buzzerControl * bc);
+
+#endif //__BUZZER_H__
+
diff --git a/crazyflie-firmware-src/src/hal/interface/eskylink.h b/crazyflie-firmware-src/src/hal/interface/eskylink.h
new file mode 100644
index 0000000000000000000000000000000000000000..062a4799bec95cc268603906a8deeab3adc5692c
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/eskylink.h
@@ -0,0 +1,37 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * eskylink.h: esky 2.4GHz-compatible link driver
+ */
+
+#ifndef __ESKYLINK_H__
+#define __ESKYLINK_H__
+
+#include "crtp.h"
+
+void eskylinkInit();
+bool eskylinkTest();
+struct crtpLinkOperations * eskylinkGetLink();
+void eskylinkReInit(void);
+
+#endif
diff --git a/crazyflie-firmware-src/src/hal/interface/freeRTOSdebug.h b/crazyflie-firmware-src/src/hal/interface/freeRTOSdebug.h
new file mode 100644
index 0000000000000000000000000000000000000000..c6dfeba710701e2e1d8f8d6456835c64ba899b25
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/freeRTOSdebug.h
@@ -0,0 +1,42 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * debug.h - Various debug functions
+ */
+#ifndef DEBUG_H_
+#define DEBUG_H_
+
+/**
+ * Initializes peripherals used for creating trace
+ * information
+ */
+void debugInitTrace(void);
+
+/**
+ * Sends trace information using the UART1. This function is
+ * used with the freertos traceTASK_SWITCHED_IN() macro.
+ * @param Task number currently running
+ */
+void debugSendTraceInfo(unsigned int taskNbr);
+
+#endif /* DEBUG_H_ */
diff --git a/crazyflie-firmware-src/src/hal/interface/imu.h b/crazyflie-firmware-src/src/hal/interface/imu.h
new file mode 100644
index 0000000000000000000000000000000000000000..60467e400e8e67a16dac42d1a36cf8606628f094
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/imu.h
@@ -0,0 +1,65 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * imu.h - inertial measurement unit header file
+ */
+#ifndef IMU_H_
+#define IMU_H_
+#include <stdbool.h>
+#include "filter.h"
+#include "imu_types.h"
+
+/**
+ * IMU update frequency dictates the overall update frequency.
+ */
+#define IMU_UPDATE_FREQ   500
+#define IMU_UPDATE_DT     (float)(1.0/IMU_UPDATE_FREQ)
+
+/**
+ * Set ACC_WANTED_LPF1_CUTOFF_HZ to the wanted cut-off freq in Hz.
+ * The highest cut-off freq that will have any affect is fs /(2*pi).
+ * E.g. fs = 350 Hz -> highest cut-off = 350/(2*pi) = 55.7 Hz -> 55 Hz
+ */
+#define IMU_ACC_WANTED_LPF_CUTOFF_HZ  4
+/**
+ * Attenuation should be between 1 to 256.
+ *
+ * f0 = fs / 2*pi*attenuation ->
+ * attenuation = fs / 2*pi*f0
+ */
+#define IMU_ACC_IIR_LPF_ATTENUATION (IMU_UPDATE_FREQ / (2 * 3.1415 * IMU_ACC_WANTED_LPF_CUTOFF_HZ))
+#define IMU_ACC_IIR_LPF_ATT_FACTOR  (int)(((1<<IIR_SHIFT) / IMU_ACC_IIR_LPF_ATTENUATION) + 0.5)
+
+void imu6Init(void);
+bool imu6Test(void);
+bool imu6ManufacturingTest(void);
+void imu6Read(Axis3f* gyro, Axis3f* acc);
+void imu9Read(Axis3f* gyroOut, Axis3f* accOut, Axis3f* magOut);
+bool imu6IsCalibrated(void);
+bool imuHasBarometer(void);
+bool imuHasMangnetometer(void);
+
+
+
+#endif /* IMU_H_ */
diff --git a/crazyflie-firmware-src/src/hal/interface/imu_types.h b/crazyflie-firmware-src/src/hal/interface/imu_types.h
new file mode 100644
index 0000000000000000000000000000000000000000..f027b7b0cb2198105fe1ab296520195bfd493d75
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/imu_types.h
@@ -0,0 +1,66 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * imu_types.h - Types used by IMU and releted functions.
+ */
+#ifndef IMU_TYPES_H_
+#define IMU_TYPES_H_
+
+ typedef union {
+   struct {
+         int16_t x;
+         int16_t y;
+         int16_t z;
+   };
+   int16_t axis[3];
+ } Axis3i16;
+
+ typedef union {
+   struct {
+         int32_t x;
+         int32_t y;
+         int32_t z;
+   };
+   int32_t axis[3];
+ } Axis3i32;
+
+ typedef union {
+   struct {
+         int64_t x;
+         int64_t y;
+         int64_t z;
+   };
+   int64_t axis[3];
+ } Axis3i64;
+
+ typedef union {
+   struct {
+         float x;
+         float y;
+         float z;
+   };
+   float axis[3];
+ } Axis3f;
+
+#endif /* IMU_TYPES_H_ */
diff --git a/crazyflie-firmware-src/src/hal/interface/ledseq.h b/crazyflie-firmware-src/src/hal/interface/ledseq.h
new file mode 100644
index 0000000000000000000000000000000000000000..609fd0544f9fc9dda8f5c4585772fd2e006ddbb3
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/ledseq.h
@@ -0,0 +1,81 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/*
+ * ledseq.h - LED sequence handler
+ */
+
+#ifndef __LEDSEQ_H__
+#define __LEDSEQ_H__
+
+/* A LED sequence is made of a list of actions. Each action contains the new
+ * state of the LED and either a time to wait before executing the next action
+ * or a command LOOP or STOP.
+ *
+ * The sequences are stored in a list by priority order ([0] is the highest
+ * priority). The list ordered by priority is defined at the beginning of
+ * ledseq.c
+ *
+ * Each sequence effects only one LED. For each LED only the runnable sequence
+ * with the highest priority is run.
+ */
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <led.h>
+
+#define LEDSEQ_CHARGE_CYCLE_TIME_500MA  1000
+#define LEDSEQ_CHARGE_CYCLE_TIME_MAX    500
+//Led sequence action
+#define LEDSEQ_WAITMS(X) (X)
+#define LEDSEQ_STOP      -1
+#define LEDSEQ_LOOP      -2
+typedef struct {
+  bool value;
+  int action;
+} ledseq_t;
+
+//Public API
+void ledseqInit(void);
+bool ledseqTest(void);
+
+void ledseqEnable(bool enable);
+void ledseqRun(led_t led, const ledseq_t * sequence);
+void ledseqStop(led_t led, const ledseq_t * sequence);
+void ledseqSetTimes(ledseq_t *sequence, int32_t onTime, int32_t offTime);
+
+//Existing led sequences
+extern const ledseq_t seq_armed[];
+extern const ledseq_t seq_calibrated[];
+extern const ledseq_t seq_alive[];
+extern const ledseq_t seq_lowbat[];
+extern const ledseq_t seq_linkup[];
+extern const ledseq_t seq_altHold[];
+extern const ledseq_t seq_charged[];
+extern ledseq_t seq_charging[];
+extern ledseq_t seq_chargingMax[];
+extern const ledseq_t seq_bootloader[];
+extern const ledseq_t seq_testPassed[];
+
+#endif
diff --git a/crazyflie-firmware-src/src/hal/interface/nrf24link.h b/crazyflie-firmware-src/src/hal/interface/nrf24link.h
new file mode 100644
index 0000000000000000000000000000000000000000..525857e8987d95afeb9ac4dc19cf6ef14d3d3885
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/nrf24link.h
@@ -0,0 +1,37 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nrf24link.c: nRF24L01 implementation of the CRTP link
+ */
+
+#ifndef __NRF24LINK_H__
+#define __NRF24LINK_H__
+
+#include "crtp.h"
+
+void nrf24linkInit();
+bool nrf24linkTest();
+struct crtpLinkOperations * nrf24linkGetLink();
+void nrf24linkReInit(void);
+
+#endif
diff --git a/crazyflie-firmware-src/src/hal/interface/ow.h b/crazyflie-firmware-src/src/hal/interface/ow.h
new file mode 100644
index 0000000000000000000000000000000000000000..f4b90c04f0f3b96e2a881932b17e22f30be9e618
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/ow.h
@@ -0,0 +1,75 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * ow.h - One-wire functions
+ */
+#ifndef __OW_H__
+#define __OW_H__
+ 
+#include <stdint.h>
+#include "syslink.h"
+
+#define OW_MAX_SIZE        112
+#define OW_READ_SIZE       29
+#define OW_MAX_WRITE_SIZE  26 // Use even numbers because of 16bits segments
+
+typedef struct owCommand_s {
+  uint8_t nmem;
+  union {
+    struct {
+      uint8_t memId[8];
+    } __attribute__((packed)) info;
+    struct  {
+      uint16_t address;
+      uint8_t data[29];
+    } __attribute__((packed)) read;
+    struct write {
+      uint16_t address;
+      uint16_t length;
+      char data[27];
+    } __attribute__((packed)) write;
+  };
+} __attribute__((packed)) OwCommand;
+
+typedef struct owSerialNum_s
+{
+  union {
+    struct {
+      uint8_t type;
+      uint8_t id[6];
+      uint8_t crc;
+    };
+    uint8_t data[8];
+  };
+} OwSerialNum;
+
+void owInit();
+bool owTest();
+void owSyslinkRecieve(SyslinkPacket *slp);
+bool owScan(uint8_t *nMem);
+bool owGetinfo(uint8_t selectMem, OwSerialNum *serialNum);
+bool owRead(uint8_t selectMem, uint16_t address, uint8_t length, uint8_t *data);
+bool owWrite(uint8_t selectMem, uint16_t address, uint8_t length, uint8_t *data);
+
+#endif //__OW_H__
+
diff --git a/crazyflie-firmware-src/src/hal/interface/pm.h b/crazyflie-firmware-src/src/hal/interface/pm.h
new file mode 100644
index 0000000000000000000000000000000000000000..7179d226335e5f94598b4b632a7e5e23e560260a
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/pm.h
@@ -0,0 +1,161 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * pm.h - Power Management driver and functions.
+ */
+
+#ifndef PM_H_
+#define PM_H_
+
+#include "adc.h"
+#include "syslink.h"
+
+#ifndef CRITICAL_LOW_VOLTAGE
+  #define PM_BAT_CRITICAL_LOW_VOLTAGE   3.0f
+#else
+  #define PM_BAT_CRITICAL_LOW_VOLTAGE   CRITICAL_LOW_VOLTAGE
+#endif
+#ifndef CRITICAL_LOW_TIMEOUT
+  #define PM_BAT_CRITICAL_LOW_TIMEOUT   M2T(1000 * 5) // 5 sec default
+#else
+  #define PM_BAT_CRITICAL_LOW_TIMEOUT   CRITICAL_LOW_VOLTAGE
+#endif
+
+#ifndef LOW_VOLTAGE
+  #define PM_BAT_LOW_VOLTAGE   3.2f
+#else
+  #define PM_BAT_LOW_VOLTAGE   LOW_VOLTAGE
+#endif
+#ifndef LOW_TIMEOUT
+  #define PM_BAT_LOW_TIMEOUT   M2T(1000 * 5) // 5 sec default
+#else
+  #define PM_BAT_LOW_TIMEOUT   LOW_TIMEOUT
+#endif
+
+#ifndef SYSTEM_SHUTDOWN_TIMEOUT
+  #define PM_SYSTEM_SHUTDOWN_TIMEOUT    M2T(1000 * 60 * 5) // 5 min default
+#else
+  #define PM_SYSTEM_SHUTDOWN_TIMEOUT    M2T(1000 * 60 * SYSTEM_SHUTDOWN_TIMEOUT)
+#endif
+
+#define PM_BAT_DIVIDER                3.0f
+#define PM_BAT_ADC_FOR_3_VOLT         (int32_t)(((3.0f / PM_BAT_DIVIDER) / 2.8f) * 4096)
+#define PM_BAT_ADC_FOR_1p2_VOLT       (int32_t)(((1.2f / PM_BAT_DIVIDER) / 2.8f) * 4096)
+
+#define PM_BAT_IIR_SHIFT     8
+/**
+ * Set PM_BAT_WANTED_LPF_CUTOFF_HZ to the wanted cut-off freq in Hz.
+ */
+#define PM_BAT_WANTED_LPF_CUTOFF_HZ   1
+
+/**
+ * Attenuation should be between 1 to 256.
+ *
+ * f0 = fs / 2*pi*attenuation.
+ * attenuation = fs / 2*pi*f0
+ */
+#define PM_BAT_IIR_LPF_ATTENUATION (int)(ADC_SAMPLING_FREQ / (int)(2 * 3.1415f * PM_BAT_WANTED_LPF_CUTOFF_HZ))
+#define PM_BAT_IIR_LPF_ATT_FACTOR  (int)((1<<PM_BAT_IIR_SHIFT) / PM_BAT_IIR_LPF_ATTENUATION)
+
+typedef enum
+{
+  battery,
+  charging,
+  charged,
+  lowPower,
+  shutDown,
+} PMStates;
+
+typedef enum
+{
+  charge100mA,
+  charge500mA,
+  chargeMax,
+} PMChargeStates;
+
+typedef enum
+{
+  USBNone,
+  USB500mA,
+  USBWallAdapter,
+} PMUSBPower;
+
+void pmInit(void);
+
+bool pmTest(void);
+
+/**
+ * Power management task
+ */
+void pmTask(void *param);
+
+void pmSetChargeState(PMChargeStates chgState);
+void pmSyslinkUpdate(SyslinkPacket *slp);
+
+/**
+ * Returns the battery voltage i volts as a float
+ */
+float pmGetBatteryVoltage(void);
+
+/**
+ * Returns the min battery voltage i volts as a float
+ */
+float pmGetBatteryVoltageMin(void);
+
+/**
+ * Returns the max battery voltage i volts as a float
+ */
+float pmGetBatteryVoltageMax(void);
+
+/**
+ * Updates and calculates battery values.
+ * Should be called for every new adcValues sample.
+ */
+void pmBatteryUpdate(AdcGroup* adcValues);
+
+/**
+ * Returns true if the battery is currently in use
+ */
+bool pmIsDischarging(void);
+
+/**
+ * Enable or disable external battery voltage measuring.
+ */
+void pmEnableExtBatteryVoltMeasuring(uint8_t pin, float multiplier);
+
+/**
+ * Measure an external voltage.
+ */
+float pmMeasureExtBatteryVoltage(void);
+
+/**
+ * Enable or disable external battery current measuring.
+ */
+void pmEnableExtBatteryCurrMeasuring(uint8_t pin, float ampPerVolt);
+
+/**
+ * Measure an external current.
+ */
+float pmMeasureExtBatteryCurrent(void);
+
+#endif /* PM_H_ */
diff --git a/crazyflie-firmware-src/src/hal/interface/proximity.h b/crazyflie-firmware-src/src/hal/interface/proximity.h
new file mode 100644
index 0000000000000000000000000000000000000000..749a08d2449ffe2433e04cb26e062e0b2e3c812b
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/proximity.h
@@ -0,0 +1,74 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * proximity.h - Interface to hardware abstraction layer for proximity sensors
+ */
+
+#ifndef __PROXIMITY_H__
+#define __PROXIMITY_H__
+
+#include <stdint.h>
+
+/**
+ * \def PROXIMITY_ENABLED
+ * Enable the proximity measurement subsystem.
+ */
+//#define PROXIMITY_ENABLED
+
+/**
+ * \def PROXIMITY_TASK_FREQ
+ * The frequency the proximity task runs at. This is the same as the sampling frequency for the distance measurements.
+ *
+ * Of the supported sensor, the following maximum frequencies apply:
+ *
+ *    MaxBotix LV-MaxSonar-EZ4 (MB1040): 20Hz
+ */
+#define PROXIMITY_TASK_FREQ 20
+
+/**
+ * Number of samples in the sliding window. Used for average and median calculations.
+ * When using median calculations, this should be an odd number.
+ *
+ * Initial testing suggests the following values:
+ *
+ *    MaxBotix LV-MaxSonar-EZ4 (MB1040): 9 (for median values, with PROXIMITY_TASK_FREQ=20Hz)
+ */
+#define PROXIMITY_SWIN_SIZE 9
+
+/**
+ * \def PROXIMITY_LOG_ENABLED
+ * Uncomment to enable log variables.
+ */
+//#define PROXIMITY_LOG_ENABLED
+
+void proximityInit(void);
+
+uint32_t proximityGetDistance(void);
+
+uint32_t proximityGetDistanceAvg(void);
+
+uint32_t proximityGetDistanceMedian(void);
+
+uint32_t proximityGetAccuracy(void);
+
+#endif
diff --git a/crazyflie-firmware-src/src/hal/interface/radiolink.h b/crazyflie-firmware-src/src/hal/interface/radiolink.h
new file mode 100644
index 0000000000000000000000000000000000000000..65361385821d35ccd6a553661ebfe2052263e17f
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/radiolink.h
@@ -0,0 +1,43 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * radiolink.c - Radio link layer
+ */
+
+#ifndef __RADIO_H__
+#define __RADIO_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "syslink.h"
+
+void radiolinkInit(void);
+bool radiolinkTest(void);
+void radiolinkSetChannel(uint8_t channel);
+void radiolinkSetDatarate(uint8_t datarate);
+void radiolinkSetAddress(uint64_t address);
+void radiolinkSyslinkDispatch(SyslinkPacket *slp);
+struct crtpLinkOperations * radiolinkGetLink();
+
+
+#endif //__RADIO_H__
diff --git a/crazyflie-firmware-src/src/hal/interface/sensors.h b/crazyflie-firmware-src/src/hal/interface/sensors.h
new file mode 100644
index 0000000000000000000000000000000000000000..c3d87fae578dc7062bc092aed3907c481dc90992
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/sensors.h
@@ -0,0 +1,49 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sensors.h - Sensors interface
+ */
+#ifndef __SENSORS_H__
+#define __SENSORS_H__
+
+#include "stabilizer_types.h"
+
+void sensorsInit(void);
+bool sensorsTest(void);
+bool sensorsAreCalibrated(void);
+
+/**
+ * More extensive test of the sensors
+ */
+bool sensorsManufacturingTest(void);
+
+// For legacy control
+void sensorsAcquire(sensorData_t *sensors, const uint32_t tick);
+
+// Allows individual sensor measurement
+bool sensorsReadGyro(Axis3f *gyro);
+bool sensorsReadAcc(Axis3f *acc);
+bool sensorsReadMag(Axis3f *mag);
+bool sensorsReadBaro(baro_t *baro);
+
+#endif //__SENSORS_H__
diff --git a/crazyflie-firmware-src/src/hal/interface/syslink.h b/crazyflie-firmware-src/src/hal/interface/syslink.h
new file mode 100644
index 0000000000000000000000000000000000000000..140182c6f9232d851843350b3b3b62c368a50201
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/syslink.h
@@ -0,0 +1,86 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * syslink.h: Implementation of the link between MCU
+ */
+
+#ifndef __SYSLINK_H__
+#define __SYSLINK_H__
+
+#include <stdbool.h>
+
+#define SYSLINK_MTU 32
+
+#define CRTP_START_BYTE  0xAA
+#define SYSLINK_START_BYTE1 0xBC
+#define SYSLINK_START_BYTE2 0xCF
+
+// Defined packet types
+#define SYSLINK_GROUP_MASK    0xF0
+
+#define SYSLINK_RADIO_GROUP         0x00
+#define SYSLINK_RADIO_RAW           0x00
+#define SYSLINK_RADIO_CHANNEL       0x01
+#define SYSLINK_RADIO_DATARATE      0x02
+#define SYSLINK_RADIO_CONTWAVE      0x03
+#define SYSLINK_RADIO_RSSI          0x04
+#define SYSLINK_RADIO_ADDRESS       0x05
+#define SYSLINK_RADIO_RAW_BROADCAST 0x06
+
+#define SYSLINK_PM_GROUP              0x10
+#define SYSLINK_PM_SOURCE             0x10
+#define SYSLINK_PM_ONOFF_SWITCHOFF    0x11
+#define SYSLINK_PM_BATTERY_VOLTAGE    0x12
+#define SYSLINK_PM_BATTERY_STATE      0x13
+#define SYSLINK_PM_BATTERY_AUTOUPDATE 0x14
+
+#define SYSLINK_OW_GROUP    0x20
+#define SYSLINK_OW_SCAN     0x20
+#define SYSLINK_OW_GETINFO  0x21
+#define SYSLINK_OW_READ     0x22
+#define SYSLINK_OW_WRITE    0x23
+
+typedef struct _SyslinkPacket
+{
+  uint8_t type;
+  uint8_t length;
+  char data[SYSLINK_MTU];
+} __attribute__((packed)) SyslinkPacket;
+
+typedef enum
+{
+  waitForFirstStart,
+  waitForSecondStart,
+  waitForType,
+  waitForLengt,
+  waitForData,
+  waitForChksum1,
+  waitForChksum2
+} SyslinkRxState;
+
+
+void syslinkInit();
+bool syslinkTest();
+int syslinkSendPacket(SyslinkPacket *slp);
+
+#endif
diff --git a/crazyflie-firmware-src/src/hal/interface/uart.h b/crazyflie-firmware-src/src/hal/interface/uart.h
new file mode 100644
index 0000000000000000000000000000000000000000..5961c81b78a0aa66b7db8bd118acedc59eed3e0c
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/uart.h
@@ -0,0 +1,117 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart.h - uart CRTP link and raw access functions
+ */
+#ifndef UART_H_
+#define UART_H_
+
+#include <stdbool.h>
+
+#include "crtp.h"
+#include "eprintf.h"
+
+#define UART_TYPE       USART3
+#define UART_PERIF      RCC_APB1Periph_USART3
+
+#define UART_DMA_IRQ    DMA1_Channel2_IRQn
+#define UART_DMA_IT_TC  DMA1_IT_TC2
+#define UART_DMA_CH     DMA1_Channel2
+
+#define UART_GPIO_PERIF RCC_APB2Periph_GPIOB
+#define UART_GPIO_PORT  GPIOB
+#define UART_GPIO_TX    GPIO_Pin_10
+#define UART_GPIO_RX    GPIO_Pin_11
+ 
+/**
+ * Initialize the UART.
+ *
+ * @note Initialize CRTP link only if USE_CRTP_UART is defined
+ */
+void uartInit(void);
+
+/**
+ * Test the UART status.
+ *
+ * @return true if the UART is initialized
+ */
+bool uartTest(void);
+
+/**
+ * Get CRTP link data structure
+ *
+ * @return Address of the crtp link operations structure.
+ */
+struct crtpLinkOperations * uartGetLink();
+
+/**
+ * Sends raw data using a lock. Should be used from
+ * exception functions and for debugging when a lot of data
+ * should be transfered.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+void uartSendData(uint32_t size, uint8_t* data);
+
+/**
+ * Send a single character to the serial port using the uartSendData function.
+ * @param[in] ch Character to print. Only the 8 LSB are used.
+ * @return Character printed
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+int uartPutchar(int ch);
+
+/**
+ * Uart printf macro that uses eprintf
+ * @param[in] FMT String format
+ * @param[in] ... Parameters to print
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+#define uartPrintf(FMT, ...) eprintf(uartPutchar, FMT, ## __VA_ARGS__)
+
+/**
+ * Sends raw data using DMA transfer. Should be used from
+ * exception functions and for debugging when a lot of data
+ * should be transfered.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+void uartSendDataDma(uint32_t size, uint8_t* data);
+
+/**
+ * Interrupt service routine handling UART interrupts.
+ */
+void uartIsr(void);
+
+/**
+ * Interrupt service routine handling UART DMA interrupts.
+ */
+void uartDmaIsr(void);
+
+#endif /* UART_H_ */
diff --git a/crazyflie-firmware-src/src/hal/interface/usb.h b/crazyflie-firmware-src/src/hal/interface/usb.h
new file mode 100644
index 0000000000000000000000000000000000000000..ac64870367baae5c9628863630666dbee2c3b4cd
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/usb.h
@@ -0,0 +1,85 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart.h - uart CRTP link and raw access functions
+ */
+#ifndef USB_H_
+#define USB_H_
+
+#include <stdbool.h>
+#include <stdint.h>
+
+#include "usbd_conf.h"
+
+
+#define USB_RX_TX_PACKET_SIZE   (64)
+
+/* Structure used for in/out data via USB */
+typedef struct
+{
+  uint8_t size;
+  uint8_t data[USB_RX_TX_PACKET_SIZE];
+} USBPacket;
+
+/**
+ * Initialize the UART.
+ *
+ * @note Initialize CRTP link only if USE_CRTP_UART is defined
+ */
+void usbInit(void);
+
+/**
+ * Test the UART status.
+ *
+ * @return true if the UART is initialized
+ */
+bool usbTest(void);
+
+/**
+ * Get CRTP link data structure
+ *
+ * @return Address of the crtp link operations structure.
+ */
+struct crtpLinkOperations * usbGetLink();
+
+/**
+ * Get data from rx queue with timeout.
+ * @param[out] c  Byte of data
+ *
+ * @return true if byte received, false if timout reached.
+ */
+bool usbGetDataBlocking(USBPacket *in);
+
+/**
+ * Sends raw data using a lock. Should be used from
+ * exception functions and for debugging when a lot of data
+ * should be transfered.
+ * @param[in] size  Number of bytes to send
+ * @param[in] data  Pointer to data
+ *
+ * @note If UART Crtp link is activated this function does nothing
+ */
+bool usbSendData(uint32_t size, uint8_t* data);
+
+
+#endif /* UART_H_ */
diff --git a/crazyflie-firmware-src/src/hal/interface/usb_conf.h b/crazyflie-firmware-src/src/hal/interface/usb_conf.h
new file mode 100644
index 0000000000000000000000000000000000000000..573237f1af60db9b35c9c89adf70764a0088be54
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/usb_conf.h
@@ -0,0 +1,313 @@
+/**
+  ******************************************************************************
+  * @file    usb_conf.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   General low level driver configuration
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_CONF__H__
+#define __USB_CONF__H__
+
+#include <sys/cdefs.h>
+
+/* Includes ------------------------------------------------------------------*/
+/*#if defined (USE_STM322xG_EVAL)
+ #include "stm322xg_eval.h"
+ #include "stm322xg_eval_lcd.h"
+ #include "stm322xg_eval_ioe.h"
+ #include "stm322xg_eval_sdio_sd.h"
+#elif defined(USE_STM324xG_EVAL)
+ #include "stm32f4xx.h"
+ #include "stm324xg_eval.h" 
+ #include "stm324xg_eval_lcd.h"
+ #include "stm324xg_eval_ioe.h"
+ #include "stm324xg_eval_sdio_sd.h"
+#elif defined (USE_STM3210C_EVAL)
+ #include "stm32f10x.h"
+ #include "stm3210c_eval.h" 
+ #include "stm3210c_eval_lcd.h"
+ #include "stm3210c_eval_ioe.h"
+ #include "stm3210c_eval_spi_sd.h"
+#else
+ #error "Missing define: Evaluation board (ie. USE_STM322xG_EVAL)"
+#endif*/
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_CONF
+  * @brief USB low level driver configuration file
+  * @{
+  */ 
+
+/** @defgroup USB_CONF_Exported_Defines
+  * @{
+  */ 
+
+/* USB Core and PHY interface configuration.
+   Tip: To avoid modifying these defines each time you need to change the USB
+        configuration, you can declare the needed define in your toolchain
+        compiler preprocessor.
+   */
+/****************** USB OTG FS PHY CONFIGURATION *******************************
+*  The USB OTG FS Core supports one on-chip Full Speed PHY.
+*  
+*  The USE_EMBEDDED_PHY symbol is defined in the project compiler preprocessor 
+*  when FS core is used.
+*******************************************************************************/
+#ifndef USE_USB_OTG_FS
+ #define USE_USB_OTG_FS
+#endif /* USE_USB_OTG_FS */
+
+#ifdef USE_USB_OTG_FS 
+ #define USB_OTG_FS_CORE
+#endif
+
+/****************** USB OTG HS PHY CONFIGURATION *******************************
+*  The USB OTG HS Core supports two PHY interfaces:
+*   (i)  An ULPI interface for the external High Speed PHY: the USB HS Core will 
+*        operate in High speed mode
+*   (ii) An on-chip Full Speed PHY: the USB HS Core will operate in Full speed mode
+*
+*  You can select the PHY to be used using one of these two defines:
+*   (i)  USE_ULPI_PHY: if the USB OTG HS Core is to be used in High speed mode 
+*   (ii) USE_EMBEDDED_PHY: if the USB OTG HS Core is to be used in Full speed mode
+*
+*  Notes: 
+*   - The USE_ULPI_PHY symbol is defined in the project compiler preprocessor as 
+*     default PHY when HS core is used.
+*   - On STM322xG-EVAL and STM324xG-EVAL boards, only configuration(i) is available.
+*     Configuration (ii) need a different hardware, for more details refer to your
+*     STM32 device datasheet.
+*******************************************************************************/
+#ifndef USE_USB_OTG_HS
+ //#define USE_USB_OTG_HS
+#endif /* USE_USB_OTG_HS */
+
+#ifndef USE_ULPI_PHY
+ //#define USE_ULPI_PHY
+#endif /* USE_ULPI_PHY */
+
+#ifndef USE_EMBEDDED_PHY
+ //#define USE_EMBEDDED_PHY
+#endif /* USE_EMBEDDED_PHY */
+
+#ifdef USE_USB_OTG_HS 
+ #define USB_OTG_HS_CORE
+#endif
+
+/*******************************************************************************
+*                      FIFO Size Configuration in Device mode
+*  
+*  (i) Receive data FIFO size = RAM for setup packets + 
+*                   OUT endpoint control information +
+*                   data OUT packets + miscellaneous
+*      Space = ONE 32-bits words
+*     --> RAM for setup packets = 10 spaces
+*        (n is the nbr of CTRL EPs the device core supports) 
+*     --> OUT EP CTRL info      = 1 space
+*        (one space for status information written to the FIFO along with each 
+*        received packet)
+*     --> data OUT packets      = (Largest Packet Size / 4) + 1 spaces 
+*        (MINIMUM to receive packets)
+*     --> OR data OUT packets  = at least 2*(Largest Packet Size / 4) + 1 spaces 
+*        (if high-bandwidth EP is enabled or multiple isochronous EPs)
+*     --> miscellaneous = 1 space per OUT EP
+*        (one space for transfer complete status information also pushed to the 
+*        FIFO with each endpoint's last packet)
+*
+*  (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for 
+*       that particular IN EP. More space allocated in the IN EP Tx FIFO results
+*       in a better performance on the USB and can hide latencies on the AHB.
+*
+*  (iii) TXn min size = 16 words. (n  : Transmit FIFO index)
+*   (iv) When a TxFIFO is not used, the Configuration should be as follows: 
+*       case 1 :  n > m    and Txn is not used    (n,m  : Transmit FIFO indexes)
+*       --> Txm can use the space allocated for Txn.
+*       case2  :  n < m    and Txn is not used    (n,m  : Transmit FIFO indexes)
+*       --> Txn should be configured with the minimum space of 16 words
+*  (v) The FIFO is used optimally when used TxFIFOs are allocated in the top 
+*       of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
+*   (vi) In HS case 12 FIFO locations should be reserved for internal DMA registers
+*        so total FIFO size should be 1012 Only instead of 1024       
+*******************************************************************************/
+ 
+/****************** USB OTG HS CONFIGURATION **********************************/
+#ifdef USB_OTG_HS_CORE
+ #define RX_FIFO_HS_SIZE                          512
+ #define TX0_FIFO_HS_SIZE                          64
+ #define TX1_FIFO_HS_SIZE                         372
+ #define TX2_FIFO_HS_SIZE                          64
+ #define TX3_FIFO_HS_SIZE                           0
+ #define TX4_FIFO_HS_SIZE                           0
+ #define TX5_FIFO_HS_SIZE                           0
+
+// #define USB_OTG_HS_SOF_OUTPUT_ENABLED
+
+ #ifdef USE_ULPI_PHY
+  #define USB_OTG_ULPI_PHY_ENABLED
+ #endif
+ #ifdef USE_EMBEDDED_PHY 
+   #define USB_OTG_EMBEDDED_PHY_ENABLED
+   /* wakeup is working only when HS core is configured in FS mode */
+   #define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT
+ #endif
+ /* #define USB_OTG_HS_INTERNAL_DMA_ENABLED */ /* Be aware that enabling DMA mode will result in data being sent only by
+                                                  multiple of 4 packet sizes. This is due to the fact that USB DMA does
+                                                  not allow sending data from non word-aligned addresses.
+                                                  For this specific application, it is advised to not enable this option
+                                                  unless required. */
+ #define USB_OTG_HS_DEDICATED_EP1_ENABLED
+#endif
+
+/****************** USB OTG FS CONFIGURATION **********************************/
+#ifdef USB_OTG_FS_CORE
+ #define RX_FIFO_FS_SIZE                          128
+ #define TX0_FIFO_FS_SIZE                          32
+ #define TX1_FIFO_FS_SIZE                         128
+ #define TX2_FIFO_FS_SIZE                          32 
+ #define TX3_FIFO_FS_SIZE                           0
+
+// #define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT
+// #define USB_OTG_FS_SOF_OUTPUT_ENABLED
+#endif
+
+/****************** USB OTG MISC CONFIGURATION ********************************/
+//#define VBUS_SENSING_ENABLED
+
+/****************** USB OTG MODE CONFIGURATION ********************************/
+//#define USE_HOST_MODE
+#define USE_DEVICE_MODE
+//#define USE_OTG_MODE
+
+#ifndef USB_OTG_FS_CORE
+ #ifndef USB_OTG_HS_CORE
+    #error  "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined"
+ #endif
+#endif
+
+#ifndef USE_DEVICE_MODE
+ #ifndef USE_HOST_MODE
+    #error  "USE_DEVICE_MODE or USE_HOST_MODE should be defined"
+ #endif
+#endif
+
+#ifndef USE_USB_OTG_HS
+ #ifndef USE_USB_OTG_FS
+    #error  "USE_USB_OTG_HS or USE_USB_OTG_FS should be defined"
+ #endif
+#else //USE_USB_OTG_HS
+ #ifndef USE_ULPI_PHY
+  #ifndef USE_EMBEDDED_PHY
+     #error  "USE_ULPI_PHY or USE_EMBEDDED_PHY should be defined"
+  #endif
+ #endif
+#endif
+
+/****************** C Compilers dependant keywords ****************************/
+/* In HS mode and when the DMA is used, all variables and data structures dealing
+   with the DMA during the transaction process should be 4-bytes aligned */    
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined   (__GNUC__)        /* GNU Compiler */
+    #define __ALIGN_END    __attribute__ ((aligned (4)))
+    #define __ALIGN_BEGIN         
+  #else                           
+    #define __ALIGN_END
+    #if defined   (__CC_ARM)      /* ARM Compiler */
+      #define __ALIGN_BEGIN    __align(4)  
+    #elif defined (__ICCARM__)    /* IAR Compiler */
+      #define __ALIGN_BEGIN 
+    #elif defined  (__TASKING__)  /* TASKING Compiler */
+      #define __ALIGN_BEGIN    __align(4) 
+    #endif /* __CC_ARM */  
+  #endif /* __GNUC__ */ 
+#else
+  #define __ALIGN_BEGIN
+  #define __ALIGN_END   
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+
+/* __packed keyword used to decrease the data type alignment to 1-byte */
+#if defined (__CC_ARM)         /* ARM Compiler */
+  #define __packed    __packed
+#elif defined (__ICCARM__)     /* IAR Compiler */
+  #define __packed    __packed
+#elif defined   ( __GNUC__ )   /* GNU Compiler */                        
+//  #define __packed    __attribute__ ((__packed__))
+#ifndef __packed
+	#define __packed    __attribute__ ((__packed__))
+#endif
+#elif defined   (__TASKING__)  /* TASKING Compiler */
+  #define __packed    __unaligned
+#endif /* __CC_ARM */
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CONF_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CONF_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+#endif //__USB_CONF__H__
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/hal/interface/usbd_conf.h b/crazyflie-firmware-src/src/hal/interface/usbd_conf.h
new file mode 100644
index 0000000000000000000000000000000000000000..449388d85ac26712a9f4c0f9b4edbbfa7918cc7d
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/usbd_conf.h
@@ -0,0 +1,107 @@
+/**
+  ******************************************************************************
+  * @file    usbd_conf.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   USB Device configuration file
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CONF__H__
+#define __USBD_CONF__H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_conf.h"
+
+/** @defgroup USB_CONF_Exported_Defines
+  * @{
+  */ 
+#define USBD_CFG_MAX_NUM                1
+#define USBD_ITF_MAX_NUM                1
+
+#define USBD_SELF_POWERED               
+
+#define USB_MAX_STR_DESC_SIZ            255 
+
+/** @defgroup USB_VCP_Class_Layer_Parameter
+  * @{
+  */ 
+#define CDC_IN_EP                       0x81  /* EP1 for data IN */
+#define CDC_OUT_EP                      0x01  /* EP1 for data OUT */
+#define CDC_CMD_EP                      0x82  /* EP2 for CDC commands */
+
+/* CDC Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */
+#ifdef USE_USB_OTG_HS
+ #define CDC_DATA_MAX_PACKET_SIZE       512  /* Endpoint IN & OUT Packet size */
+ #define CDC_CMD_PACKET_SZE             8    /* Control Endpoint Packet size */
+
+ #define CDC_IN_FRAME_INTERVAL          40   /* Number of micro-frames between IN transfers */
+ #define APP_RX_DATA_SIZE               2048 /* Total size of IN buffer: 
+                                                APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL*8 */
+#else
+ #define CDC_DATA_MAX_PACKET_SIZE       64   /* Endpoint IN & OUT Packet size */
+ #define CDC_CMD_PACKET_SZE             8    /* Control Endpoint Packet size */
+
+ #define CDC_IN_FRAME_INTERVAL          1    /* Number of frames between IN transfers */
+ #define APP_RX_DATA_SIZE               2048 /* Total size of IN buffer: 
+                                                APP_RX_DATA_SIZE*8/MAX_BAUDARATE*1000 should be > CDC_IN_FRAME_INTERVAL */
+#endif /* USE_USB_OTG_HS */
+
+#define APP_FOPS                        CRTP_fops
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CONF_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+#endif //__USBD_CONF__H__
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/hal/interface/usbd_desc.h b/crazyflie-firmware-src/src/hal/interface/usbd_desc.h
new file mode 100644
index 0000000000000000000000000000000000000000..e28e14ae08061ad62db603fd2b3cc6a46ecbb763
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/usbd_desc.h
@@ -0,0 +1,120 @@
+/**
+  ******************************************************************************
+  * @file    usbd_desc.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   header file for the usbd_desc.c file
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+
+#ifndef __USB_DESC_H
+#define __USB_DESC_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_def.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+  
+/** @defgroup USB_DESC
+  * @brief general defines for the usb device library file
+  * @{
+  */ 
+
+/** @defgroup USB_DESC_Exported_Defines
+  * @{
+  */
+#define USB_DEVICE_DESCRIPTOR_TYPE              0x01
+#define USB_CONFIGURATION_DESCRIPTOR_TYPE       0x02
+#define USB_STRING_DESCRIPTOR_TYPE              0x03
+#define USB_INTERFACE_DESCRIPTOR_TYPE           0x04
+#define USB_ENDPOINT_DESCRIPTOR_TYPE            0x05
+#define USB_SIZ_DEVICE_DESC                     18
+#define USB_SIZ_STRING_LANGID                   4
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_DESC_Exported_TypesDefinitions
+  * @{
+  */
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USBD_DESC_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_DESC_Exported_Variables
+  * @{
+  */ 
+extern  uint8_t USBD_DeviceDesc  [USB_SIZ_DEVICE_DESC];
+extern  uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ];
+extern  uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC]; 
+extern  uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC];
+extern  uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID];
+extern  USBD_DEVICE USR_desc; 
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_DESC_Exported_FunctionsPrototype
+  * @{
+  */ 
+
+
+uint8_t *     USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length);
+uint8_t *     USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length);
+uint8_t *     USBD_USR_ManufacturerStrDescriptor ( uint8_t speed , uint16_t *length);
+uint8_t *     USBD_USR_ProductStrDescriptor ( uint8_t speed , uint16_t *length);
+uint8_t *     USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length);
+uint8_t *     USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length);
+uint8_t *     USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length);
+
+#ifdef USB_SUPPORT_USER_STRING_DESC
+uint8_t *     USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length);  
+#endif /* USB_SUPPORT_USER_STRING_DESC */  
+  
+/**
+  * @}
+  */ 
+
+#endif /* __USBD_DESC_H */
+
+/**
+  * @}
+  */ 
+
+/**
+* @}
+*/ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/hal/interface/usblink.h b/crazyflie-firmware-src/src/hal/interface/usblink.h
new file mode 100644
index 0000000000000000000000000000000000000000..d4a5fa92aeb0d21291c00cb7b503f78eedf846b0
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/usblink.h
@@ -0,0 +1,79 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * syslink.h: Implementation of the link between MCU
+ */
+
+#ifndef __USBLINK_H__
+#define __USBLINK_H__
+
+#include <stdbool.h>
+#include "crtp.h"
+
+//#define SYSLINK_MTU 32
+
+#define CRTP_START_BYTE  0xAA
+#define SYSLINK_START_BYTE1 0xBC
+#define SYSLINK_START_BYTE2 0xCF
+
+// Defined packet types
+//#define SYSLINK_RADIO_RAW      0x00
+//#define SYSLINK_RADIO_CHANNEL  0x01
+//#define SYSLINK_RADIO_DATARATE 0x02
+
+
+//#define SYSLINK_PM_SOURCE 0x10
+
+//#define SYSLINK_PM_ONOFF_SWITCHOFF 0x11
+
+//#define SYSLINK_PM_BATTERY_VOLTAGE 0x12
+//#define SYSLINK_PM_BATTERY_STATE   0x13
+//#define SYSLINK_PM_BATTERY_AUTOUPDATE 0x14
+
+//#define SYSLINK_OW_SCAN 0x20
+//#define SYSLINK_OW_READ 0x21
+/*
+typedef struct _SyslinkPacket
+{
+  uint8_t type;
+  uint8_t length;
+  char data[SYSLINK_MTU];
+} __attribute__((packed)) SyslinkPacket;
+
+typedef enum
+{
+  waitForFirstStart,
+  waitForSecondStart,
+  waitForType,
+  waitForLengt,
+  waitForData,
+  waitForChksum1,
+  waitForChksum2
+} SyslinkRxState;
+*/
+
+void usblinkInit();
+bool usblinkTest();
+struct crtpLinkOperations * usblinkGetLink();
+
+#endif
diff --git a/crazyflie-firmware-src/src/hal/interface/usec_time.h b/crazyflie-firmware-src/src/hal/interface/usec_time.h
new file mode 100644
index 0000000000000000000000000000000000000000..8542f64ad5664597d7e86c1c59d8ae271849b1f1
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/interface/usec_time.h
@@ -0,0 +1,41 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2013 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * usec_time.h - Microsecond-resolution timer.
+ */
+#ifndef USEC_TIME_H_
+#define USEC_TIME_H_
+
+#include <stdint.h>
+
+/**
+ * Initialize microsecond-resolution timer (TIM1).
+ */
+void initUsecTimer(void);
+
+/**
+ * Get microsecond-resolution timestamp.
+ */
+uint64_t usecTimestamp(void);
+
+#endif /* USEC_TIME_H_ */
diff --git a/crazyflie-firmware-src/src/hal/src/buzzer.c b/crazyflie-firmware-src/src/hal/src/buzzer.c
new file mode 100644
index 0000000000000000000000000000000000000000..63daeca586be7d5da8da3cab4009dc3697cd3ac3
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/buzzer.c
@@ -0,0 +1,56 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * buzzer.c - Functions for interfacing with decks with buzzers
+ */
+#define DEBUG_MODULE "BUZZER"
+
+#include "buzzer.h"
+
+static struct buzzerControl * ctrl;
+
+void buzzerInit()
+{
+}
+
+bool buzzerTest()
+{
+  return true;
+}
+
+void buzzerOff()
+{
+  if (ctrl)
+    ctrl->off();
+}
+
+void buzzerOn(uint32_t freq)
+{
+  if (ctrl)
+    ctrl->on(freq);
+}
+
+void buzzerSetControl(struct buzzerControl * bc)
+{
+  ctrl = bc;
+}
diff --git a/crazyflie-firmware-src/src/hal/src/eskylink.c b/crazyflie-firmware-src/src/hal/src/eskylink.c
new file mode 100644
index 0000000000000000000000000000000000000000..c3c6d08f669c274cd481b550a7589b3531edb56b
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/eskylink.c
@@ -0,0 +1,334 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * eskylink.c: esky 2.4GHz-compatible link driver
+ */
+/*
+ * Experimental code!
+ * This link implements the ESky remote protocol using the nRF24L01p chip and
+ * sends CRTP packets to the commander.
+ *
+ * Thanks to 'dvdouden' for documenting the protocol!
+ *  -> http://www.deviationtx.com/forum/protocol-development/1059-esky-protocol?q=/forum/protocol-development/1059-esky-protocol
+ *  -> http://sourceforge.net/p/arduinorclib/wiki/Esky%20Radio/
+ */
+
+#include <stdbool.h>
+#include <string.h>
+#include <errno.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "semphr.h"
+#include "system.h"
+
+#include "config.h"
+#include "nrf24l01.h"
+#include "crtp.h"
+#include "configblock.h"
+#include "ledseq.h"
+
+/* FIXME: This might be a bit tight range? */
+#define PPM_ZERO 1500
+#define PPM_RANGE 500
+#define PPM_MIN 1000
+#define PPM_MAX 2000
+
+static bool isInit;
+
+static char address[4] = {0x00, 0x00, 0x00, 0xBB};
+static char packet[32];
+
+/* Synchronisation */
+xSemaphoreHandle dataRdy;
+/* Data queue */
+xQueueHandle rxQueue;
+
+static struct {
+  bool enabled;
+
+  bool paired;
+  uint8_t band;
+} state;
+
+static void interruptCallback()
+{
+  portBASE_TYPE  xHigherPriorityTaskWoken = pdFALSE;
+
+  //To unlock RadioTask
+  xSemaphoreGiveFromISR(dataRdy, &xHigherPriorityTaskWoken);
+
+  if(xHigherPriorityTaskWoken)
+    portYIELD();
+}
+
+// 'Class' functions, called from callbacks
+static int setEnable(bool enable)
+{
+  nrfSetEnable(enable);
+  state.enabled = enable;
+
+  return 0;
+}
+
+static int sendPacket(CRTPPacket * pk)
+{
+  if (!state.enabled)
+    return ENETDOWN;
+
+  // NOP!
+
+  return 0;
+}
+
+static int receivePacket(CRTPPacket * pk)
+{
+  if (!state.enabled)
+    return ENETDOWN;
+
+  xQueueReceive( rxQueue, pk, portMAX_DELAY);
+
+  return 0;
+}
+
+static struct crtpLinkOperations eskyOp =
+{
+  .setEnable         = setEnable,
+  .sendPacket        = sendPacket,
+  .receivePacket     = receivePacket,
+};
+
+static int eskylinkFetchData(char * packet, int dataLen)
+{
+  nrfSetEnable(false);
+
+  //Fetch the data
+  nrfReadRX(packet, dataLen);
+
+  //clear the interruptions flags
+  nrfWrite1Reg(REG_STATUS, 0x70);
+
+  nrfSetEnable(true);
+
+  return dataLen;
+}
+
+static void eskylinkInitPairing(void)
+{
+  int i;
+
+  //Power the radio, Enable the DR interruption, set the radio in PRX mode with 2bytes CRC
+  nrfWrite1Reg(REG_CONFIG, 0x3F);
+  vTaskDelay(M2T(2)); //Wait for the chip to be ready
+
+   //Set the radio channel, pairing channel is 50
+  nrfSetChannel(50);
+  //Set the radio data rate
+  nrfSetDatarate(RADIO_RATE_1M);
+
+  nrfWrite1Reg(REG_SETUP_AW, VAL_SETUP_AW_3B); // 3 bytes address
+  address[0] = address[1] = address[2] = 0;
+  nrfWriteReg(REG_RX_ADDR_P0, address, 3);     // Pipe address == 0
+  nrfWrite1Reg(REG_EN_RXADDR, 0x01);
+  nrfWrite1Reg(REG_FEATURE, 0x00);             // No dynamic size payload
+  nrfWrite1Reg(REG_DYNPD, 0x00);
+  nrfWrite1Reg(REG_RX_PW_P0, 13);              //13 bytes payload
+  nrfWrite1Reg(REG_EN_AA, 0);                  //Disable shockburst
+
+  //Flush RX
+  for(i=0;i<3;i++)
+    nrfFlushRx();
+  //Flush TX
+  for(i=0;i<3;i++)
+    nrfFlushTx();
+}
+
+static void eskylinkInitPaired(int channel)
+{
+  nrfSetChannel(channel);
+  nrfSetDatarate(RADIO_RATE_1M);
+
+  nrfWrite1Reg(REG_SETUP_AW, VAL_SETUP_AW_4B); // 4 bytes address
+  nrfWriteReg(REG_RX_ADDR_P0, address, 4);     // Pipe address == from pairing packet
+  nrfWrite1Reg(REG_EN_RXADDR, 0x01);
+  nrfWrite1Reg(REG_FEATURE, 0x00);             // No dynamic size payload
+  nrfWrite1Reg(REG_DYNPD, 0x00);
+  nrfWrite1Reg(REG_RX_PW_P0, 13);              //13 bytes payload
+  nrfWrite1Reg(REG_EN_AA, 0);                  //Disable shockburst
+}
+
+//FIXME: A lot of parameters shall be configurable
+static void eskylinkDecode(char* packet)
+{
+  static CRTPPacket crtpPacket;
+  float pitch, roll, yaw;
+  uint16_t thrust;
+
+  pitch = ((packet[2]<<8) | packet[3])-PPM_ZERO;
+  if (roll<(-PPM_RANGE)) roll = -PPM_RANGE;
+  if (roll>PPM_RANGE) roll = PPM_RANGE;
+  pitch *= 20.0/PPM_RANGE;
+
+  roll = ((packet[0]<<8) | packet[1])-PPM_ZERO;
+  if (roll<(-PPM_RANGE)) roll = -PPM_RANGE;
+  if (roll>PPM_RANGE) roll = PPM_RANGE;
+  roll *= 20.0/PPM_RANGE;
+
+  yaw = ((packet[6]<<8) | packet[7])-PPM_ZERO;
+  if (yaw<(-PPM_RANGE)) yaw = -PPM_RANGE;
+  if (yaw>PPM_RANGE) yaw = PPM_RANGE;
+  yaw *= 200.0/PPM_RANGE;
+
+  thrust = ((packet[4]<<8) | packet[5])-PPM_MIN;
+  if (thrust<0) thrust = 0;
+  if (thrust>(2*PPM_RANGE)) thrust = 2*PPM_RANGE;
+  thrust *= 55000/(2*PPM_RANGE);
+
+  crtpPacket.port = CRTP_PORT_SETPOINT;
+  memcpy(&crtpPacket.data[0],  (char*)&roll,   4);
+  memcpy(&crtpPacket.data[4],  (char*)&pitch,  4);
+  memcpy(&crtpPacket.data[8],  (char*)&yaw,    4);
+  memcpy(&crtpPacket.data[12], (char*)&thrust, 2);
+
+  xQueueSend(rxQueue, &crtpPacket, 0);
+}
+
+static void eskylinkTask(void * arg)
+{
+  int channel = 7;
+  int channel1 = -1; //As long as channel1<0 the copter is in scann mode
+  int channel2 = 0;
+
+  //Waiting for pairing packet
+  while (!state.paired)
+  {
+    xSemaphoreTake(dataRdy, portMAX_DELAY);
+    ledseqRun(LED_GREEN, seq_linkup);
+
+    eskylinkFetchData(packet, 13);
+
+    if (packet[4]==0x18 && packet[5]==0x29)
+    {
+      address[2]=packet[0];
+      address[1]=packet[1];
+      address[0]=packet[2];
+      state.band = packet[3];
+      state.paired = true;
+    }
+  }
+
+  ledseqRun(LED_GREEN, seq_testPassed);
+
+  nrfSetEnable(false);
+  eskylinkInitPaired(channel);
+  nrfSetEnable(true);
+
+  //Paired! handling packets.
+  while(1)
+  {
+    if (xSemaphoreTake(dataRdy, M2T(10))==pdTRUE)
+    {
+      ledseqRun(LED_GREEN, seq_linkup);
+
+      eskylinkFetchData(packet, 13);
+      eskylinkDecode(packet);
+
+      if (channel1<0) //Channels found!
+      {
+        channel1 = channel;
+        channel2 = channel1+37;
+        if (channel2>83) channel2 = channel1 - 37;
+      }
+    }
+    else
+    {
+      if (channel1<0)
+      {
+        channel++;
+        if(channel>83) channel=7;
+        nrfSetEnable(false);
+        nrfSetChannel(channel);
+        nrfSetEnable(true);
+      }
+      else
+      {
+        if (channel == channel1)
+          channel = channel2;
+        else
+          channel = channel1;
+
+        nrfSetEnable(false);
+        nrfSetChannel(channel);
+        nrfSetEnable(true);
+      }
+
+    }
+  }
+}
+
+/*
+ * Public functions
+ */
+
+void eskylinkInit()
+{
+  if(isInit)
+    return;
+
+  nrfInit();
+
+  nrfSetInterruptCallback(interruptCallback);
+
+  //vTaskSetApplicationTaskTag(0, (void*)TASK_RADIO_ID_NBR);
+
+  /* Initialise the semaphores */
+  vSemaphoreCreateBinary(dataRdy);
+
+  /* Queue init */
+  rxQueue = xQueueCreate(3, sizeof(CRTPPacket));
+
+  eskylinkInitPairing();
+
+    /* Launch the Radio link task */
+  xTaskCreate(eskylinkTask, ESKYLINK_TASK_NAME,
+              ESKYLINK_TASK_STACKSIZE, NULL, ESKYLINK_TASK_PRI, NULL);
+
+  isInit = true;
+}
+
+bool eskylinkTest()
+{
+  return nrfTest();
+}
+
+struct crtpLinkOperations * eskylinkGetLink()
+{
+  return &eskyOp;
+}
+
+//FIXME: To implement!
+void eskylinkReInit(void)
+{
+  ;
+}
diff --git a/crazyflie-firmware-src/src/hal/src/freeRTOSdebug.c b/crazyflie-firmware-src/src/hal/src/freeRTOSdebug.c
new file mode 100644
index 0000000000000000000000000000000000000000..4ea013593f75f8b8d04f9d524d28f36a4804ac34
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/freeRTOSdebug.c
@@ -0,0 +1,103 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * debug.c - Various debug functions
+ */
+#include <stdint.h>
+
+#include "FreeRTOSConfig.h"
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "config.h"
+#include "debug.h"
+#include "nvicconf.h"
+#include "led.h"
+
+#ifdef UART_OUTPUT_TRACE_DATA
+  #include "uart.h"
+#endif
+
+uint32_t traceTickCount;
+
+void vApplicationMallocFailedHook( void )
+{
+	  portDISABLE_INTERRUPTS();
+	  DEBUG_PRINT("\nMalloc failed!\n");
+	  ledSet(ERR_LED1, 1);
+	  ledSet(ERR_LED2, 1);
+	  while(1);
+}
+
+#if (configCHECK_FOR_STACK_OVERFLOW == 1)
+void vApplicationStackOverflowHook(xTaskHandle *pxTask, signed portCHAR *pcTaskName)
+{
+  portDISABLE_INTERRUPTS();
+  DEBUG_PRINT("\nStack overflow!\n");
+  ledSet(ERR_LED1, 1);
+  ledSet(ERR_LED2, 1);
+  while(1);
+}
+#endif
+
+#ifdef UART_OUTPUT_TRACE_DATA
+void debugSendTraceInfo(unsigned int taskNbr)
+{
+  uint32_t traceData;
+  traceData = (taskNbr << 29) | (((traceTickCount << 16) + TIM1->CNT) & 0x1FFFFFF);
+  uartSendDataDma(sizeof(traceData), (uint8_t*)&traceData);
+}
+
+void debugInitTrace(void)
+{
+  /*TIM_TimeBaseInitTypeDef  TIM_TimeBaseStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  //Enable the Timer
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
+
+  //Timer configuration
+  TIM_TimeBaseStructure.TIM_Period = 0xFFFF;
+  TIM_TimeBaseStructure.TIM_Prescaler = 72;
+  TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
+  TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+  TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannel = TIM1_UP_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_TRACE_TIM_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  DBGMCU_Config(DBGMCU_TIM1_STOP, ENABLE);
+  TIM_ITConfig(TIM1, TIM_IT_Update, ENABLE);
+  TIM_Cmd(TIM1, ENABLE);
+
+  traceTickCount = 0;*/
+}
+#else
+void debugSendTraceInfo(unsigned int taskNbr)
+{
+}
+#endif
diff --git a/crazyflie-firmware-src/src/hal/src/imu_cf1.c b/crazyflie-firmware-src/src/hal/src/imu_cf1.c
new file mode 100644
index 0000000000000000000000000000000000000000..b0abd42a5b4d87c627865d58fceb9adbd66ae573
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/imu_cf1.c
@@ -0,0 +1,503 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * imu.c - inertial measurement unit
+ */
+#define DEBUG_MODULE "IMU"
+
+#include <math.h>
+
+#include "stm32f10x_conf.h"
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "debug.h"
+#include "configblock.h"
+#include "cfassert.h"
+#include "imu.h"
+#include "i2cdev.h"
+#include "mpu6050.h"
+#include "hmc5883l.h"
+#include "ms5611.h"
+#include "ledseq.h"
+#include "uart.h"
+#include "param.h"
+
+#define IMU_ENABLE_MAG_HMC5883
+#define IMU_ENABLE_PRESSURE_MS5611
+//#define IMU_MPU6050_DLPF_256HZ
+
+#define IMU_GYRO_FS_CFG       MPU6050_GYRO_FS_2000
+#define IMU_DEG_PER_LSB_CFG   MPU6050_DEG_PER_LSB_2000
+#define IMU_ACCEL_FS_CFG      MPU6050_ACCEL_FS_8
+#define IMU_G_PER_LSB_CFG     MPU6050_G_PER_LSB_8
+#define IMU_1G_RAW            (int16_t)(1.0 / MPU6050_G_PER_LSB_8)
+
+#define IMU_STARTUP_TIME_MS   1000
+
+#define GYRO_NBR_OF_AXES 3
+#define GYRO_X_SIGN      (-1)
+#define GYRO_Y_SIGN      (-1)
+#define GYRO_Z_SIGN      (-1)
+#define GYRO_NBR_OF_AXES            3
+#define GYRO_MIN_BIAS_TIMEOUT_MS    M2T(1*1000)
+
+#define IMU_NBR_OF_BIAS_SAMPLES  128
+
+#define GYRO_VARIANCE_BASE        4000
+#define GYRO_VARIANCE_THRESHOLD_X (GYRO_VARIANCE_BASE)
+#define GYRO_VARIANCE_THRESHOLD_Y (GYRO_VARIANCE_BASE)
+#define GYRO_VARIANCE_THRESHOLD_Z (GYRO_VARIANCE_BASE)
+
+#define MAG_GAUSS_PER_LSB_CFG    HMC5883L_GAIN_660
+#define MAG_GAUSS_PER_LSB        660.0
+
+
+typedef struct
+{
+  Axis3i16   bias;
+  bool       isBiasValueFound;
+  bool       isBufferFilled;
+  Axis3i16*  bufHead;
+  Axis3i16   buffer[IMU_NBR_OF_BIAS_SAMPLES];
+} BiasObj;
+
+static BiasObj    gyroBias;
+static BiasObj    accelBias;
+static int32_t    varianceSampleTime;
+static Axis3i16   gyroMpu;
+static Axis3i16   accelMpu;
+static Axis3i16   accelLPF;
+static Axis3i16   accelLPFAligned;
+static Axis3i16   mag;
+static Axis3i32   accelStoredFilterValues;
+static uint8_t    imuAccLpfAttFactor;
+static bool       isHmc5883lPresent;
+static bool       isMs5611Present;
+
+static bool isMpu6050TestPassed;
+static bool isHmc5883lTestPassed;
+static bool isMs5611TestPassed;
+
+// Pre-calculated values for accelerometer alignment
+static float cosPitch;
+static float sinPitch;
+static float cosRoll;
+static float sinRoll;
+
+/**
+ * MPU6050 selt test function. If the chip is moved to much during the self test
+ * it will cause the test to fail.
+ */
+static void imuBiasInit(BiasObj* bias);
+static void imuCalculateBiasMean(BiasObj* bias, Axis3i32* meanOut);
+static void imuCalculateVarianceAndMean(BiasObj* bias, Axis3i32* varOut, Axis3i32* meanOut);
+static bool imuFindBiasValue(BiasObj* bias);
+static void imuAddBiasValue(BiasObj* bias, Axis3i16* dVal);
+static void imuAccIIRLPFilter(Axis3i16* in, Axis3i16* out,
+                              Axis3i32* storedValues, int32_t attenuation);
+static void imuAccAlignToGravity(Axis3i16* in, Axis3i16* out);
+
+static bool isInit;
+
+void imu6Init(void)
+{
+  if(isInit)
+    return;
+
+ isHmc5883lPresent = false;
+ isMs5611Present = false;
+
+  // Wait for sensors to startup
+  while (xTaskGetTickCount() < M2T(IMU_STARTUP_TIME_MS));
+
+  i2cdevInit(I2C1);
+  mpu6050Init(I2C1);
+  if (mpu6050TestConnection() == true)
+  {
+    DEBUG_PRINT("MPU6050 I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("MPU6050 I2C connection [FAIL].\n");
+  }
+
+  mpu6050Reset();
+  vTaskDelay(M2T(50));
+  // Activate MPU6050
+  mpu6050SetSleepEnabled(false);
+  // Enable temp sensor
+  mpu6050SetTempSensorEnabled(true);
+  // Disable interrupts
+  mpu6050SetIntEnabled(false);
+  // Connect the HMC5883L to the main I2C bus
+  mpu6050SetI2CBypassEnabled(true);
+  // Set x-axis gyro as clock source
+  mpu6050SetClockSource(MPU6050_CLOCK_PLL_XGYRO);
+  // Set gyro full scale range
+  mpu6050SetFullScaleGyroRange(IMU_GYRO_FS_CFG);
+  // Set accelerometer full scale range
+  mpu6050SetFullScaleAccelRange(IMU_ACCEL_FS_CFG);
+
+#ifdef IMU_MPU6050_DLPF_256HZ
+  // 256Hz digital low-pass filter only works with little vibrations
+  // Set output rate (15): 8000 / (1 + 15) = 500Hz
+  mpu6050SetRate(15);
+  // Set digital low-pass bandwidth
+  mpu6050SetDLPFMode(MPU6050_DLPF_BW_256);
+#else
+  // To low DLPF bandwidth might cause instability and decrease agility
+  // but it works well for handling vibrations and unbalanced propellers
+  // Set output rate (1): 1000 / (1 + 1) = 500Hz
+  mpu6050SetRate(1);
+  // Set digital low-pass bandwidth
+  mpu6050SetDLPFMode(MPU6050_DLPF_BW_98);
+#endif
+
+
+#ifdef IMU_ENABLE_MAG_HMC5883
+  hmc5883lInit(I2C1);
+	if (hmc5883lTestConnection() == true)
+	{
+		isHmc5883lPresent = true;
+    DEBUG_PRINT("HMC5883 I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("HMC5883L I2C connection [FAIL].\n");
+  }
+#endif
+
+#ifdef IMU_ENABLE_PRESSURE_MS5611
+  if (ms5611Init(I2C1) == true)
+  {
+    isMs5611Present = true;
+    DEBUG_PRINT("MS5611 I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("MS5611 I2C connection [FAIL].\n");
+  }
+#endif
+
+  imuBiasInit(&gyroBias);
+  imuBiasInit(&accelBias);
+  varianceSampleTime = -GYRO_MIN_BIAS_TIMEOUT_MS + 1;
+  imuAccLpfAttFactor = IMU_ACC_IIR_LPF_ATT_FACTOR;
+
+  cosPitch = cos(configblockGetCalibPitch() * M_PI/180);
+  sinPitch = sin(configblockGetCalibPitch() * M_PI/180);
+  cosRoll = cos(configblockGetCalibRoll() * M_PI/180);
+  sinRoll = sin(configblockGetCalibRoll() * M_PI/180);
+
+  isInit = true;
+}
+
+bool imu6Test(void)
+{
+  bool testStatus = true;
+
+  if (!isInit)
+  {
+    DEBUG_PRINT("Uninitialized\n");
+    testStatus = false;
+  }
+  // Test for CF 10-DOF variant with none responding sensor
+  if((isHmc5883lPresent && !isMs5611Present) ||
+     (!isHmc5883lPresent && isMs5611Present))
+  {
+    DEBUG_PRINT("HMC5883L or MS5611 is not responding\n");
+    testStatus = false;
+  }
+  if (testStatus)
+  {
+    isMpu6050TestPassed = mpu6050SelfTest();
+    testStatus = isMpu6050TestPassed ;
+  }
+  if (testStatus && isHmc5883lPresent)
+  {
+    isHmc5883lTestPassed = hmc5883lSelfTest();
+    testStatus = isHmc5883lTestPassed;
+  }
+  if (testStatus && isMs5611Present)
+  {
+    isMs5611TestPassed = ms5611SelfTest();
+    testStatus = isMs5611TestPassed;
+  }
+
+  return testStatus;
+}
+
+
+void imu6Read(Axis3f* gyroOut, Axis3f* accOut)
+{
+  mpu6050GetMotion6(&accelMpu.x, &accelMpu.y, &accelMpu.z, &gyroMpu.x, &gyroMpu.y, &gyroMpu.z);
+
+  imuAddBiasValue(&gyroBias, &gyroMpu);
+  if (!accelBias.isBiasValueFound)
+  {
+    imuAddBiasValue(&accelBias, &accelMpu);
+  }
+  if (!gyroBias.isBiasValueFound)
+  {
+    imuFindBiasValue(&gyroBias);
+    if (gyroBias.isBiasValueFound)
+    {
+      ledseqRun(LED_RED, seq_calibrated);
+//      uartPrintf("Gyro bias: %i, %i, %i\n",
+//                  gyroBias.bias.x, gyroBias.bias.y, gyroBias.bias.z);
+    }
+  }
+
+#ifdef IMU_TAKE_ACCEL_BIAS
+  if (gyroBias.isBiasValueFound &&
+      !accelBias.isBiasValueFound)
+  {
+    Axis3i32 mean;
+
+    imuCalculateBiasMean(&accelBias, &mean);
+    accelBias.bias.x = mean.x;
+    accelBias.bias.y = mean.y;
+    accelBias.bias.z = mean.z - IMU_1G_RAW;
+    accelBias.isBiasValueFound = true;
+    //uartPrintf("Accel bias: %i, %i, %i\n",
+    //            accelBias.bias.x, accelBias.bias.y, accelBias.bias.z);
+  }
+#endif
+
+  imuAccIIRLPFilter(&accelMpu, &accelLPF, &accelStoredFilterValues,
+                    (int32_t)imuAccLpfAttFactor);
+
+  imuAccAlignToGravity(&accelLPF, &accelLPFAligned);
+
+  // Re-map outputs
+  gyroOut->x = (gyroMpu.x - gyroBias.bias.x) * IMU_DEG_PER_LSB_CFG;
+  gyroOut->y = (gyroMpu.y - gyroBias.bias.y) * IMU_DEG_PER_LSB_CFG;
+  gyroOut->z = (gyroMpu.z - gyroBias.bias.z) * IMU_DEG_PER_LSB_CFG;
+  accOut->x = (accelLPFAligned.x - accelBias.bias.x) * IMU_G_PER_LSB_CFG;
+  accOut->y = (accelLPFAligned.y - accelBias.bias.y) * IMU_G_PER_LSB_CFG;
+  accOut->z = (accelLPFAligned.z - accelBias.bias.z) * IMU_G_PER_LSB_CFG;
+}
+
+void imu9Read(Axis3f* gyroOut, Axis3f* accOut, Axis3f* magOut)
+{
+  imu6Read(gyroOut, accOut);
+
+  if (isHmc5883lPresent)
+  {
+    hmc5883lGetHeading(&mag.x, &mag.y, &mag.z);
+    magOut->x = (float)mag.x / MAG_GAUSS_PER_LSB;
+    magOut->y = (float)mag.y / MAG_GAUSS_PER_LSB;
+    magOut->z = (float)mag.z / MAG_GAUSS_PER_LSB;
+  }
+  else
+  {
+    magOut->x = 0.0;
+    magOut->y = 0.0;
+    magOut->z = 0.0;
+  }
+}
+
+bool imu6IsCalibrated(void)
+{
+  bool status;
+
+  status = gyroBias.isBiasValueFound;
+#ifdef IMU_TAKE_ACCEL_BIAS
+  status &= accelBias.isBiasValueFound;
+#endif
+
+  return status;
+}
+
+bool imuHasBarometer(void)
+{
+  return isMs5611Present;
+}
+
+bool imuHasMangnetometer(void)
+{
+  return isHmc5883lPresent;
+}
+
+static void imuBiasInit(BiasObj* bias)
+{
+  bias->isBufferFilled = false;
+  bias->bufHead = bias->buffer;
+}
+
+/**
+ * Calculates the variance and mean for the bias buffer.
+ */
+static void imuCalculateVarianceAndMean(BiasObj* bias, Axis3i32* varOut, Axis3i32* meanOut)
+{
+  uint32_t i;
+  int32_t sum[GYRO_NBR_OF_AXES] = {0};
+  int64_t sumSq[GYRO_NBR_OF_AXES] = {0};
+
+  for (i = 0; i < IMU_NBR_OF_BIAS_SAMPLES; i++)
+  {
+    sum[0] += bias->buffer[i].x;
+    sum[1] += bias->buffer[i].y;
+    sum[2] += bias->buffer[i].z;
+    sumSq[0] += bias->buffer[i].x * bias->buffer[i].x;
+    sumSq[1] += bias->buffer[i].y * bias->buffer[i].y;
+    sumSq[2] += bias->buffer[i].z * bias->buffer[i].z;
+  }
+
+  varOut->x = (sumSq[0] - ((int64_t)sum[0] * sum[0]) / IMU_NBR_OF_BIAS_SAMPLES);
+  varOut->y = (sumSq[1] - ((int64_t)sum[1] * sum[1]) / IMU_NBR_OF_BIAS_SAMPLES);
+  varOut->z = (sumSq[2] - ((int64_t)sum[2] * sum[2]) / IMU_NBR_OF_BIAS_SAMPLES);
+
+  meanOut->x = sum[0] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->y = sum[1] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->z = sum[2] / IMU_NBR_OF_BIAS_SAMPLES;
+
+  isInit = true;
+}
+
+/**
+ * Calculates the mean for the bias buffer.
+ */
+static void __attribute__((used)) imuCalculateBiasMean(BiasObj* bias, Axis3i32* meanOut)
+{
+  uint32_t i;
+  int32_t sum[GYRO_NBR_OF_AXES] = {0};
+
+  for (i = 0; i < IMU_NBR_OF_BIAS_SAMPLES; i++)
+  {
+    sum[0] += bias->buffer[i].x;
+    sum[1] += bias->buffer[i].y;
+    sum[2] += bias->buffer[i].z;
+  }
+
+  meanOut->x = sum[0] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->y = sum[1] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->z = sum[2] / IMU_NBR_OF_BIAS_SAMPLES;
+
+}
+
+/**
+ * Adds a new value to the variance buffer and if it is full
+ * replaces the oldest one. Thus a circular buffer.
+ */
+static void imuAddBiasValue(BiasObj* bias, Axis3i16* dVal)
+{
+  bias->bufHead->x = dVal->x;
+  bias->bufHead->y = dVal->y;
+  bias->bufHead->z = dVal->z;
+  bias->bufHead++;
+
+  if (bias->bufHead >= &bias->buffer[IMU_NBR_OF_BIAS_SAMPLES])
+  {
+    bias->bufHead = bias->buffer;
+    bias->isBufferFilled = true;
+  }
+}
+
+/**
+ * Checks if the variances is below the predefined thresholds.
+ * The bias value should have been added before calling this.
+ * @param bias  The bias object
+ */
+static bool imuFindBiasValue(BiasObj* bias)
+{
+  bool foundBias = false;
+
+  if (bias->isBufferFilled)
+  {
+    Axis3i32 variance;
+    Axis3i32 mean;
+
+    imuCalculateVarianceAndMean(bias, &variance, &mean);
+
+    //uartSendData(sizeof(variance), (uint8_t*)&variance);
+    //uartSendData(sizeof(mean), (uint8_t*)&mean);
+    //uartPrintf("%i, %i, %i", variance.x, variance.y, variance.z);
+    //uartPrintf("    %i, %i, %i\n", mean.x, mean.y, mean.z);
+
+    if (variance.x < GYRO_VARIANCE_THRESHOLD_X &&
+        variance.y < GYRO_VARIANCE_THRESHOLD_Y &&
+        variance.z < GYRO_VARIANCE_THRESHOLD_Z &&
+        (varianceSampleTime + GYRO_MIN_BIAS_TIMEOUT_MS < xTaskGetTickCount()))
+    {
+      varianceSampleTime = xTaskGetTickCount();
+      bias->bias.x = mean.x;
+      bias->bias.y = mean.y;
+      bias->bias.z = mean.z;
+      foundBias = true;
+      bias->isBiasValueFound = true;
+    }
+  }
+
+  return foundBias;
+}
+
+static void imuAccIIRLPFilter(Axis3i16* in, Axis3i16* out, Axis3i32* storedValues, int32_t attenuation)
+{
+  out->x = iirLPFilterSingle(in->x, attenuation, &storedValues->x);
+  out->y = iirLPFilterSingle(in->y, attenuation, &storedValues->y);
+  out->z = iirLPFilterSingle(in->z, attenuation, &storedValues->z);
+}
+
+
+/**
+ * Compensate for a miss-aligned accelerometer. It uses the trim
+ * data gathered from the UI and written in the config-block to
+ * rotate the accelerometer to be aligned with gravity.
+ */
+static void imuAccAlignToGravity(Axis3i16* in, Axis3i16* out)
+{
+  Axis3i16 rx;
+  Axis3i16 ry;
+
+  // Rotate around x-axis
+  rx.x = in->x;
+  rx.y = in->y * cosRoll - in->z * sinRoll;
+  rx.z = in->y * sinRoll + in->z * cosRoll;
+
+  // Rotate around y-axis
+  ry.x = rx.x * cosPitch - rx.z * sinPitch;
+  ry.y = rx.y;
+  ry.z = -rx.x * sinPitch + rx.z * cosPitch;
+
+  out->x = ry.x;
+  out->y = ry.y;
+  out->z = ry.z;
+}
+
+PARAM_GROUP_START(imu_acc_lpf)
+PARAM_ADD(PARAM_UINT8, factor, &imuAccLpfAttFactor)
+PARAM_GROUP_STOP(imu_acc_lpf)
+
+PARAM_GROUP_START(imu_sensors)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, HMC5883L, &isHmc5883lPresent)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MS5611, &isMs5611Present)
+PARAM_GROUP_STOP(imu_sensors)
+
+PARAM_GROUP_START(imu_tests)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MPU6050, &isMpu6050TestPassed)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, HMC5883L, &isHmc5883lTestPassed)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MS5611, &isMs5611TestPassed)
+PARAM_GROUP_STOP(imu_tests)
diff --git a/crazyflie-firmware-src/src/hal/src/imu_cf2.c b/crazyflie-firmware-src/src/hal/src/imu_cf2.c
new file mode 100644
index 0000000000000000000000000000000000000000..1d2b1f10d1ce260d05a57d7a9cd7655e81c82eaa
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/imu_cf2.c
@@ -0,0 +1,572 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * imu.c - inertial measurement unit
+ */
+#define DEBUG_MODULE "IMU"
+
+#include <math.h>
+
+#include "stm32fxxx.h"
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "debug.h"
+#include "configblock.h"
+#include "cfassert.h"
+#include "imu.h"
+#include "i2cdev.h"
+#include "mpu6500.h"
+#include "hmc5883l.h"
+#include "ms5611.h"
+#include "ak8963.h"
+#include "lps25h.h"
+#include "ledseq.h"
+#include "param.h"
+#include "log.h"
+#include "sound.h"
+
+#define IMU_ENABLE_PRESSURE_LPS25H
+#define IMU_ENABLE_MAG_AK8963
+//#define IMU_MPU6500_DLPF_256HZ
+
+#define IMU_GYRO_FS_CFG       MPU6500_GYRO_FS_2000
+#define IMU_DEG_PER_LSB_CFG   MPU6500_DEG_PER_LSB_2000
+#define IMU_ACCEL_FS_CFG      MPU6500_ACCEL_FS_8
+#define IMU_G_PER_LSB_CFG     MPU6500_G_PER_LSB_8
+#define IMU_1G_RAW            (int16_t)(1.0f / MPU6500_G_PER_LSB_8)
+
+#define IMU_VARIANCE_MAN_TEST_TIMEOUT M2T(1000) // Timeout in ms
+#define IMU_MAN_TEST_LEVEL_MAX        5.0f      // Max degrees off
+
+#define MAG_GAUSS_PER_LSB     666.7f
+
+#define IMU_STARTUP_TIME_MS   1000
+
+#define GYRO_NBR_OF_AXES 3
+#define GYRO_X_SIGN      (-1)
+#define GYRO_Y_SIGN      (-1)
+#define GYRO_Z_SIGN      (-1)
+#define GYRO_NBR_OF_AXES            3
+#define GYRO_MIN_BIAS_TIMEOUT_MS    M2T(1*1000)
+
+// Number of samples used in variance calculation. Changing this effects the threshold
+#define IMU_NBR_OF_BIAS_SAMPLES  1024
+
+// Variance threshold to take zero bias for gyro
+#define GYRO_VARIANCE_BASE        5000
+#define GYRO_VARIANCE_THRESHOLD_X (GYRO_VARIANCE_BASE)
+#define GYRO_VARIANCE_THRESHOLD_Y (GYRO_VARIANCE_BASE)
+#define GYRO_VARIANCE_THRESHOLD_Z (GYRO_VARIANCE_BASE)
+
+typedef struct
+{
+  Axis3f     bias;
+  bool       isBiasValueFound;
+  bool       isBufferFilled;
+  Axis3i16*  bufHead;
+  Axis3i16   buffer[IMU_NBR_OF_BIAS_SAMPLES];
+} BiasObj;
+
+BiasObj    gyroBias;
+#ifdef IMU_TAKE_ACCEL_BIAS
+BiasObj    accelBias;
+#endif
+static int32_t    varianceSampleTime;
+static Axis3i16   gyroMpu;
+static Axis3i16   accelMpu;
+static Axis3i16   accelLPF;
+static Axis3i16   accelLPFAligned;
+static Axis3i16   mag;
+static Axis3i32   accelStoredFilterValues;
+static uint8_t    imuAccLpfAttFactor;
+static bool isMagPresent;
+static bool isBaroPresent;
+
+static bool isMpu6500TestPassed = true;
+static bool isAK8963TestPassed = true;
+static bool isLPS25HTestPassed = true;
+
+// Pre-calculated values for accelerometer alignment
+float cosPitch;
+float sinPitch;
+float cosRoll;
+float sinRoll;
+
+LOG_GROUP_START(mag_raw)
+LOG_ADD(LOG_INT16, x, &mag.x)
+LOG_ADD(LOG_INT16, y, &mag.y)
+LOG_ADD(LOG_INT16, z, &mag.z)
+LOG_GROUP_STOP(mag_raw)
+/**
+ * MPU6500 selt test function. If the chip is moved to much during the self test
+ * it will cause the test to fail.
+ */
+static void imuBiasInit(BiasObj* bias);
+static void imuCalculateBiasMean(BiasObj* bias, Axis3i32* meanOut);
+static void imuCalculateVarianceAndMean(BiasObj* bias, Axis3f* varOut, Axis3f* meanOut);
+static bool imuFindBiasValue(BiasObj* bias);
+static void imuAddBiasValue(BiasObj* bias, Axis3i16* dVal);
+static void imuAccIIRLPFilter(Axis3i16* in, Axis3i16* out,
+                              Axis3i32* storedValues, int32_t attenuation);
+static void imuAccAlignToGravity(Axis3i16* in, Axis3i16* out);
+
+static bool isInit;
+
+void imu6Init(void)
+{
+  if(isInit)
+    return;
+
+ isMagPresent = false;
+ isBaroPresent = false;
+
+  // Wait for sensors to startup
+  while (xTaskGetTickCount() < M2T(IMU_STARTUP_TIME_MS));
+
+  i2cdevInit(I2C3_DEV);
+  mpu6500Init(I2C3_DEV);
+
+  if (mpu6500TestConnection() == true)
+  {
+    DEBUG_PRINT("MPU9250 I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("MPU9250 I2C connection [FAIL].\n");
+  }
+
+  mpu6500Reset();
+  vTaskDelay(M2T(50));
+  // Activate MPU6500
+  mpu6500SetSleepEnabled(false);
+  // Enable temp sensor
+  mpu6500SetTempSensorEnabled(true);
+  // Disable interrupts
+  mpu6500SetIntEnabled(false);
+  // Connect the HMC5883L to the main I2C bus
+  mpu6500SetI2CBypassEnabled(true);
+  // Set x-axis gyro as clock source
+  mpu6500SetClockSource(MPU6500_CLOCK_PLL_XGYRO);
+  // Set gyro full scale range
+  mpu6500SetFullScaleGyroRange(IMU_GYRO_FS_CFG);
+  // Set accelerometer full scale range
+  mpu6500SetFullScaleAccelRange(IMU_ACCEL_FS_CFG);
+
+#ifdef IMU_MPU6500_DLPF_256HZ
+  // 256Hz digital low-pass filter only works with little vibrations
+  // Set output rate (15): 8000 / (1 + 15) = 500Hz
+  mpu6500SetRate(15);
+  // Set digital low-pass bandwidth
+  mpu6500SetDLPFMode(MPU6500_DLPF_BW_256);
+#else
+  // To low DLPF bandwidth might cause instability and decrease agility
+  // but it works well for handling vibrations and unbalanced propellers
+  // Set output rate (1): 1000 / (1 + 1) = 500Hz
+  mpu6500SetRate(1);
+  // Set digital low-pass bandwidth
+  mpu6500SetDLPFMode(MPU6500_DLPF_BW_98);
+#endif
+
+
+#ifdef IMU_ENABLE_MAG_AK8963
+  ak8963Init(I2C3_DEV);
+  if (ak8963TestConnection() == true)
+  {
+    isMagPresent = true;
+    ak8963SetMode(AK8963_MODE_16BIT | AK8963_MODE_CONT2); // 16bit 100Hz
+    DEBUG_PRINT("AK8963 I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("AK8963 I2C connection [FAIL].\n");
+  }
+#endif
+
+#ifdef IMU_ENABLE_PRESSURE_LPS25H
+  lps25hInit(I2C3_DEV);
+  if (lps25hTestConnection() == true)
+  {
+    lps25hSetEnabled(true);
+    isBaroPresent = true;
+    DEBUG_PRINT("LPS25H I2C connection [OK].\n");
+  }
+  else
+  {
+    //TODO: Should sensor test fail hard if no connection
+    DEBUG_PRINT("LPS25H I2C connection [FAIL].\n");
+  }
+#endif
+
+  imuBiasInit(&gyroBias);
+#ifdef IMU_TAKE_ACCEL_BIAS
+  imuBiasInit(&accelBias);
+#endif
+  varianceSampleTime = -GYRO_MIN_BIAS_TIMEOUT_MS + 1;
+  imuAccLpfAttFactor = IMU_ACC_IIR_LPF_ATT_FACTOR;
+
+  cosPitch = cosf(configblockGetCalibPitch() * (float) M_PI/180);
+  sinPitch = sinf(configblockGetCalibPitch() * (float) M_PI/180);
+  cosRoll = cosf(configblockGetCalibRoll() * (float) M_PI/180);
+  sinRoll = sinf(configblockGetCalibRoll() * (float) M_PI/180);
+
+  isInit = true;
+}
+
+bool imu6Test(void)
+{
+  bool testStatus = true;
+
+  if (!isInit)
+  {
+    DEBUG_PRINT("Uninitialized\n");
+    testStatus = false;
+  }
+
+#ifdef IMU_ENABLE_MAG_AK8963
+  testStatus &= isMagPresent;
+  if (testStatus)
+  {
+    isAK8963TestPassed = ak8963SelfTest();
+    testStatus = isAK8963TestPassed;
+  }
+#endif
+
+#ifdef IMU_ENABLE_PRESSURE_LPS25H
+  testStatus &= isBaroPresent;
+  if (testStatus)
+  {
+    isLPS25HTestPassed = lps25hSelfTest();
+    testStatus = isLPS25HTestPassed;
+  }
+#endif
+
+  return testStatus;
+}
+
+bool imu6ManufacturingTest(void)
+{
+  bool testStatus = false;
+  Axis3f gyro; // Gyro axis data in deg/s
+  Axis3f acc;  // Accelerometer axis data in mG
+  float pitch, roll;
+  uint32_t startTick = xTaskGetTickCount();
+
+  testStatus = mpu6500SelfTest();
+
+  if (testStatus)
+  {
+    while (xTaskGetTickCount() - startTick < IMU_VARIANCE_MAN_TEST_TIMEOUT)
+    {
+      imu6Read(&gyro, &acc);
+      if (gyroBias.isBiasValueFound)
+      {
+        DEBUG_PRINT("Gyro variance test [OK]\n");
+        break;
+      }
+    }
+
+    if (gyroBias.isBiasValueFound)
+    {
+      // Calculate pitch and roll based on accelerometer. Board must be level
+      pitch = tanf(-acc.x/(sqrtf(acc.y*acc.y + acc.z*acc.z))) * 180/(float) M_PI;
+      roll = tanf(acc.y/acc.z) * 180/(float) M_PI;
+
+      if ((fabsf(roll) < IMU_MAN_TEST_LEVEL_MAX) && (fabsf(pitch) < IMU_MAN_TEST_LEVEL_MAX))
+      {
+        DEBUG_PRINT("Acc level test [OK]\n");
+        testStatus = true;
+      }
+      else
+      {
+        DEBUG_PRINT("Acc level test Roll:%0.2f, Pitch:%0.2f [FAIL]\n", roll, pitch);
+        testStatus = false;
+      }
+    }
+    else
+    {
+      DEBUG_PRINT("Gyro variance test [FAIL]\n");
+      testStatus = false;
+    }
+  }
+
+  return testStatus;
+}
+
+void imu6Read(Axis3f* gyroOut, Axis3f* accOut)
+{
+  mpu6500GetMotion6(&accelMpu.y, &accelMpu.x, &accelMpu.z, &gyroMpu.y, &gyroMpu.x, &gyroMpu.z);
+
+  imuAddBiasValue(&gyroBias, &gyroMpu);
+#ifdef IMU_TAKE_ACCEL_BIAS
+  if (!accelBias.isBiasValueFound)
+  {
+    imuAddBiasValue(&accelBias, &accelMpu);
+  }
+#endif
+  if (!gyroBias.isBiasValueFound)
+  {
+    imuFindBiasValue(&gyroBias);
+    if (gyroBias.isBiasValueFound)
+    {
+      soundSetEffect(SND_CALIB);
+      ledseqRun(SYS_LED, seq_calibrated);
+    }
+  }
+
+#ifdef IMU_TAKE_ACCEL_BIAS
+  if (gyroBias.isBiasValueFound &&
+      !accelBias.isBiasValueFound)
+  {
+    Axis3i32 mean;
+
+    imuCalculateBiasMean(&accelBias, &mean);
+    accelBias.bias.x = mean.x;
+    accelBias.bias.y = mean.y;
+    accelBias.bias.z = mean.z - IMU_1G_RAW;
+    accelBias.isBiasValueFound = true;
+  }
+#endif
+
+
+  imuAccIIRLPFilter(&accelMpu, &accelLPF, &accelStoredFilterValues,
+                    (int32_t)imuAccLpfAttFactor);
+
+  imuAccAlignToGravity(&accelLPF, &accelLPFAligned);
+
+  // Re-map outputs
+  gyroOut->x = -(gyroMpu.x - gyroBias.bias.x) * IMU_DEG_PER_LSB_CFG;
+  gyroOut->y = (gyroMpu.y - gyroBias.bias.y) * IMU_DEG_PER_LSB_CFG;
+  gyroOut->z = (gyroMpu.z - gyroBias.bias.z) * IMU_DEG_PER_LSB_CFG;
+#ifdef IMU_TAKE_ACCEL_BIAS
+  accOut->x = (accelLPFAligned.x - accelBias.bias.x) * IMU_G_PER_LSB_CFG;
+  accOut->y = (accelLPFAligned.y - accelBias.bias.y) * IMU_G_PER_LSB_CFG;
+  accOut->z = (accelLPFAligned.z - accelBias.bias.z) * IMU_G_PER_LSB_CFG;
+#else
+  accOut->x = -(accelLPFAligned.x) * IMU_G_PER_LSB_CFG;
+  accOut->y = (accelLPFAligned.y) * IMU_G_PER_LSB_CFG;
+  accOut->z = (accelLPFAligned.z) * IMU_G_PER_LSB_CFG;
+#endif
+
+}
+
+bool imu6IsCalibrated(void)
+{
+  bool status;
+
+  status = gyroBias.isBiasValueFound;
+#ifdef IMU_TAKE_ACCEL_BIAS
+  status &= accelBias.isBiasValueFound;
+#endif
+
+  return status;
+}
+
+void imu9Read(Axis3f* gyroOut, Axis3f* accOut, Axis3f* magOut)
+{
+  imu6Read(gyroOut, accOut);
+
+  if (isMagPresent)
+  {
+    if (ak8963GetDataReady() == true) {
+      ak8963GetHeading(&mag.x, &mag.y, &mag.z);
+      ak8963GetOverflowStatus();
+      magOut->x = (float)mag.x / MAG_GAUSS_PER_LSB;
+      magOut->y = (float)mag.y / MAG_GAUSS_PER_LSB;
+      magOut->z = (float)mag.z / MAG_GAUSS_PER_LSB;
+    }
+  }
+  else
+  {
+    magOut->x = 0.0;
+    magOut->y = 0.0;
+    magOut->z = 0.0;
+  }
+}
+
+bool imuHasBarometer(void)
+{
+  return isBaroPresent;
+}
+
+bool imuHasMangnetometer(void)
+{
+  return isMagPresent;
+}
+
+static void imuBiasInit(BiasObj* bias)
+{
+  bias->isBufferFilled = false;
+  bias->bufHead = bias->buffer;
+}
+
+/**
+ * Calculates the variance and mean for the bias buffer.
+ */
+static void imuCalculateVarianceAndMean(BiasObj* bias, Axis3f* varOut, Axis3f* meanOut)
+{
+  uint32_t i;
+  int64_t sum[GYRO_NBR_OF_AXES] = {0};
+  int64_t sumSq[GYRO_NBR_OF_AXES] = {0};
+
+  for (i = 0; i < IMU_NBR_OF_BIAS_SAMPLES; i++)
+  {
+    sum[0] += bias->buffer[i].x;
+    sum[1] += bias->buffer[i].y;
+    sum[2] += bias->buffer[i].z;
+    sumSq[0] += bias->buffer[i].x * bias->buffer[i].x;
+    sumSq[1] += bias->buffer[i].y * bias->buffer[i].y;
+    sumSq[2] += bias->buffer[i].z * bias->buffer[i].z;
+  }
+
+  varOut->x = (sumSq[0] - ((int64_t)sum[0] * sum[0]) / IMU_NBR_OF_BIAS_SAMPLES);
+  varOut->y = (sumSq[1] - ((int64_t)sum[1] * sum[1]) / IMU_NBR_OF_BIAS_SAMPLES);
+  varOut->z = (sumSq[2] - ((int64_t)sum[2] * sum[2]) / IMU_NBR_OF_BIAS_SAMPLES);
+
+  meanOut->x = (float)sum[0] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->y = (float)sum[1] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->z = (float)sum[2] / IMU_NBR_OF_BIAS_SAMPLES;
+
+  isInit = true;
+}
+
+/**
+ * Calculates the mean for the bias buffer.
+ */
+static void __attribute__((used)) imuCalculateBiasMean(BiasObj* bias, Axis3i32* meanOut)
+{
+  uint32_t i;
+  int32_t sum[GYRO_NBR_OF_AXES] = {0};
+
+  for (i = 0; i < IMU_NBR_OF_BIAS_SAMPLES; i++)
+  {
+    sum[0] += bias->buffer[i].x;
+    sum[1] += bias->buffer[i].y;
+    sum[2] += bias->buffer[i].z;
+  }
+
+  meanOut->x = sum[0] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->y = sum[1] / IMU_NBR_OF_BIAS_SAMPLES;
+  meanOut->z = sum[2] / IMU_NBR_OF_BIAS_SAMPLES;
+
+}
+
+/**
+ * Adds a new value to the variance buffer and if it is full
+ * replaces the oldest one. Thus a circular buffer.
+ */
+static void imuAddBiasValue(BiasObj* bias, Axis3i16* dVal)
+{
+  bias->bufHead->x = dVal->x;
+  bias->bufHead->y = dVal->y;
+  bias->bufHead->z = dVal->z;
+  bias->bufHead++;
+
+  if (bias->bufHead >= &bias->buffer[IMU_NBR_OF_BIAS_SAMPLES])
+  {
+    bias->bufHead = bias->buffer;
+    bias->isBufferFilled = true;
+  }
+}
+
+/**
+ * Checks if the variances is below the predefined thresholds.
+ * The bias value should have been added before calling this.
+ * @param bias  The bias object
+ */
+static bool imuFindBiasValue(BiasObj* bias)
+{
+  bool foundBias = false;
+
+  if (bias->isBufferFilled)
+  {
+    Axis3f variance;
+    Axis3f mean;
+
+    imuCalculateVarianceAndMean(bias, &variance, &mean);
+
+    if (variance.x < GYRO_VARIANCE_THRESHOLD_X &&
+        variance.y < GYRO_VARIANCE_THRESHOLD_Y &&
+        variance.z < GYRO_VARIANCE_THRESHOLD_Z &&
+        (varianceSampleTime + GYRO_MIN_BIAS_TIMEOUT_MS < xTaskGetTickCount()))
+    {
+      varianceSampleTime = xTaskGetTickCount();
+      bias->bias.x = mean.x;
+      bias->bias.y = mean.y;
+      bias->bias.z = mean.z;
+      foundBias = true;
+      bias->isBiasValueFound = true;
+    }
+  }
+
+  return foundBias;
+}
+
+static void imuAccIIRLPFilter(Axis3i16* in, Axis3i16* out, Axis3i32* storedValues, int32_t attenuation)
+{
+  out->x = iirLPFilterSingle(in->x, attenuation, &storedValues->x);
+  out->y = iirLPFilterSingle(in->y, attenuation, &storedValues->y);
+  out->z = iirLPFilterSingle(in->z, attenuation, &storedValues->z);
+}
+
+
+/**
+ * Compensate for a miss-aligned accelerometer. It uses the trim
+ * data gathered from the UI and written in the config-block to
+ * rotate the accelerometer to be aligned with gravity.
+ */
+static void imuAccAlignToGravity(Axis3i16* in, Axis3i16* out)
+{
+  Axis3i16 rx;
+  Axis3i16 ry;
+
+  // Rotate around x-axis
+  rx.x = in->x;
+  rx.y = in->y * cosRoll - in->z * sinRoll;
+  rx.z = in->y * sinRoll + in->z * cosRoll;
+
+  // Rotate around y-axis
+  ry.x = rx.x * cosPitch - rx.z * sinPitch;
+  ry.y = rx.y;
+  ry.z = -rx.x * sinPitch + rx.z * cosPitch;
+
+  out->x = ry.x;
+  out->y = ry.y;
+  out->z = ry.z;
+}
+
+PARAM_GROUP_START(imu_acc_lpf)
+PARAM_ADD(PARAM_UINT8, factor, &imuAccLpfAttFactor)
+PARAM_GROUP_STOP(imu_acc_lpf)
+
+PARAM_GROUP_START(imu_sensors)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, HMC5883L, &isMagPresent)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MS5611, &isBaroPresent) // TODO: Rename MS5611 to LPS25H. Client needs to be updated at the same time.
+PARAM_GROUP_STOP(imu_sensors)
+
+PARAM_GROUP_START(imu_tests)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MPU6500, &isMpu6500TestPassed)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, HMC5883L, &isAK8963TestPassed)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MS5611, &isLPS25HTestPassed) // TODO: Rename MS5611 to LPS25H. Client needs to be updated at the same time.
+PARAM_GROUP_STOP(imu_tests)
diff --git a/crazyflie-firmware-src/src/hal/src/ledseq.c b/crazyflie-firmware-src/src/hal/src/ledseq.c
new file mode 100644
index 0000000000000000000000000000000000000000..3107297cf4c25126835efe5cf82a84a3a64d6d0f
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/ledseq.c
@@ -0,0 +1,329 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/*
+ * ledseq.c - LED sequence handler
+ */
+
+#include <stdbool.h>
+
+#include "ledseq.h"
+
+#include "FreeRTOS.h"
+#include "timers.h"
+#include "semphr.h"
+
+#include "led.h"
+
+#ifdef CALIBRATED_LED_MORSE
+  #define DOT 100
+  #define DASH (3 * DOT)
+  #define GAP DOT
+  #define LETTER_GAP (3 * DOT)
+  #define WORD_GAP (7 * DOT)
+#endif // #ifdef CALIBRATED_LED_MORSE
+
+/* Led sequence priority */
+static ledseq_t const * sequences[] = {
+  seq_testPassed,
+  seq_lowbat,
+  seq_charged,
+  seq_charging,
+  seq_chargingMax,
+  seq_bootloader,
+  seq_armed,
+  seq_calibrated,
+  seq_alive,
+  seq_linkup,
+};
+
+/* Led sequences */
+const ledseq_t seq_lowbat[] = {
+  { true, LEDSEQ_WAITMS(1000)},
+  {    0, LEDSEQ_LOOP},
+};
+
+const ledseq_t seq_armed[] = {
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(250)},
+  {    0, LEDSEQ_LOOP},
+};
+
+const ledseq_t seq_calibrated[] = {
+#ifndef CALIBRATED_LED_MORSE
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(450)},
+  {    0, LEDSEQ_LOOP},
+#else
+  { true, LEDSEQ_WAITMS(DASH)},
+  {false, LEDSEQ_WAITMS(GAP)},
+  { true, LEDSEQ_WAITMS(DOT)},
+  {false, LEDSEQ_WAITMS(GAP)},
+  { true, LEDSEQ_WAITMS(DASH)},
+  {false, LEDSEQ_WAITMS(GAP)},
+  { true, LEDSEQ_WAITMS(DOT)},
+  {false, LEDSEQ_WAITMS(LETTER_GAP)},
+  { true, LEDSEQ_WAITMS(DOT)},
+  {false, LEDSEQ_WAITMS(GAP)},
+  { true, LEDSEQ_WAITMS(DOT)},
+  {false, LEDSEQ_WAITMS(GAP)},
+  { true, LEDSEQ_WAITMS(DASH)},
+  {false, LEDSEQ_WAITMS(GAP)},
+  { true, LEDSEQ_WAITMS(DOT)},
+  {false, LEDSEQ_WAITMS(WORD_GAP)},
+  {    0, LEDSEQ_LOOP},
+#endif // ifndef CALIBRATED_LED_MORSE
+};
+
+const ledseq_t seq_alive[] = {
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(1950)},
+  {    0, LEDSEQ_LOOP},
+};
+
+
+//TODO: Change, right now is called so fast it looks like seq_lowbat
+const ledseq_t seq_altHold[] = {
+  { true, LEDSEQ_WAITMS(1)},
+  {false, LEDSEQ_WAITMS(50)},
+  {    0, LEDSEQ_STOP},
+};
+
+const ledseq_t seq_linkup[] = {
+  { true, LEDSEQ_WAITMS(1)},
+  {false, LEDSEQ_WAITMS(0)},
+  {    0, LEDSEQ_STOP},
+};
+
+
+const ledseq_t seq_charged[] = {
+  { true, LEDSEQ_WAITMS(1000)},
+  {    0, LEDSEQ_LOOP},
+};
+
+ledseq_t seq_charging[] = {
+  { true, LEDSEQ_WAITMS(200)},
+  {false, LEDSEQ_WAITMS(800)},
+  {    0, LEDSEQ_LOOP},
+};
+
+ledseq_t seq_chargingMax[] = {
+  { true, LEDSEQ_WAITMS(100)},
+  {false, LEDSEQ_WAITMS(400)},
+  {    0, LEDSEQ_LOOP},
+};
+
+const ledseq_t seq_bootloader[] = {
+  { true, LEDSEQ_WAITMS(500)},
+  {false, LEDSEQ_WAITMS(500)},
+  {    0, LEDSEQ_LOOP},
+};
+
+const ledseq_t seq_testPassed[] = {
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(50)},
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(50)},
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(50)},
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(50)},
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(50)},
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(50)},
+  { true, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_WAITMS(50)},
+  {false, LEDSEQ_STOP},
+};
+
+/* Led sequence handling machine implementation */
+#define SEQ_NUM (sizeof(sequences)/sizeof(sequences[0]))
+
+static void runLedseq(xTimerHandle xTimer);
+static int getPrio(const ledseq_t *seq);
+static void updateActive(led_t led);
+
+//State of every sequence for every led: LEDSEQ_STOP if stopped or the current
+//step
+static int state[LED_NUM][SEQ_NUM];
+//Active sequence for each led
+static int activeSeq[LED_NUM];
+
+static xTimerHandle timer[LED_NUM];
+
+static xSemaphoreHandle ledseqSem;
+
+static bool isInit = false;
+static bool ledseqEnabled = false;
+
+void ledseqInit()
+{
+  int i,j;
+
+  if(isInit)
+    return;
+
+  ledInit();
+
+  //Initialise the sequences state
+  for(i=0; i<LED_NUM; i++) {
+    activeSeq[i] = LEDSEQ_STOP;
+    for(j=0; j<SEQ_NUM; j++)
+      state[i][j] = LEDSEQ_STOP;
+  }
+
+  //Init the soft timers that runs the led sequences for each leds
+  for(i=0; i<LED_NUM; i++)
+    timer[i] = xTimerCreate("ledseqTimer", M2T(1000), pdFALSE, (void*)i, runLedseq);
+
+  vSemaphoreCreateBinary(ledseqSem);
+
+  isInit = true;
+}
+
+bool ledseqTest(void)
+{
+  bool status;
+
+  status = isInit & ledTest();
+  ledseqEnable(true);
+  return status;
+}
+
+void ledseqEnable(bool enable)
+{
+  ledseqEnabled = enable;
+}
+
+void ledseqRun(led_t led, const ledseq_t *sequence)
+{
+  int prio = getPrio(sequence);
+
+  if(prio<0) return;
+
+  xSemaphoreTake(ledseqSem, portMAX_DELAY);
+  state[led][prio] = 0;  //Reset the seq. to its first step
+  updateActive(led);
+  xSemaphoreGive(ledseqSem);
+
+  //Run the first step if the new seq is the active sequence
+  if(activeSeq[led] == prio)
+    runLedseq(timer[led]);
+}
+
+void ledseqSetTimes(ledseq_t *sequence, int32_t onTime, int32_t offTime)
+{
+  sequence[0].action = onTime;
+  sequence[1].action = offTime;
+}
+
+void ledseqStop(led_t led, const ledseq_t *sequence)
+{
+  int prio = getPrio(sequence);
+
+  if(prio<0) return;
+
+  xSemaphoreTake(ledseqSem, portMAX_DELAY);
+  state[led][prio] = LEDSEQ_STOP;  //Stop the seq.
+  updateActive(led);
+  xSemaphoreGive(ledseqSem);
+
+  //Run the next active sequence (if any...)
+  runLedseq(timer[led]);
+}
+
+/* Center of the led sequence machine. This function is executed by the FreeRTOS
+ * timer and runs the sequences
+ */
+static void runLedseq( xTimerHandle xTimer )
+{
+  led_t led = (led_t)pvTimerGetTimerID(xTimer);
+  const ledseq_t *step;
+  bool leave=false;
+
+  if (!ledseqEnabled)
+    return;
+
+  while(!leave) {
+    int prio = activeSeq[led];
+
+    if (prio == LEDSEQ_STOP)
+      return;
+
+    step = &sequences[prio][state[led][prio]];
+
+    state[led][prio]++;
+
+    xSemaphoreTake(ledseqSem, portMAX_DELAY);
+    switch(step->action)
+    {
+      case LEDSEQ_LOOP:
+        state[led][prio] = 0;
+        break;
+      case LEDSEQ_STOP:
+        state[led][prio] = LEDSEQ_STOP;
+        updateActive(led);
+        break;
+      default:  //The step is a LED action and a time
+        ledSet(led, step->value);
+        if (step->action == 0)
+          break;
+        xTimerChangePeriod(xTimer, M2T(step->action), 0);
+        xTimerStart(xTimer, 0);
+        leave=true;
+        break;
+    }
+    xSemaphoreGive(ledseqSem);
+  }
+}
+
+//Utility functions
+static int getPrio(const ledseq_t *seq)
+{
+  int prio;
+
+  //Find the priority of the sequence
+  for(prio=0; prio<SEQ_NUM; prio++)
+    if(sequences[prio]==seq) return prio;
+
+  return -1; //Invalid sequence
+}
+
+static void updateActive(led_t led)
+{
+  int prio;
+
+  activeSeq[led]=LEDSEQ_STOP;
+  ledSet(led, false);
+
+  for(prio=0;prio<SEQ_NUM;prio++)
+  {
+    if (state[led][prio] != LEDSEQ_STOP)
+    {
+      activeSeq[led]=prio;
+      break;
+    }
+  }
+}
diff --git a/crazyflie-firmware-src/src/hal/src/nrf24link.c b/crazyflie-firmware-src/src/hal/src/nrf24link.c
new file mode 100644
index 0000000000000000000000000000000000000000..76cfb7427890035d30f896cbc11e47c0d9ebc0ff
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/nrf24link.c
@@ -0,0 +1,264 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * nrf24link.c: nRF24L01 implementation of the CRTP link
+ */
+
+#include <stdbool.h>
+#include <errno.h>
+
+#include "config.h"
+#include "nrf24l01.h"
+#include "crtp.h"
+#include "configblock.h"
+#include "ledseq.h"
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "semphr.h"
+
+static bool isInit;
+
+#define RADIO_CONNECTED_TIMEOUT   M2T(2000)
+
+/* Synchronisation */
+xSemaphoreHandle dataRdy;
+/* Data queue */
+xQueueHandle txQueue;
+xQueueHandle rxQueue;
+
+static uint32_t lastPacketTick;
+
+//Union used to efficiently handle the packets (Private type)
+typedef union
+{
+  CRTPPacket crtp;
+  struct {
+    uint8_t size;
+    uint8_t data[32];
+  } __attribute__((packed)) raw;
+} RadioPacket;
+
+static struct {
+  bool enabled;
+} state;
+
+static void interruptCallback()
+{
+  portBASE_TYPE  xHigherPriorityTaskWoken = pdFALSE;
+
+  //To unlock RadioTask
+  xSemaphoreGiveFromISR(dataRdy, &xHigherPriorityTaskWoken);
+
+  if(xHigherPriorityTaskWoken)
+    portYIELD();
+}
+
+// 'Class' functions, called from callbacks
+static int setEnable(bool enable)
+{
+  nrfSetEnable(enable);
+  state.enabled = enable;
+
+  return 0;
+}
+
+static int sendPacket(CRTPPacket * pk)
+{
+  if (!state.enabled)
+    return ENETDOWN;
+
+  if (xQueueSend(txQueue, pk, M2T(100)) == pdTRUE)
+  {
+    return true;
+  }
+
+  return false;
+}
+
+static int receivePacket(CRTPPacket * pk)
+{
+  if (!state.enabled)
+    return ENETDOWN;
+
+  xQueueReceive( rxQueue, pk, portMAX_DELAY);
+
+  return 0;
+}
+
+static int reset(void)
+{
+  xQueueReset(txQueue);
+  nrfFlushTx();
+
+  return 0;
+}
+
+static bool isConnected(void)
+{
+  if ((xTaskGetTickCount() - lastPacketTick) > RADIO_CONNECTED_TIMEOUT)
+    return false;
+
+  return true;
+}
+
+static struct crtpLinkOperations radioOp =
+{
+  .setEnable         = setEnable,
+  .sendPacket        = sendPacket,
+  .receivePacket     = receivePacket,
+  .isConnected       = isConnected,
+  .reset             = reset,
+};
+
+/* Radio task handles the CRTP packet transfers as well as the radio link
+ * specific communications (eg. Scann and ID ports, communication error handling
+ * and so much other cool things that I don't have time for it ...)
+ */
+static void nrf24linkTask(void * arg)
+{
+  unsigned char dataLen;
+  static RadioPacket pk;
+
+  //Packets handling loop
+  while(1)
+  {
+    ledseqRun(LED_GREEN, seq_linkup);
+
+    xSemaphoreTake(dataRdy, portMAX_DELAY);
+    lastPacketTick = xTaskGetTickCount();
+    
+    nrfSetEnable(false);
+    
+    //Fetch all the data (Loop until the RX Fifo is NOT empty)
+    while( !(nrfRead1Reg(REG_FIFO_STATUS)&0x01) )
+    {
+      dataLen = nrfRxLength(0);
+
+      if (dataLen>32)          //If a packet has a wrong size it is dropped
+        nrfFlushRx();
+      else                     //Else, it is processed
+      {
+        //Fetch the data
+        pk.raw.size = dataLen-1;
+        nrfReadRX((char *)pk.raw.data, dataLen);
+
+        //Push it in the queue (If overflow, the packet is dropped)
+        if (!CRTP_IS_NULL_PACKET(pk.crtp))  //Don't follow the NULL packets
+          xQueueSend( rxQueue, &pk, 0);
+      }
+    }
+
+    //Push the data to send (Loop until the TX Fifo is full or there is no more data to send)
+    while( (uxQueueMessagesWaiting((xQueueHandle)txQueue) > 0) && !(nrfRead1Reg(REG_FIFO_STATUS)&0x20) )
+    {
+      xQueueReceive(txQueue, &pk, 0);
+      pk.raw.size++;
+
+      nrfWriteAck(0, (char*) pk.raw.data, pk.raw.size);
+    }
+
+    //clear the interruptions flags
+    nrfWrite1Reg(REG_STATUS, 0x70);
+    
+    //Re-enable the radio
+    nrfSetEnable(true);
+  }
+}
+
+static void nrf24linkInitNRF24L01P(void)
+{
+  int i;
+  char radioAddress[5] = {0xE7, 0xE7, 0xE7, 0xE7, 0xE7};
+
+  //Set the radio channel
+  nrfSetChannel(configblockGetRadioChannel());
+  //Set the radio data rate
+  nrfSetDatarate(configblockGetRadioSpeed());
+  //Set radio address
+  nrfSetAddress(0, radioAddress);
+
+  //Power the radio, Enable the DS interruption, set the radio in PRX mode
+  nrfWrite1Reg(REG_CONFIG, 0x3F);
+  vTaskDelay(M2T(2)); //Wait for the chip to be ready
+  // Enable the dynamic payload size and the ack payload for the pipe 0
+  nrfWrite1Reg(REG_FEATURE, 0x06);
+  nrfWrite1Reg(REG_DYNPD, 0x01);
+
+  //Flush RX
+  for(i=0;i<3;i++)
+    nrfFlushRx();
+  //Flush TX
+  for(i=0;i<3;i++)
+    nrfFlushTx();
+}
+
+/*
+ * Public functions
+ */
+
+void nrf24linkInit()
+{
+  if(isInit)
+    return;
+
+  nrfInit();
+
+  nrfSetInterruptCallback(interruptCallback);
+
+  vTaskSetApplicationTaskTag(0, (void*)TASK_RADIO_ID_NBR);
+
+  /* Initialise the semaphores */
+  vSemaphoreCreateBinary(dataRdy);
+
+  /* Queue init */
+  rxQueue = xQueueCreate(3, sizeof(RadioPacket));
+  txQueue = xQueueCreate(3, sizeof(RadioPacket));
+
+  nrf24linkInitNRF24L01P();
+
+    /* Launch the Radio link task */
+  xTaskCreate(nrf24linkTask, NRF24LINK_TASK_NAME,
+              NRF24LINK_TASK_STACKSIZE, NULL, NRF24LINK_TASK_PRI, NULL);
+
+  isInit = true;
+}
+
+bool nrf24linkTest()
+{
+  return nrfTest();
+}
+
+struct crtpLinkOperations * nrf24linkGetLink()
+{
+  return &radioOp;
+}
+
+void nrf24linkReInit(void)
+{
+  if (!isInit)
+    return;
+
+  nrf24linkInitNRF24L01P();
+}
diff --git a/crazyflie-firmware-src/src/hal/src/ow_none.c b/crazyflie-firmware-src/src/hal/src/ow_none.c
new file mode 100644
index 0000000000000000000000000000000000000000..f3261ca0cb4f4bc847bf323eea1ff2953e94470a
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/ow_none.c
@@ -0,0 +1,68 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * ow.c - One-wire functions
+ */
+#define DEBUG_MODULE "OW"
+
+#include  <string.h>
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+
+#include "ow.h"
+
+
+void owInit()
+{
+}
+
+bool owTest()
+{
+  return true;
+}
+
+void owSyslinkRecieve(SyslinkPacket *slp)
+{
+}
+
+bool owScan(uint8_t *nMem)
+{
+  return true;
+}
+
+bool owGetinfo(uint8_t selectMem, OwSerialNum *serialNum)
+{
+  return false;
+}
+
+bool owRead(uint8_t selectMem, uint16_t address, uint8_t length, uint8_t *data)
+{
+  return false;
+}
+
+bool owWrite(uint8_t selectMem, uint16_t address, uint8_t length, uint8_t *data)
+{
+  return false;
+}
+
diff --git a/crazyflie-firmware-src/src/hal/src/ow_syslink.c b/crazyflie-firmware-src/src/hal/src/ow_syslink.c
new file mode 100644
index 0000000000000000000000000000000000000000..ec54051c23ddd9e3e0d91b18c7be62aaa25985af
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/ow_syslink.c
@@ -0,0 +1,320 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * ow.c - One-wire functions
+ */
+#define DEBUG_MODULE "OW"
+
+#include  <string.h>
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+
+#include "ow.h"
+#include "assert.h"
+#include "debug.h"
+
+static xSemaphoreHandle waitForReply;
+static xSemaphoreHandle lockCmdBuf;
+static OwCommand owCmdBuf;
+static bool owDataIsValid;
+
+static bool owSyslinkTransfer(uint8_t type, uint8_t length);
+
+#ifdef OW_WRITE_TEST
+static uint8_t bqtestData[] =
+{
+  0xEB, 0x00, 0x00, 0x00, 0x00, 0xBC, 0xFE, 0x3C, 0x00, 0x0D, 0x01, 0x08,
+  0x62, 0x63, 0x42, 0x51, 0x74, 0x65, 0x73, 0x74, 0x02, 0x01, 0x61, 0x70
+};
+#endif
+
+
+void owInit()
+{
+  syslinkInit();
+  vSemaphoreCreateBinary(waitForReply);
+  lockCmdBuf = xSemaphoreCreateMutex();
+
+  // Put reply semaphore in right state.
+  xSemaphoreTake(waitForReply, portMAX_DELAY);
+}
+
+bool owTest()
+{
+  uint8_t nOwMem = 0;
+  uint8_t nOwIter = 0;
+  OwSerialNum sn;
+
+  if (owScan(&nOwMem))
+  {
+    DEBUG_PRINT("Found %d.\n", nOwMem);
+  }
+  else
+  {
+    DEBUG_PRINT("Scan [FAILED].\n");
+  }
+
+  for (nOwIter = 0; nOwIter < nOwMem; nOwIter++)
+  {
+    if (owGetinfo(nOwIter, &sn))
+    {
+      DEBUG_PRINT("Serial 0x%X %X %X %X %X %X %X %X.\n",
+                  sn.type, sn.id[0], sn.id[1], sn.id[2],
+                  sn.id[3], sn.id[4], sn.id[5], sn.crc);
+    }
+    else
+    {
+      DEBUG_PRINT("Mem:%d Getinfo [FAILED].\n", nOwIter);
+    }
+  }
+
+#ifdef OW_READ_TEST
+  {
+    static uint8_t testbuf[129];
+
+    if (owRead(0, 0, OW_MAX_SIZE, testbuf))
+    {
+      for (nOwIter = 0; nOwIter < OW_MAX_SIZE; nOwIter++)
+      {
+        consolePrintf("%X ", testbuf[nOwIter]);
+        testbuf[nOwIter] = nOwIter;
+      }
+      consolePrintf("\n");
+    }
+  }
+#endif
+#ifdef OW_WRITE_TEST
+  if (owWrite(0, 0, sizeof(bqtestData), bqtestData))
+  {
+    DEBUG_PRINT("Write [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("Write [FAIL].\n");
+  }
+#endif
+
+  return true;
+}
+
+void owSyslinkRecieve(SyslinkPacket *slp)
+{
+  switch (slp->type)
+  {
+    case SYSLINK_OW_SCAN:
+    case SYSLINK_OW_GETINFO:
+    case SYSLINK_OW_READ:
+    case SYSLINK_OW_WRITE:
+      memcpy(&owCmdBuf, slp->data, sizeof(OwCommand));
+      //DEBUG_PRINT("t:%X n:%d:%X\n", slp->type, owCmdBuf.nmem, owCmdBuf.info.memId[0]);
+      owDataIsValid = true;
+      break;
+    default:
+      // Unknown reply
+      owDataIsValid = false;
+      break;
+  }
+  xSemaphoreGive(waitForReply);
+}
+
+static bool owSyslinkTransfer(uint8_t type, uint8_t length)
+{
+  SyslinkPacket slp;
+
+  ASSERT(length <= SYSLINK_MTU);
+
+  slp.type = type;
+  slp.length = length;
+  memcpy(slp.data, &owCmdBuf, length);
+
+  syslinkSendPacket(&slp);
+  // Wait for reply
+  if (xSemaphoreTake(waitForReply, M2T(5000)) == pdTRUE)
+  //if (xSemaphoreTake(waitForReply, portMAX_DELAY))
+  {
+    // We have now got a reply and *owCmd has been filled with data
+    if (owDataIsValid)
+    {
+      owDataIsValid = false;
+      return true;
+    }
+  }
+  else
+  {
+    DEBUG_PRINT("Cmd 0x%X timeout.\n", slp.type);
+  }
+
+  return false;
+}
+
+bool owScan(uint8_t *nMem)
+{
+  bool status = false;
+
+  xSemaphoreTake(lockCmdBuf, portMAX_DELAY);
+
+  if (owSyslinkTransfer(SYSLINK_OW_SCAN, 0))
+  {
+    *nMem = owCmdBuf.nmem;
+    status = true;
+  }
+  else
+  {
+    status = false;
+  }
+
+  xSemaphoreGive(lockCmdBuf);
+
+  return status;
+}
+
+bool owGetinfo(uint8_t selectMem, OwSerialNum *serialNum)
+{
+  bool status = false;
+
+  xSemaphoreTake(lockCmdBuf, portMAX_DELAY);
+  owCmdBuf.nmem = selectMem;
+
+  if (owSyslinkTransfer(SYSLINK_OW_GETINFO, 1))
+  {
+    memcpy(serialNum, owCmdBuf.info.memId, sizeof(OwSerialNum));
+    if (owCmdBuf.nmem != 0xFF)
+    {
+      status = true;
+    }
+  }
+  else
+  {
+    status = false;
+  }
+
+  xSemaphoreGive(lockCmdBuf);
+
+  return status;
+}
+
+bool owRead(uint8_t selectMem, uint16_t address, uint8_t length, uint8_t *data)
+{
+  bool status = true;
+  uint16_t currAddr = address;
+  uint16_t endAddr = address + length;
+  uint8_t bytesRead = 0;
+
+  ASSERT(length <= OW_MAX_SIZE);
+
+  xSemaphoreTake(lockCmdBuf, portMAX_DELAY);
+  owCmdBuf.nmem = selectMem;
+
+  while (currAddr < endAddr)
+  {
+    if (endAddr - currAddr < OW_READ_SIZE)
+    {
+      owCmdBuf.read.address = currAddr;
+      if (owSyslinkTransfer(SYSLINK_OW_READ, 3 + endAddr - currAddr))
+      {
+        memcpy(data + bytesRead, owCmdBuf.read.data, endAddr - currAddr);
+        currAddr += endAddr - currAddr;
+        bytesRead += endAddr - currAddr;
+      }
+      else
+      {
+        status = false;
+        break;
+      }
+    }
+    else // Size is bigger then OW_READ_SIZE
+    {
+      owCmdBuf.read.address = currAddr;
+      if (owSyslinkTransfer(SYSLINK_OW_READ, 3 + OW_READ_SIZE))
+      {
+        memcpy(data + bytesRead, owCmdBuf.read.data, OW_READ_SIZE);
+        currAddr += OW_READ_SIZE;
+        bytesRead += OW_READ_SIZE;
+      }
+      else
+      {
+        status = false;
+        break;
+      }
+    }
+  }
+
+  xSemaphoreGive(lockCmdBuf);
+
+  return status;
+}
+
+bool owWrite(uint8_t selectMem, uint16_t address, uint8_t length, uint8_t *data)
+{
+  bool status = true;
+  uint16_t currAddr = address;
+  uint16_t endAddr = address + length;
+  uint8_t bytesWritten = 0;
+
+  ASSERT(length <= OW_MAX_SIZE);
+
+  xSemaphoreTake(lockCmdBuf, portMAX_DELAY);
+  owCmdBuf.nmem = selectMem;
+
+  while (currAddr < endAddr)
+  {
+    if (endAddr - currAddr < OW_MAX_WRITE_SIZE)
+    {
+      owCmdBuf.write.address = currAddr;
+      owCmdBuf.write.length = endAddr - currAddr;
+      memcpy(owCmdBuf.write.data, data + bytesWritten, owCmdBuf.write.length);
+      if (owSyslinkTransfer(SYSLINK_OW_WRITE, 5 + owCmdBuf.write.length))
+      {
+        currAddr += endAddr - currAddr;
+        bytesWritten += endAddr - currAddr;
+      }
+      else
+      {
+        status = false;
+        break;
+      }
+    }
+    else // Size is bigger then OW_MAX_WRITE_SIZE
+    {
+      owCmdBuf.write.address = currAddr;
+      owCmdBuf.write.length = OW_MAX_WRITE_SIZE;
+      memcpy(owCmdBuf.write.data, data + bytesWritten, owCmdBuf.write.length);
+      if (owSyslinkTransfer(SYSLINK_OW_WRITE, 5 + owCmdBuf.write.length))
+      {
+        currAddr += OW_MAX_WRITE_SIZE;
+        bytesWritten += OW_MAX_WRITE_SIZE;
+      }
+      else
+      {
+        status = false;
+        break;
+      }
+    }
+  }
+
+  xSemaphoreGive(lockCmdBuf);
+
+  return status;
+}
+
diff --git a/crazyflie-firmware-src/src/hal/src/pm_f103.c b/crazyflie-firmware-src/src/hal/src/pm_f103.c
new file mode 100644
index 0000000000000000000000000000000000000000..fd9b5aa7d586651db28bd16efcca56895a926d17
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/pm_f103.c
@@ -0,0 +1,508 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * pm.c - Power Management driver and functions.
+ */
+
+#include "stm32fxxx.h"
+#include <string.h>
+#include <stdbool.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+
+#include "config.h"
+#include "system.h"
+#include "pm.h"
+#include "led.h"
+#include "log.h"
+#include "adc.h"
+#include "ledseq.h"
+#include "commander.h"
+#include "nrf24link.h"
+
+// Power managment pins
+#define PM_GPIO_SYSOFF_PERIF    RCC_APB2Periph_GPIOA
+#define PM_GPIO_SYSOFF_PORT     GPIOA
+#define PM_GPIO_SYSOFF          GPIO_Pin_1
+
+#define PM_GPIO_EN1_PERIF       RCC_APB2Periph_GPIOC
+#define PM_GPIO_EN1_PORT        GPIOC
+#define PM_GPIO_EN1             GPIO_Pin_13
+
+#define PM_GPIO_EN2_PERIF       RCC_APB2Periph_GPIOA
+#define PM_GPIO_EN2_PORT        GPIOA
+#define PM_GPIO_EN2             GPIO_Pin_2
+
+#define PM_GPIO_IN_CHG_PERIF    RCC_APB2Periph_GPIOB
+#define PM_GPIO_IN_CHG_PORT     GPIOB
+#define PM_GPIO_IN_CHG          GPIO_Pin_2
+
+#define PM_GPIO_IN_PGOOD_PERIF  RCC_APB2Periph_GPIOC
+#define PM_GPIO_IN_PGOOD_PORT   GPIOC
+#define PM_GPIO_IN_PGOOD        GPIO_Pin_15
+
+// Power managment pins
+#define PM_GPIO_BAT_PERIF       RCC_APB2Periph_GPIOA
+#define PM_GPIO_BAT_PORT        GPIOA
+#define PM_GPIO_BAT             GPIO_Pin_3
+
+//USB pins to detect adapter or host.
+#define PM_GPIO_USB_CON_PERIF   RCC_APB2Periph_GPIOA
+#define PM_GPIO_USB_CON_PORT    GPIOA
+#define PM_GPIO_USB_CON         GPIO_Pin_0
+
+#define PM_GPIO_USB_DM_PERIF    RCC_APB2Periph_GPIOA
+#define PM_GPIO_USB_DM_PORT     GPIOA
+#define PM_GPIO_USB_DM          GPIO_Pin_11
+
+#define PM_GPIO_USB_DP_PERIF    RCC_APB2Periph_GPIOA
+#define PM_GPIO_USB_DP_PORT     GPIOA
+#define PM_GPIO_USB_DP          GPIO_Pin_12
+
+static float    batteryVoltage;
+static float    batteryVoltageMin = 6.0;
+static float    batteryVoltageMax = 0.0;
+static int32_t  batteryVRawFilt = PM_BAT_ADC_FOR_3_VOLT;
+static int32_t  batteryVRefRawFilt = PM_BAT_ADC_FOR_1p2_VOLT;
+static uint32_t batteryLowTimeStamp;
+static uint32_t batteryCriticalLowTimeStamp;
+static bool isInit;
+static PMStates pmState;
+static PMChargeStates pmChargeState;
+
+static void pmSetBatteryVoltage(float voltage);
+
+const static float bat671723HS25C[10] =
+{
+  3.00, // 00%
+  3.78, // 10%
+  3.83, // 20%
+  3.87, // 30%
+  3.89, // 40%
+  3.92, // 50%
+  3.96, // 60%
+  4.00, // 70%
+  4.04, // 80%
+  4.10  // 90%
+};
+
+void pmInit(void)
+{
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  if(isInit)
+    return;
+
+  RCC_APB2PeriphClockCmd(PM_GPIO_IN_PGOOD_PERIF | PM_GPIO_IN_CHG_PERIF |
+                         PM_GPIO_SYSOFF_PERIF | PM_GPIO_EN1_PERIF | 
+                         PM_GPIO_EN2_PERIF | PM_GPIO_BAT_PERIF, ENABLE);
+
+  // Configure PM PGOOD pin (Power good)
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_IN_PGOOD;
+  GPIO_Init(PM_GPIO_IN_PGOOD_PORT, &GPIO_InitStructure);
+  // Configure PM CHG pin (Charge)
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_IN_CHG;
+  GPIO_Init(PM_GPIO_IN_CHG_PORT, &GPIO_InitStructure);
+  // Configure PM EN2 pin
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_EN2;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+  GPIO_Init(PM_GPIO_EN2_PORT, &GPIO_InitStructure);
+  // Configure PM EN1 pin
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_EN1;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+  GPIO_Init(PM_GPIO_EN1_PORT, &GPIO_InitStructure);
+  // Configure PM SYSOFF pin
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_SYSOFF;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+  GPIO_Init(PM_GPIO_SYSOFF_PORT, &GPIO_InitStructure);
+  // Configure battery ADC pin
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_BAT;
+  GPIO_Init(PM_GPIO_BAT_PORT, &GPIO_InitStructure);
+
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_USB_CON;
+  GPIO_Init(PM_GPIO_USB_CON_PORT, &GPIO_InitStructure);
+  
+  xTaskCreate(pmTask, PM_TASK_NAME,
+              PM_TASK_STACKSIZE, NULL, PM_TASK_PRI, NULL);
+  
+  isInit = true;
+
+  pmSetBatteryVoltage(3.7f); //TODO remove
+}
+
+bool pmTest(void)
+{
+  return isInit;
+}
+
+/**
+ * Test USB signals for host or power adapter
+ */
+static PMUSBPower pmTestUSBPower(void)
+{
+  PMUSBPower pmUSBPower = USB500mA;
+
+#ifdef ENABLE_FAST_CHARGE
+  GPIO_InitTypeDef GPIO_InitStructure;
+
+  RCC_APB2PeriphClockCmd(PM_GPIO_USB_DM_PERIF | PM_GPIO_USB_DM_PERIF | PM_GPIO_USB_DP_PERIF, ENABLE);
+
+  // Configure USB connect pin
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_USB_CON;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+  GPIO_Init(PM_GPIO_USB_CON_PORT, &GPIO_InitStructure);
+  // Configure USB DM pin
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_USB_DM;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD;
+  GPIO_Init(PM_GPIO_USB_DM_PORT, &GPIO_InitStructure);
+  // Configure USB DP pin
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_USB_DP;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
+  GPIO_Init(PM_GPIO_USB_DP_PORT, &GPIO_InitStructure);
+  
+  // Enable 1.5K pull-up for USB DP signal
+  GPIO_SetBits(PM_GPIO_USB_CON_PORT, PM_GPIO_USB_CON);
+  // Let the voltage level setle.
+  vTaskDelay(M2T(1));
+  // Read the weak pull-down of USB-DM. If it is high, DP and DM are shorted.
+  if (GPIO_ReadInputDataBit(PM_GPIO_USB_DM_PORT, PM_GPIO_USB_DM) == Bit_SET)
+  {
+    pmUSBPower = USBWallAdapter;
+  }
+  else
+  {
+    pmUSBPower = USB500mA;
+  }
+  // Reset USB pins to default
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+  GPIO_InitStructure.GPIO_Pin = PM_GPIO_USB_DM | PM_GPIO_USB_CON | PM_GPIO_USB_DP;
+  GPIO_Init(PM_GPIO_USB_DP_PORT, &GPIO_InitStructure);
+#endif
+
+  return pmUSBPower;
+}
+
+/**
+ * IIR low pass filter the samples.
+ */
+static int16_t pmBatteryIIRLPFilter(uint16_t in, int32_t* filt)
+{
+  int32_t inScaled;
+  int32_t filttmp = *filt;
+  int16_t out;
+
+  // Shift to keep accuracy
+  inScaled = in << PM_BAT_IIR_SHIFT;
+  // Calculate IIR filter
+  filttmp = filttmp + (((inScaled-filttmp) >> 8) * PM_BAT_IIR_LPF_ATT_FACTOR);
+  // Scale and round
+  out = (filttmp >> 8) + ((filttmp & (1 << (PM_BAT_IIR_SHIFT - 1))) >> (PM_BAT_IIR_SHIFT - 1));
+  *filt = filttmp;
+
+  return out;
+}
+
+/**
+ * Sets the battery voltage and its min and max values
+ */
+static void pmSetBatteryVoltage(float voltage)
+{
+  batteryVoltage = voltage;
+  if (batteryVoltageMax < voltage)
+  {
+    batteryVoltageMax = voltage;
+  }
+  if (batteryVoltageMin > voltage)
+  {
+    batteryVoltageMin = voltage;
+  }
+}
+
+/**
+ * Shutdown system
+ */
+static void pmSystemShutdown(void)
+{
+#ifdef ACTIVATE_AUTO_SHUTDOWN
+  GPIO_SetBits(PM_GPIO_SYSOFF_PORT, PM_GPIO_SYSOFF);
+#endif
+}
+
+/**
+ * Returns a number from 0 to 9 where 0 is completely discharged
+ * and 9 is 90% charged.
+ */
+static int32_t pmBatteryChargeFromVoltage(float voltage)
+{
+  int charge = 0;
+
+  if (voltage < bat671723HS25C[0])
+  {
+    return 0;
+  }
+  if (voltage > bat671723HS25C[9])
+  {
+    return 9;
+  }
+  while (voltage >  bat671723HS25C[charge])
+  {
+    charge++;
+  }
+
+  return charge;
+}
+
+
+float pmGetBatteryVoltage(void)
+{
+  return batteryVoltage;
+}
+
+float pmGetBatteryVoltageMin(void)
+{
+  return batteryVoltageMin;
+}
+
+float pmGetBatteryVoltageMax(void)
+{
+  return batteryVoltageMax;
+}
+
+void pmBatteryUpdate(AdcGroup* adcValues)
+{
+  float vBat;
+  int16_t vBatRaw;
+  int16_t vBatRefRaw;
+
+  vBatRaw = pmBatteryIIRLPFilter(adcValues->vbat.val, &batteryVRawFilt);
+  vBatRefRaw = pmBatteryIIRLPFilter(adcValues->vbat.vref, &batteryVRefRawFilt);
+
+  vBat = adcConvertToVoltageFloat(vBatRaw, vBatRefRaw) * PM_BAT_DIVIDER;
+  pmSetBatteryVoltage(vBat);
+}
+
+void pmSetChargeState(PMChargeStates chgState)
+{
+  pmChargeState = chgState;
+
+  switch (chgState)
+  {
+    case charge100mA:
+      GPIO_ResetBits(PM_GPIO_EN1_PORT, PM_GPIO_EN1);
+      GPIO_ResetBits(PM_GPIO_EN2_PORT, PM_GPIO_EN2);
+      break;
+    case charge500mA:
+      GPIO_SetBits(PM_GPIO_EN1_PORT, PM_GPIO_EN1);
+      GPIO_ResetBits(PM_GPIO_EN2_PORT, PM_GPIO_EN2);
+      break;
+    case chargeMax:
+      GPIO_ResetBits(PM_GPIO_EN1_PORT, PM_GPIO_EN1);
+      GPIO_SetBits(PM_GPIO_EN2_PORT, PM_GPIO_EN2);
+      break;
+  }
+}
+
+PMChargeStates pmGetChargeState(void)
+{
+  return pmChargeState;
+}
+
+PMStates pmUpdateState()
+{
+  PMStates state;
+  bool isCharging = !GPIO_ReadInputDataBit(PM_GPIO_IN_CHG_PORT, PM_GPIO_IN_CHG);
+  bool isPgood = !GPIO_ReadInputDataBit(PM_GPIO_IN_PGOOD_PORT, PM_GPIO_IN_PGOOD);
+  uint32_t batteryLowTime;
+
+  batteryLowTime = xTaskGetTickCount() - batteryLowTimeStamp;
+
+  if (isPgood && !isCharging)
+  {
+    state = charged;
+  }
+  else if (isPgood && isCharging)
+  {
+    state = charging;
+  }
+  else if (!isPgood && !isCharging && (batteryLowTime > PM_BAT_LOW_TIMEOUT))
+  {
+    state = lowPower;
+  }
+  else
+  {
+    state = battery;
+  }
+
+  return state;
+}
+
+
+// return true if battery discharging
+bool pmIsDischarging(void) {
+    PMStates pmState;
+    pmState = pmUpdateState();
+    return (pmState == lowPower )|| (pmState == battery);
+}
+
+void pmTask(void *param)
+{
+  PMStates pmStateOld = battery;
+  uint32_t tickCount;
+
+  vTaskSetApplicationTaskTag(0, (void*)TASK_PM_ID_NBR);
+
+  tickCount = xTaskGetTickCount();
+  batteryLowTimeStamp = tickCount;
+  batteryCriticalLowTimeStamp = tickCount;
+
+  pmSetChargeState(charge500mA);
+
+  vTaskDelay(1000);
+
+  while(1)
+  {
+    vTaskDelay(100);
+    tickCount = xTaskGetTickCount();
+
+    if (pmGetBatteryVoltage() > PM_BAT_LOW_VOLTAGE)
+    {
+      batteryLowTimeStamp = tickCount;
+    }
+    if (pmGetBatteryVoltage() > PM_BAT_CRITICAL_LOW_VOLTAGE)
+    {
+      batteryCriticalLowTimeStamp = tickCount;
+    }
+
+    pmState = pmUpdateState();
+
+    if (pmState != pmStateOld)
+    {
+      // Actions on state change
+      switch (pmState)
+      {
+        case charged:
+          ledseqStop(LED_GREEN, seq_charging);
+          ledseqStop(LED_GREEN, seq_chargingMax);
+          ledseqRun(LED_GREEN, seq_charged);
+          systemSetCanFly(false);
+          break;
+        case charging:
+          ledseqStop(LED_RED, seq_lowbat);
+          ledseqStop(LED_GREEN, seq_charged);
+          if (pmTestUSBPower() == USBWallAdapter)
+          {
+            pmSetChargeState(chargeMax);
+            ledseqRun(LED_GREEN, seq_chargingMax);
+          }
+          else
+          {
+            pmSetChargeState(charge500mA);
+            ledseqRun(LED_GREEN, seq_charging);
+          }
+          systemSetCanFly(false);
+          //Due to voltage change radio must be restarted
+          nrf24linkReInit();
+          break;
+        case lowPower:
+          ledseqRun(LED_RED, seq_lowbat);
+          systemSetCanFly(true);
+          break;
+        case battery:
+          ledseqStop(LED_GREEN, seq_charging);
+          ledseqStop(LED_GREEN, seq_charged);
+          systemSetCanFly(true);
+          //Due to voltage change radio must be restarted
+          nrf24linkReInit();
+          break;
+        default:
+          systemSetCanFly(true);
+          break;
+      }
+      pmStateOld = pmState;
+    }
+    // Actions during state
+    switch (pmState)
+    {
+      case charged:
+        break;
+      case charging:
+        {
+          uint32_t onTime;
+          if (pmGetChargeState() == chargeMax)
+          {
+            onTime = pmBatteryChargeFromVoltage(pmGetBatteryVoltage()) *
+                     (LEDSEQ_CHARGE_CYCLE_TIME_MAX / 10);
+            ledseqSetTimes(seq_chargingMax, onTime, LEDSEQ_CHARGE_CYCLE_TIME_MAX - onTime);
+          }
+          else
+          {
+            onTime = pmBatteryChargeFromVoltage(pmGetBatteryVoltage()) *
+                     (LEDSEQ_CHARGE_CYCLE_TIME_500MA / 10);
+            ledseqSetTimes(seq_charging, onTime, LEDSEQ_CHARGE_CYCLE_TIME_500MA - onTime);
+          }
+        }
+        break;
+      case lowPower:
+        {
+          uint32_t batteryCriticalLowTime;
+
+          batteryCriticalLowTime = tickCount - batteryCriticalLowTimeStamp;
+          if (batteryCriticalLowTime > PM_BAT_CRITICAL_LOW_TIMEOUT)
+          {
+            pmSystemShutdown();
+          }
+        }
+        break;
+      case battery:
+        {
+          if ((commanderGetInactivityTime() > PM_SYSTEM_SHUTDOWN_TIMEOUT))
+          {
+            pmSystemShutdown();
+          }
+        }
+        break;
+      default:
+        break;
+    }
+  }
+}
+
+LOG_GROUP_START(pm)
+LOG_ADD(LOG_FLOAT, vbat, &batteryVoltage)
+LOG_ADD(LOG_INT8, state, &pmState)
+LOG_GROUP_STOP(pm)
+
diff --git a/crazyflie-firmware-src/src/hal/src/pm_f405.c b/crazyflie-firmware-src/src/hal/src/pm_f405.c
new file mode 100644
index 0000000000000000000000000000000000000000..6b372c7fb21c81c2aefeda140a55e49e3ffd4b80
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/pm_f405.c
@@ -0,0 +1,391 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * pm.c - Power Management driver and functions.
+ */
+
+#include "stm32fxxx.h"
+#include <string.h>
+#include <stdbool.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+
+#include "config.h"
+#include "system.h"
+#include "pm.h"
+#include "led.h"
+#include "log.h"
+#include "ledseq.h"
+#include "commander.h"
+#include "sound.h"
+#include "deck.h"
+
+typedef struct _PmSyslinkInfo
+{
+  union
+  {
+    uint8_t flags;
+    struct
+    {
+      uint8_t pgood  : 1;
+      uint8_t chg    : 1;
+      uint8_t unused : 6;
+    };
+  };
+  float vBat;
+  float chargeCurrent;
+}  __attribute__((packed)) PmSyslinkInfo;
+
+static float    batteryVoltage;
+static uint16_t batteryVoltageMV;
+static float    batteryVoltageMin = 6.0;
+static float    batteryVoltageMax = 0.0;
+
+static float    extBatteryVoltage;
+static uint16_t extBatteryVoltageMV;
+static uint8_t  extBatVoltDeckPin;
+static float    extBatVoltMultiplier;
+static float    extBatteryCurrent;
+static uint8_t  extBatCurrDeckPin;
+static float    extBatCurrAmpPerVolt;
+
+static uint32_t batteryLowTimeStamp;
+static uint32_t batteryCriticalLowTimeStamp;
+static bool isInit;
+static PMStates pmState;
+static PmSyslinkInfo pmSyslinkInfo;
+
+static void pmSetBatteryVoltage(float voltage);
+
+const static float bat671723HS25C[10] =
+{
+  3.00, // 00%
+  3.78, // 10%
+  3.83, // 20%
+  3.87, // 30%
+  3.89, // 40%
+  3.92, // 50%
+  3.96, // 60%
+  4.00, // 70%
+  4.04, // 80%
+  4.10  // 90%
+};
+
+void pmInit(void)
+{
+  if(isInit)
+    return;
+  
+  xTaskCreate(pmTask, PM_TASK_NAME,
+              PM_TASK_STACKSIZE, NULL, PM_TASK_PRI, NULL);
+  
+  isInit = true;
+
+  pmSyslinkInfo.vBat = 3.7f;
+  pmSetBatteryVoltage(pmSyslinkInfo.vBat); //TODO remove
+}
+
+bool pmTest(void)
+{
+  return isInit;
+}
+
+/**
+ * Sets the battery voltage and its min and max values
+ */
+static void pmSetBatteryVoltage(float voltage)
+{
+  batteryVoltage = voltage;
+  batteryVoltageMV = (uint16_t)(voltage * 1000);
+  if (batteryVoltageMax < voltage)
+  {
+    batteryVoltageMax = voltage;
+  }
+  if (batteryVoltageMin > voltage)
+  {
+    batteryVoltageMin = voltage;
+  }
+}
+
+/**
+ * Shutdown system
+ */
+static void pmSystemShutdown(void)
+{
+#ifdef ACTIVATE_AUTO_SHUTDOWN
+//TODO: Implement syslink call to shutdown
+#endif
+}
+
+/**
+ * Returns a number from 0 to 9 where 0 is completely discharged
+ * and 9 is 90% charged.
+ */
+static int32_t pmBatteryChargeFromVoltage(float voltage)
+{
+  int charge = 0;
+
+  if (voltage < bat671723HS25C[0])
+  {
+    return 0;
+  }
+  if (voltage > bat671723HS25C[9])
+  {
+    return 9;
+  }
+  while (voltage >  bat671723HS25C[charge])
+  {
+    charge++;
+  }
+
+  return charge;
+}
+
+
+float pmGetBatteryVoltage(void)
+{
+  return batteryVoltage;
+}
+
+float pmGetBatteryVoltageMin(void)
+{
+  return batteryVoltageMin;
+}
+
+float pmGetBatteryVoltageMax(void)
+{
+  return batteryVoltageMax;
+}
+
+void pmSyslinkUpdate(SyslinkPacket *slp)
+{
+  memcpy(&pmSyslinkInfo, &slp->data[0], sizeof(pmSyslinkInfo));
+  pmSetBatteryVoltage(pmSyslinkInfo.vBat);
+}
+
+void pmSetChargeState(PMChargeStates chgState)
+{
+  // TODO: Send syslink packafe with charge state
+}
+
+PMStates pmUpdateState()
+{
+  PMStates state;
+  bool isCharging = pmSyslinkInfo.chg;
+  bool isPgood = pmSyslinkInfo.pgood;
+  uint32_t batteryLowTime;
+
+  batteryLowTime = xTaskGetTickCount() - batteryLowTimeStamp;
+
+  if (isPgood && !isCharging)
+  {
+    state = charged;
+  }
+  else if (isPgood && isCharging)
+  {
+    state = charging;
+  }
+  else if (!isPgood && !isCharging && (batteryLowTime > PM_BAT_LOW_TIMEOUT))
+  {
+    state = lowPower;
+  }
+  else
+  {
+    state = battery;
+  }
+
+  return state;
+}
+
+void pmEnableExtBatteryCurrMeasuring(uint8_t pin, float ampPerVolt)
+{
+  extBatCurrDeckPin = pin;
+  extBatCurrAmpPerVolt = ampPerVolt;
+}
+
+float pmMeasureExtBatteryCurrent(void)
+{
+  float current;
+
+  if (extBatCurrDeckPin)
+  {
+    current = analogReadVoltage(extBatCurrDeckPin) * extBatCurrAmpPerVolt;
+  }
+  else
+  {
+    current = 0.0;
+  }
+
+  return current;
+}
+
+void pmEnableExtBatteryVoltMeasuring(uint8_t pin, float multiplier)
+{
+  extBatVoltDeckPin = pin;
+  extBatVoltMultiplier = multiplier;
+}
+
+float pmMeasureExtBatteryVoltage(void)
+{
+  float voltage;
+
+  if (extBatVoltDeckPin)
+  {
+    voltage = analogReadVoltage(extBatVoltDeckPin) * extBatVoltMultiplier;
+  }
+  else
+  {
+    voltage = 0.0;
+  }
+
+  return voltage;
+}
+
+
+// return true if battery discharging
+bool pmIsDischarging(void) {
+    PMStates pmState;
+    pmState = pmUpdateState();
+    return (pmState == lowPower )|| (pmState == battery);
+}
+
+void pmTask(void *param)
+{
+  PMStates pmStateOld = battery;
+  uint32_t tickCount;
+
+  vTaskSetApplicationTaskTag(0, (void*)TASK_PM_ID_NBR);
+
+  tickCount = xTaskGetTickCount();
+  batteryLowTimeStamp = tickCount;
+  batteryCriticalLowTimeStamp = tickCount;
+
+  pmSetChargeState(charge500mA);
+  vTaskDelay(500);
+
+  while(1)
+  {
+    vTaskDelay(100);
+    tickCount = xTaskGetTickCount();
+
+    extBatteryVoltage = pmMeasureExtBatteryVoltage();
+    extBatteryVoltageMV = (uint16_t)(extBatteryVoltage * 1000);
+    extBatteryCurrent = pmMeasureExtBatteryCurrent();
+
+    if (pmGetBatteryVoltage() > PM_BAT_LOW_VOLTAGE)
+    {
+      batteryLowTimeStamp = tickCount;
+    }
+    if (pmGetBatteryVoltage() > PM_BAT_CRITICAL_LOW_VOLTAGE)
+    {
+      batteryCriticalLowTimeStamp = tickCount;
+    }
+
+    pmState = pmUpdateState();
+
+    if (pmState != pmStateOld)
+    {
+      // Actions on state change
+      switch (pmState)
+      {
+        case charged:
+          ledseqStop(CHG_LED, seq_charging);
+          ledseqRun(CHG_LED, seq_charged);
+          soundSetEffect(SND_BAT_FULL);
+          systemSetCanFly(false);
+          break;
+        case charging:
+          ledseqStop(LOWBAT_LED, seq_lowbat);
+          ledseqStop(CHG_LED, seq_charged);
+          ledseqRun(CHG_LED, seq_charging);
+          soundSetEffect(SND_USB_CONN);
+          systemSetCanFly(false);
+          break;
+        case lowPower:
+          ledseqRun(LOWBAT_LED, seq_lowbat);
+          soundSetEffect(SND_BAT_LOW);
+          systemSetCanFly(true);
+          break;
+        case battery:
+          ledseqStop(CHG_LED, seq_charging);
+          ledseqRun(CHG_LED, seq_charged);
+          soundSetEffect(SND_USB_DISC);
+          systemSetCanFly(true);
+          break;
+        default:
+          systemSetCanFly(true);
+          break;
+      }
+      pmStateOld = pmState;
+    }
+    // Actions during state
+    switch (pmState)
+    {
+      case charged:
+        break;
+      case charging:
+        {
+          uint32_t onTime;
+
+          onTime = pmBatteryChargeFromVoltage(pmGetBatteryVoltage()) *
+                   (LEDSEQ_CHARGE_CYCLE_TIME_500MA / 10);
+          ledseqSetTimes(seq_charging, onTime, LEDSEQ_CHARGE_CYCLE_TIME_500MA - onTime);
+        }
+        break;
+      case lowPower:
+        {
+          uint32_t batteryCriticalLowTime;
+
+          batteryCriticalLowTime = tickCount - batteryCriticalLowTimeStamp;
+          if (batteryCriticalLowTime > PM_BAT_CRITICAL_LOW_TIMEOUT)
+          {
+            pmSystemShutdown();
+          }
+        }
+        break;
+      case battery:
+        {
+          if ((commanderGetInactivityTime() > PM_SYSTEM_SHUTDOWN_TIMEOUT))
+          {
+            pmSystemShutdown();
+          }
+        }
+        break;
+      default:
+        break;
+    }
+  }
+}
+
+LOG_GROUP_START(pm)
+LOG_ADD(LOG_FLOAT, vbat, &batteryVoltage)
+LOG_ADD(LOG_UINT16, vbatMV, &batteryVoltageMV)
+LOG_ADD(LOG_FLOAT, extVbat, &extBatteryVoltage)
+LOG_ADD(LOG_UINT16, extVbatMV, &extBatteryVoltageMV)
+LOG_ADD(LOG_FLOAT, extCurr, &extBatteryCurrent)
+LOG_ADD(LOG_FLOAT, chargeCurrent, &pmSyslinkInfo.chargeCurrent)
+LOG_ADD(LOG_INT8, state, &pmState)
+LOG_GROUP_STOP(pm)
+
diff --git a/crazyflie-firmware-src/src/hal/src/proximity.c b/crazyflie-firmware-src/src/hal/src/proximity.c
new file mode 100644
index 0000000000000000000000000000000000000000..203c89fb78d6bd22da277f962a3d8d2b89667c7d
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/proximity.c
@@ -0,0 +1,223 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * proximity.c - Implementation of hardware abstraction layer for proximity sensors
+ */
+
+#include <string.h>
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "config.h"
+#include "deck.h"
+#include "proximity.h"
+#include "maxsonar.h"
+#include "system.h"
+#include "param.h"
+#include "log.h"
+
+#include "stm32fxxx.h"
+
+/* Flag indicating if the proximityInit() function has been called or not. */
+static bool isInit = false;
+
+/* Internal values exported by functions below. */
+static uint32_t proximityDistance       = 0; /* The distance measured in millimeters for the latest sample. */
+static uint32_t proximityDistanceAvg    = 0; /* Average distance in millimeters, initialized to zero. */
+static uint32_t proximityDistanceMedian = 0; /* Median distance in millimeters, initialized to zero. */
+static uint32_t proximityAccuracy       = 0; /* The accuracy as reported by the sensor driver for the latest sample. */
+
+/* The most recent samples in chronological order. Must be initialized before use. */
+static uint32_t proximitySWin[PROXIMITY_SWIN_SIZE];
+
+#if defined(PROXIMITY_ENABLED)
+
+#if defined(PROXIMITY_LOG_ENABLED)
+/* Define a log group. */
+LOG_GROUP_START(proximity)
+LOG_ADD(LOG_UINT32, distance, &proximityDistance)
+LOG_ADD(LOG_UINT32, distanceAvg, &proximityDistanceAvg)
+LOG_ADD(LOG_UINT32, distanceMed, &proximityDistanceMedian)
+LOG_ADD(LOG_UINT32, accuracy, &proximityAccuracy)
+LOG_GROUP_STOP(proximity)
+#endif
+
+/**
+ * This function returns the median value of an array.
+ *
+ * Internal sorting function by Bill Gentles Nov. 12 2010, seen
+ * on http://forum.arduino.cc/index.php?topic=20920.0
+ *
+ * @param proximitySWin Array of chronologically sequenced samples.
+ *
+ * @return Median value from the array.
+ */
+static uint32_t proximitySWinMedian(uint32_t *proximitySWin)
+{
+  /* The most recent samples, sorted in increasing sample value order. Must be initialized before use. */
+  uint32_t proximitySorted[PROXIMITY_SWIN_SIZE];
+
+  /* Create a copy of the chronologically sequenced buffer. */
+  memcpy(proximitySorted, proximitySWin, sizeof(uint32_t)*PROXIMITY_SWIN_SIZE);
+
+  /* Now sort this copy. */
+  uint8_t n;
+  for (n = 1; n < PROXIMITY_SWIN_SIZE; ++n) {
+    uint32_t valn = proximitySorted[n];
+    int8_t m; /* May reach value of -1 */
+    for (m = n - 1; (m >= 0) && (valn < proximitySorted[m]); m--)
+    {
+      proximitySorted[m + 1] = proximitySorted[m];
+    }
+    proximitySorted[m + 1] = valn;
+  }
+
+  /* Return the median value of the samples. */
+  return proximitySorted[PROXIMITY_SWIN_SIZE / 2];
+}
+
+/**
+ * This function adds a distance measurement to the sliding window, discarding the oldest sample.
+ * After having added the new sample, a new average value of the samples is calculated and returned.
+ *
+ * @param distance The new sample to add to the sliding window.
+ *
+ * @return The new average value of the samples in the sliding window (after adding the new sample).
+ */
+static uint32_t proximitySWinAdd(uint32_t distance)
+{
+  /* Discard oldest sample, move remaining samples one slot to the left. */
+  memmove(&proximitySWin[0], &proximitySWin[1], (PROXIMITY_SWIN_SIZE - 1) * sizeof(uint32_t));
+
+  /* Add the new sample in the last (right-most) slot. */
+  proximitySWin[PROXIMITY_SWIN_SIZE - 1] = distance;
+
+  /**
+   * Calculate the new average distance. Sum all the samples into a uint64_t,
+   * so that we only do a single division at the end.
+   */
+  uint64_t proximityNewAvg = 0;
+  uint8_t n;
+  for (n = 0; n < PROXIMITY_SWIN_SIZE; n++) {
+    proximityNewAvg += proximitySWin[n];
+  }
+  proximityNewAvg = proximityNewAvg / PROXIMITY_SWIN_SIZE;
+
+  return (uint32_t)proximityNewAvg;
+}
+
+/**
+ * Proximity task running at PROXIMITY_TASK_FREQ Hz.
+ *
+ * @param param Currently unused.
+ */
+static void proximityTask(void* param)
+{
+  uint32_t lastWakeTime;
+
+  vTaskSetApplicationTaskTag(0, (void*)TASK_PROXIMITY_ID_NBR);
+
+  //Wait for the system to be fully started to start stabilization loop
+  systemWaitStart();
+
+  lastWakeTime = xTaskGetTickCount();
+
+  while(1)
+  {
+    vTaskDelayUntil(&lastWakeTime, F2T(PROXIMITY_TASK_FREQ));
+
+#if defined(MAXSONAR_ENABLED)
+    /* Read the MaxBotix sensor. */
+    proximityDistance = maxSonarReadDistance(MAXSONAR_MB1040_AN, &proximityAccuracy);
+#endif
+
+    /* Get the latest average value calculated. */
+    proximityDistanceAvg = proximitySWinAdd(proximityDistance);
+
+    /* Get the latest median value calculated. */
+    proximityDistanceMedian = proximitySWinMedian(proximitySWin);
+  }
+}
+#endif
+
+/**
+ * Initialization of the proximity task.
+ */
+void proximityInit(void)
+{
+  if(isInit)
+    return;
+
+  /* Initialise the sliding window to zero. */
+  memset(&proximitySWin, 0, sizeof(uint32_t)*PROXIMITY_SWIN_SIZE);
+
+#if defined(PROXIMITY_ENABLED)
+  /* Only start the task if the proximity subsystem is enabled in conf.h */
+  xTaskCreate(proximityTask, PROXIMITY_TASK_NAME,
+              PROXIMITY_TASK_STACKSIZE, NULL, PROXIMITY_TASK_PRI, NULL);
+#endif
+
+  isInit = true;
+}
+
+/**
+ * Function returning the last proximity measurement.
+ *
+ * @return The last proximity measurement made.
+ */
+uint32_t proximityGetDistance(void)
+{
+  return proximityDistance;
+}
+
+/**
+ * Function returning the result of the last, average proximity calculation.
+ * The calculation is a simple average of the last PROXIMITY_SWIN_SIZE samples.
+ *
+ * @return The result from the last, average proximity calculation.
+ */
+uint32_t proximityGetDistanceAvg(void)
+{
+  return proximityDistanceAvg;
+}
+
+/**
+ * Function returning the result of the last, median proximity calculation.
+ * The calculation is the median of the last PROXIMITY_SWIN_SIZE samples.
+ *
+ * @return The result from the last, median proximity calculation.
+ */
+uint32_t proximityGetDistanceMedian(void)
+{
+  return proximityDistanceMedian;
+}
+
+/**
+ * Function returning the accuracy of the last proximity measurement.
+ *
+ * @return The accuracy of the last proximity measurement made.
+ */
+uint32_t proximityGetAccuracy(void)
+{
+  return proximityAccuracy;
+}
diff --git a/crazyflie-firmware-src/src/hal/src/radiolink.c b/crazyflie-firmware-src/src/hal/src/radiolink.c
new file mode 100644
index 0000000000000000000000000000000000000000..b0b09db88ce436c3f9a970967980bf859ed70d89
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/radiolink.c
@@ -0,0 +1,192 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * radiolink.c - Radio link layer
+ */
+
+#include <string.h>
+#include <stdint.h>
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+#include "queue.h"
+
+#include "config.h"
+#include "radiolink.h"
+#include "syslink.h"
+#include "crtp.h"
+#include "configblock.h"
+#include "log.h"
+#include "led.h"
+#include "ledseq.h"
+#include "queuemonitor.h"
+
+#define RADIOLINK_TX_QUEUE_SIZE (1)
+
+static xQueueHandle  txQueue;
+static xQueueHandle crtpPacketDelivery;
+
+static bool isInit;
+
+static int radiolinkSendCRTPPacket(CRTPPacket *p);
+static int radiolinkSetEnable(bool enable);
+static int radiolinkReceiveCRTPPacket(CRTPPacket *p);
+
+//Local RSSI variable used to enable logging of RSSI values from Radio
+static uint8_t rssi;
+
+static struct crtpLinkOperations radiolinkOp =
+{
+  .setEnable         = radiolinkSetEnable,
+  .sendPacket        = radiolinkSendCRTPPacket,
+  .receivePacket     = radiolinkReceiveCRTPPacket,
+};
+
+void radiolinkInit(void)
+{
+  if (isInit)
+    return;
+
+  txQueue = xQueueCreate(RADIOLINK_TX_QUEUE_SIZE, sizeof(SyslinkPacket));
+  DEBUG_QUEUE_MONITOR_REGISTER(txQueue);
+  crtpPacketDelivery = xQueueCreate(5, sizeof(CRTPPacket));
+  DEBUG_QUEUE_MONITOR_REGISTER(crtpPacketDelivery);
+
+
+  ASSERT(crtpPacketDelivery);
+
+  syslinkInit();
+
+  radiolinkSetChannel(configblockGetRadioChannel());
+  radiolinkSetDatarate(configblockGetRadioSpeed());
+  radiolinkSetAddress(configblockGetRadioAddress());
+
+  isInit = true;
+}
+
+bool radiolinkTest(void)
+{
+  return syslinkTest();
+}
+
+void radiolinkSetChannel(uint8_t channel)
+{
+  SyslinkPacket slp;
+
+  slp.type = SYSLINK_RADIO_CHANNEL;
+  slp.length = 1;
+  slp.data[0] = channel;
+  syslinkSendPacket(&slp);
+}
+
+void radiolinkSetDatarate(uint8_t datarate)
+{
+  SyslinkPacket slp;
+
+  slp.type = SYSLINK_RADIO_DATARATE;
+  slp.length = 1;
+  slp.data[0] = datarate;
+  syslinkSendPacket(&slp);
+}
+
+void radiolinkSetAddress(uint64_t address)
+{
+  SyslinkPacket slp;
+
+  slp.type = SYSLINK_RADIO_ADDRESS;
+  slp.length = 5;
+  memcpy(&slp.data[0], &address, 5);
+  syslinkSendPacket(&slp);
+}
+
+
+void radiolinkSyslinkDispatch(SyslinkPacket *slp)
+{
+  static SyslinkPacket txPacket;
+  if (slp->type == SYSLINK_RADIO_RAW)
+  {
+    slp->length--; // Decrease to get CRTP size.
+    xQueueSend(crtpPacketDelivery, &slp->length, 0);
+    ledseqRun(LINK_LED, seq_linkup);
+    // If a radio packet is received, one can be sent
+    if (xQueueReceive(txQueue, &txPacket, 0) == pdTRUE)
+    {
+      ledseqRun(LINK_DOWN_LED, seq_linkup);
+      syslinkSendPacket(&txPacket);
+    }
+  } else if (slp->type == SYSLINK_RADIO_RAW_BROADCAST)
+  {
+    slp->length--; // Decrease to get CRTP size.
+    xQueueSend(crtpPacketDelivery, &slp->length, 0);
+    ledseqRun(LINK_LED, seq_linkup);
+    // no ack for broadcasts
+  } else if (slp->type == SYSLINK_RADIO_RSSI)
+	{
+		//Extract RSSI sample sent from radio
+		memcpy(&rssi, slp->data, sizeof(uint8_t));
+	}
+}
+
+static int radiolinkReceiveCRTPPacket(CRTPPacket *p)
+{
+  if (xQueueReceive(crtpPacketDelivery, p, M2T(100)) == pdTRUE)
+  {
+    return 0;
+  }
+
+  return -1;
+}
+
+static int radiolinkSendCRTPPacket(CRTPPacket *p)
+{
+  static SyslinkPacket slp;
+
+  ASSERT(p->size <= CRTP_MAX_DATA_SIZE);
+
+  slp.type = SYSLINK_RADIO_RAW;
+  slp.length = p->size + 1;
+  memcpy(slp.data, &p->header, p->size + 1);
+
+  if (xQueueSend(txQueue, &slp, M2T(100)) == pdTRUE)
+  {
+    return true;
+  }
+
+  return false;
+}
+
+struct crtpLinkOperations * radiolinkGetLink()
+{
+  return &radiolinkOp;
+}
+
+static int radiolinkSetEnable(bool enable)
+{
+  return 0;
+}
+
+LOG_GROUP_START(radio)
+LOG_ADD(LOG_UINT8, rssi, &rssi)
+LOG_GROUP_STOP(radio)
diff --git a/crazyflie-firmware-src/src/hal/src/sensors_cf2.c b/crazyflie-firmware-src/src/hal/src/sensors_cf2.c
new file mode 100644
index 0000000000000000000000000000000000000000..46a777e9def0cd5ea58e62bd00b525e5481d42fc
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/sensors_cf2.c
@@ -0,0 +1,880 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sensors_task.h - Sensors interface using an interrupt-driven task to reduce CPU load
+ *
+ * 2016.06.15: Initial version by Mike Hamer, http://mikehamer.info
+ */
+
+#ifdef PLATFORM_CF1
+#error SENSORS = task is only compatible with the Crazyflie 2.0 // due to the IMU initialization
+#endif
+
+#include "sensors.h"
+
+#include <math.h>
+#include <stm32f4xx.h>
+
+#include "lps25h.h"
+#include "mpu6500.h"
+#include "ak8963.h"
+
+#include "FreeRTOS.h"
+#include "semphr.h"
+#include "task.h"
+
+#include "system.h"
+#include "configblock.h"
+#include "param.h"
+#include "debug.h"
+#include "imu.h"
+#include "nvicconf.h"
+#include "ledseq.h"
+#include "sound.h"
+#include "filter.h"
+
+/**
+ * Enable 250Hz digital LPF mode. However does not work with
+ * multiple slave reading through MPU9250 (MAG and BARO), only single for some reason.
+ */
+//#define SENSORS_MPU6500_DLPF_256HZ
+
+#define SENSORS_ENABLE_PRESSURE_LPS25H
+
+#define SENSORS_ENABLE_MAG_AK8963
+#define MAG_GAUSS_PER_LSB     666.7f
+
+#define SENSORS_GYRO_FS_CFG       MPU6500_GYRO_FS_2000
+#define SENSORS_DEG_PER_LSB_CFG   MPU6500_DEG_PER_LSB_2000
+
+#define SENSORS_ACCEL_FS_CFG      MPU6500_ACCEL_FS_16
+#define SENSORS_G_PER_LSB_CFG     MPU6500_G_PER_LSB_16
+
+#define SENSORS_VARIANCE_MAN_TEST_TIMEOUT M2T(2000) // Timeout in ms
+#define SENSORS_MAN_TEST_LEVEL_MAX        5.0f      // Max degrees off
+
+#define SENSORS_BIAS_SAMPLES       1000
+#define SENSORS_ACC_SCALE_SAMPLES  200
+#define SENSORS_GYRO_BIAS_CALCULATE_STDDEV
+
+// Buffer length for MPU9250 slave reads
+#define SENSORS_MPU6500_BUFF_LEN    14
+#define SENSORS_MAG_BUFF_LEN        8
+#define SENSORS_BARO_BUFF_S_P_LEN   4
+#define SENSORS_BARO_BUFF_T_LEN     2
+#define SENSORS_BARO_BUFF_LEN       (SENSORS_BARO_BUFF_S_P_LEN + SENSORS_BARO_BUFF_T_LEN)
+
+#define GYRO_NBR_OF_AXES            3
+#define GYRO_MIN_BIAS_TIMEOUT_MS    M2T(1*1000)
+// Number of samples used in variance calculation. Changing this effects the threshold
+#define SENSORS_NBR_OF_BIAS_SAMPLES     1024
+// Variance threshold to take zero bias for gyro
+#define GYRO_VARIANCE_BASE          5000
+#define GYRO_VARIANCE_THRESHOLD_X   (GYRO_VARIANCE_BASE)
+#define GYRO_VARIANCE_THRESHOLD_Y   (GYRO_VARIANCE_BASE)
+#define GYRO_VARIANCE_THRESHOLD_Z   (GYRO_VARIANCE_BASE)
+
+typedef struct
+{
+  Axis3f     bias;
+  bool       isBiasValueFound;
+  bool       isBufferFilled;
+  Axis3i16*  bufHead;
+  Axis3i16   buffer[SENSORS_NBR_OF_BIAS_SAMPLES];
+} BiasObj;
+
+static xQueueHandle accelerometerDataQueue;
+static xQueueHandle gyroDataQueue;
+static xQueueHandle magnetometerDataQueue;
+static xQueueHandle barometerDataQueue;
+static xSemaphoreHandle sensorsDataReady;
+
+static bool isInit = false;
+static sensorData_t sensors;
+
+static BiasObj gyroBiasRunning;
+static Axis3f  gyroBias;
+#if defined(SENSORS_GYRO_BIAS_CALCULATE_STDDEV) && defined (GYRO_BIAS_LIGHT_WEIGHT)
+static Axis3f  gyroBiasStdDev;
+#endif
+static bool    gyroBiasFound = false;
+static float accScaleSum = 0;
+static float accScale = 1;
+
+// Low Pass filtering
+#define GYRO_LPF_CUTOFF_FREQ  80
+#define ACCEL_LPF_CUTOFF_FREQ 30
+static lpf2pData accLpf[3];
+static lpf2pData gyroLpf[3];
+static void applyAxis3fLpf(lpf2pData *data, Axis3f* in);
+
+static bool isBarometerPresent = false;
+static bool isMagnetometerPresent = false;
+
+static bool isMpu6500TestPassed = false;
+static bool isAK8963TestPassed = false;
+static bool isLPS25HTestPassed = false;
+
+// Pre-calculated values for accelerometer alignment
+float cosPitch;
+float sinPitch;
+float cosRoll;
+float sinRoll;
+
+// This buffer needs to hold data from all sensors
+static uint8_t buffer[SENSORS_MPU6500_BUFF_LEN + SENSORS_MAG_BUFF_LEN + SENSORS_BARO_BUFF_LEN] = {0};
+
+static void processAccGyroMeasurements(const uint8_t *buffer);
+static void processMagnetometerMeasurements(const uint8_t *buffer);
+static void processBarometerMeasurements(const uint8_t *buffer);
+static void sensorsSetupSlaveRead(void);
+
+#ifdef GYRO_GYRO_BIAS_LIGHT_WEIGHT
+static bool processGyroBiasNoBuffer(int16_t gx, int16_t gy, int16_t gz, Axis3f *gyroBiasOut);
+#else
+static bool processGyroBias(int16_t gx, int16_t gy, int16_t gz,  Axis3f *gyroBiasOut);
+#endif
+static bool processAccScale(int16_t ax, int16_t ay, int16_t az);
+static void sensorsBiasObjInit(BiasObj* bias);
+static void sensorsCalculateVarianceAndMean(BiasObj* bias, Axis3f* varOut, Axis3f* meanOut);
+static void sensorsCalculateBiasMean(BiasObj* bias, Axis3i32* meanOut);
+static void sensorsAddBiasValue(BiasObj* bias, int16_t x, int16_t y, int16_t z);
+static bool sensorsFindBiasValue(BiasObj* bias);
+static void sensorsAccAlignToGravity(Axis3f* in, Axis3f* out);
+
+bool sensorsReadGyro(Axis3f *gyro)
+{
+  return (pdTRUE == xQueueReceive(gyroDataQueue, gyro, 0));
+}
+
+bool sensorsReadAcc(Axis3f *acc)
+{
+  return (pdTRUE == xQueueReceive(accelerometerDataQueue, acc, 0));
+}
+
+bool sensorsReadMag(Axis3f *mag)
+{
+  return (pdTRUE == xQueueReceive(magnetometerDataQueue, mag, 0));
+}
+
+bool sensorsReadBaro(baro_t *baro)
+{
+  return (pdTRUE == xQueueReceive(barometerDataQueue, baro, 0));
+}
+
+void sensorsAcquire(sensorData_t *sensors, const uint32_t tick)
+{
+  sensorsReadGyro(&sensors->gyro);
+  sensorsReadAcc(&sensors->acc);
+  sensorsReadMag(&sensors->mag);
+  sensorsReadBaro(&sensors->baro);
+}
+
+bool sensorsAreCalibrated() {
+  return gyroBiasFound;
+}
+
+static void sensorsTask(void *param)
+{
+  systemWaitStart();
+
+  sensorsSetupSlaveRead();
+
+  while (1)
+  {
+    if (pdTRUE == xSemaphoreTake(sensorsDataReady, portMAX_DELAY))
+    {
+      // data is ready to be read
+      uint8_t dataLen = (uint8_t) (SENSORS_MPU6500_BUFF_LEN +
+              (isMagnetometerPresent ? SENSORS_MAG_BUFF_LEN : 0) +
+              (isBarometerPresent ? SENSORS_BARO_BUFF_LEN : 0));
+
+      i2cdevRead(I2C3_DEV, MPU6500_ADDRESS_AD0_HIGH, MPU6500_RA_ACCEL_XOUT_H, dataLen, buffer);
+      // these functions process the respective data and queue it on the output queues
+      processAccGyroMeasurements(&(buffer[0]));
+      if (isMagnetometerPresent)
+      {
+          processMagnetometerMeasurements(&(buffer[SENSORS_MPU6500_BUFF_LEN]));
+      }
+      if (isBarometerPresent)
+      {
+          processBarometerMeasurements(&(buffer[isMagnetometerPresent ?
+                  SENSORS_MPU6500_BUFF_LEN + SENSORS_MAG_BUFF_LEN : SENSORS_MPU6500_BUFF_LEN]));
+      }
+
+      vTaskSuspendAll(); // ensure all queues are populated at the same time
+      xQueueOverwrite(accelerometerDataQueue, &sensors.acc);
+      xQueueOverwrite(gyroDataQueue, &sensors.gyro);
+      if (isMagnetometerPresent)
+      {
+        xQueueOverwrite(magnetometerDataQueue, &sensors.mag);
+      }
+      if (isBarometerPresent)
+      {
+        xQueueOverwrite(barometerDataQueue, &sensors.baro);
+      }
+      xTaskResumeAll();
+    }
+  }
+}
+
+void processBarometerMeasurements(const uint8_t *buffer)
+{
+  static uint32_t rawPressure = 0;
+  static int16_t rawTemp = 0;
+
+  // Check if there is a new pressure update
+  if (buffer[0] & 0x02) {
+    rawPressure = ((uint32_t) buffer[3] << 16) | ((uint32_t) buffer[2] << 8) | buffer[1];
+  }
+  // Check if there is a new temp update
+  if (buffer[0] & 0x01) {
+    rawTemp = ((int16_t) buffer[5] << 8) | buffer[4];
+  }
+
+  sensors.baro.pressure = (float) rawPressure / LPS25H_LSB_PER_MBAR;
+  sensors.baro.temperature = LPS25H_TEMP_OFFSET + ((float) rawTemp / LPS25H_LSB_PER_CELSIUS);
+  sensors.baro.asl = lps25hPressureToAltitude(&sensors.baro.pressure);
+}
+
+void processMagnetometerMeasurements(const uint8_t *buffer)
+{
+  if (buffer[0] & (1 << AK8963_ST1_DRDY_BIT)) {
+    int16_t headingx = (((int16_t) buffer[2]) << 8) | buffer[1];
+    int16_t headingy = (((int16_t) buffer[4]) << 8) | buffer[3];
+    int16_t headingz = (((int16_t) buffer[6]) << 8) | buffer[5];
+
+    sensors.mag.x = (float)headingx / MAG_GAUSS_PER_LSB;
+    sensors.mag.y = (float)headingy / MAG_GAUSS_PER_LSB;
+    sensors.mag.z = (float)headingz / MAG_GAUSS_PER_LSB;
+  }
+}
+
+void processAccGyroMeasurements(const uint8_t *buffer)
+{
+  Axis3f accScaled;
+  // Note the ordering to correct the rotated 90º IMU coordinate system
+  int16_t ay = (((int16_t) buffer[0]) << 8) | buffer[1];
+  int16_t ax = (((int16_t) buffer[2]) << 8) | buffer[3];
+  int16_t az = (((int16_t) buffer[4]) << 8) | buffer[5];
+  int16_t gy = (((int16_t) buffer[8]) << 8) | buffer[9];
+  int16_t gx = (((int16_t) buffer[10]) << 8) | buffer[11];
+  int16_t gz = (((int16_t) buffer[12]) << 8) | buffer[13];
+
+
+#ifdef GYRO_BIAS_LIGHT_WEIGHT
+  gyroBiasFound = processGyroBiasNoBuffer(gx, gy, gz, &gyroBias);
+#else
+  gyroBiasFound = processGyroBias(gx, gy, gz, &gyroBias);
+#endif
+  if (gyroBiasFound)
+  {
+     processAccScale(ax, ay, az);
+  }
+
+  sensors.gyro.x = -(gx - gyroBias.x) * SENSORS_DEG_PER_LSB_CFG;
+  sensors.gyro.y =  (gy - gyroBias.y) * SENSORS_DEG_PER_LSB_CFG;
+  sensors.gyro.z =  (gz - gyroBias.z) * SENSORS_DEG_PER_LSB_CFG;
+  applyAxis3fLpf((lpf2pData*)(&gyroLpf), &sensors.gyro);
+
+  accScaled.x = -(ax) * SENSORS_G_PER_LSB_CFG / accScale;
+  accScaled.y =  (ay) * SENSORS_G_PER_LSB_CFG / accScale;
+  accScaled.z =  (az) * SENSORS_G_PER_LSB_CFG / accScale;
+  sensorsAccAlignToGravity(&accScaled, &sensors.acc);
+  applyAxis3fLpf((lpf2pData*)(&accLpf), &sensors.acc);
+}
+
+static void sensorsDeviceInit(void)
+{
+  isMagnetometerPresent = false;
+  isBarometerPresent = false;
+
+  // Wait for sensors to startup
+  while (xTaskGetTickCount() < 1000);
+
+  i2cdevInit(I2C3_DEV);
+  mpu6500Init(I2C3_DEV);
+  if (mpu6500TestConnection() == true)
+  {
+    DEBUG_PRINT("MPU9250 I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("MPU9250 I2C connection [FAIL].\n");
+  }
+
+  mpu6500Reset();
+  vTaskDelay(M2T(50));
+  // Activate MPU6500
+  mpu6500SetSleepEnabled(false);
+  // Delay until registers are reset
+  vTaskDelay(M2T(100));
+  // Set x-axis gyro as clock source
+  mpu6500SetClockSource(MPU6500_CLOCK_PLL_XGYRO);
+  // Delay until clock is set and stable
+  vTaskDelay(M2T(200));
+  // Enable temp sensor
+  mpu6500SetTempSensorEnabled(true);
+  // Disable interrupts
+  mpu6500SetIntEnabled(false);
+  // Connect the MAG and BARO to the main I2C bus
+  mpu6500SetI2CBypassEnabled(true);
+  // Set gyro full scale range
+  mpu6500SetFullScaleGyroRange(SENSORS_GYRO_FS_CFG);
+  // Set accelerometer full scale range
+  mpu6500SetFullScaleAccelRange(SENSORS_ACCEL_FS_CFG);
+  // Set accelerometer digital low-pass bandwidth
+  mpu6500SetAccelDLPF(MPU6500_ACCEL_DLPF_BW_41);
+
+#if SENSORS_MPU6500_DLPF_256HZ
+  // 256Hz digital low-pass filter only works with little vibrations
+  // Set output rate (15): 8000 / (1 + 7) = 1000Hz
+  mpu6500SetRate(7);
+  // Set digital low-pass bandwidth
+  mpu6500SetDLPFMode(MPU6500_DLPF_BW_256);
+#else
+  // To low DLPF bandwidth might cause instability and decrease agility
+  // but it works well for handling vibrations and unbalanced propellers
+  // Set output rate (1): 1000 / (1 + 0) = 1000Hz
+  mpu6500SetRate(0);
+  // Set digital low-pass bandwidth for gyro
+  mpu6500SetDLPFMode(MPU6500_DLPF_BW_98);
+  // Init second order filer for accelerometer
+  for (uint8_t i = 0; i < 3; i++)
+  {
+    lpf2pInit(&gyroLpf[i], 1000, GYRO_LPF_CUTOFF_FREQ);
+    lpf2pInit(&accLpf[i],  1000, ACCEL_LPF_CUTOFF_FREQ);
+  }
+#endif
+
+
+#ifdef SENSORS_ENABLE_MAG_AK8963
+  ak8963Init(I2C3_DEV);
+  if (ak8963TestConnection() == true)
+  {
+    isMagnetometerPresent = true;
+    ak8963SetMode(AK8963_MODE_16BIT | AK8963_MODE_CONT2); // 16bit 100Hz
+    DEBUG_PRINT("AK8963 I2C connection [OK].\n");
+  }
+  else
+  {
+    DEBUG_PRINT("AK8963 I2C connection [FAIL].\n");
+  }
+#endif
+
+#ifdef SENSORS_ENABLE_PRESSURE_LPS25H
+  lps25hInit(I2C3_DEV);
+  if (lps25hTestConnection() == true)
+  {
+    lps25hSetEnabled(true);
+    isBarometerPresent = true;
+    DEBUG_PRINT("LPS25H I2C connection [OK].\n");
+  }
+  else
+  {
+    //TODO: Should sensor test fail hard if no connection
+    DEBUG_PRINT("LPS25H I2C connection [FAIL].\n");
+  }
+#endif
+
+  cosPitch = cosf(configblockGetCalibPitch() * (float) M_PI/180);
+  sinPitch = sinf(configblockGetCalibPitch() * (float) M_PI/180);
+  cosRoll = cosf(configblockGetCalibRoll() * (float) M_PI/180);
+  sinRoll = sinf(configblockGetCalibRoll() * (float) M_PI/180);
+}
+
+
+static void sensorsSetupSlaveRead(void)
+{
+  // Now begin to set up the slaves
+#ifdef SENSORS_MPU6500_DLPF_256HZ
+  // As noted in registersheet 4.4: "Data should be sampled at or above sample rate;
+  // SMPLRT_DIV is only used for 1kHz internal sampling." Slowest update rate is then 500Hz.
+  mpu6500SetSlave4MasterDelay(15); // read slaves at 500Hz = (8000Hz / (1 + 15))
+#else
+  mpu6500SetSlave4MasterDelay(9); // read slaves at 100Hz = (500Hz / (1 + 4))
+#endif
+
+  mpu6500SetI2CBypassEnabled(false);
+  mpu6500SetWaitForExternalSensorEnabled(true); // the slave data isn't so important for the state estimation
+  mpu6500SetInterruptMode(0); // active high
+  mpu6500SetInterruptDrive(0); // push pull
+  mpu6500SetInterruptLatch(0); // latched until clear
+  mpu6500SetInterruptLatchClear(1); // cleared on any register read
+  mpu6500SetSlaveReadWriteTransitionEnabled(false); // Send a stop at the end of a slave read
+  mpu6500SetMasterClockSpeed(13); // Set i2c speed to 400kHz
+
+#ifdef SENSORS_ENABLE_MAG_AK8963
+  if (isMagnetometerPresent)
+  {
+    // Set registers for MPU6500 master to read from
+    mpu6500SetSlaveAddress(0, 0x80 | AK8963_ADDRESS_00); // set the magnetometer to Slave 0, enable read
+    mpu6500SetSlaveRegister(0, AK8963_RA_ST1); // read the magnetometer heading register
+    mpu6500SetSlaveDataLength(0, SENSORS_MAG_BUFF_LEN); // read 8 bytes (ST1, x, y, z heading, ST2 (overflow check))
+    mpu6500SetSlaveDelayEnabled(0, true);
+    mpu6500SetSlaveEnabled(0, true);
+  }
+#endif
+
+#ifdef SENSORS_ENABLE_PRESSURE_LPS25H
+  if (isBarometerPresent)
+  {
+    // Configure the LPS25H as a slave and enable read
+    // Setting up two reads works for LPS25H fifo avg filter as well as the
+    // auto inc wraps back to LPS25H_PRESS_OUT_L after LPS25H_PRESS_OUT_H is read.
+    mpu6500SetSlaveAddress(1, 0x80 | LPS25H_I2C_ADDR);
+    mpu6500SetSlaveRegister(1, LPS25H_STATUS_REG | LPS25H_ADDR_AUTO_INC);
+    mpu6500SetSlaveDataLength(1, SENSORS_BARO_BUFF_S_P_LEN);
+    mpu6500SetSlaveDelayEnabled(1, true);
+    mpu6500SetSlaveEnabled(1, true);
+
+    mpu6500SetSlaveAddress(2, 0x80 | LPS25H_I2C_ADDR);
+    mpu6500SetSlaveRegister(2, LPS25H_TEMP_OUT_L | LPS25H_ADDR_AUTO_INC);
+    mpu6500SetSlaveDataLength(2, SENSORS_BARO_BUFF_T_LEN);
+    mpu6500SetSlaveDelayEnabled(2, true);
+    mpu6500SetSlaveEnabled(2, true);
+  }
+#endif
+
+  // Enable sensors after configuration
+  mpu6500SetI2CMasterModeEnabled(true);
+
+  mpu6500SetIntDataReadyEnabled(true);
+}
+
+static void sensorsTaskInit(void)
+{
+  accelerometerDataQueue = xQueueCreate(1, sizeof(Axis3f));
+  gyroDataQueue = xQueueCreate(1, sizeof(Axis3f));
+  magnetometerDataQueue = xQueueCreate(1, sizeof(Axis3f));
+  barometerDataQueue = xQueueCreate(1, sizeof(baro_t));
+
+  xTaskCreate(sensorsTask, SENSORS_TASK_NAME, SENSORS_TASK_STACKSIZE, NULL, SENSORS_TASK_PRI, NULL);
+}
+
+static void sensorsInterruptInit(void)
+{
+  GPIO_InitTypeDef GPIO_InitStructure;
+  EXTI_InitTypeDef EXTI_InitStructure;
+
+  // FSYNC "shall not be floating, must be set high or low by the MCU"
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_14;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_Init(GPIOC, &GPIO_InitStructure);
+  GPIO_ResetBits(GPIOC, GPIO_Pin_14);
+
+  // Enable the MPU6500 interrupt on PC13
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
+  GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+  SYSCFG_EXTILineConfig(EXTI_PortSourceGPIOC, EXTI_PinSource13);
+
+  EXTI_InitStructure.EXTI_Line = EXTI_Line13;
+  EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
+  EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
+  EXTI_InitStructure.EXTI_LineCmd = ENABLE;
+  portDISABLE_INTERRUPTS();
+  EXTI_Init(&EXTI_InitStructure);
+  EXTI_ClearITPendingBit(EXTI_Line13);
+  portENABLE_INTERRUPTS();
+}
+
+void sensorsInit(void)
+{
+  if (isInit)
+  {
+    return;
+  }
+
+  sensorsDataReady = xSemaphoreCreateBinary();
+
+  sensorsBiasObjInit(&gyroBiasRunning);
+  sensorsDeviceInit();
+  sensorsInterruptInit();
+  sensorsTaskInit();
+
+  isInit = true;
+}
+
+bool sensorsTest(void)
+{
+  bool testStatus = true;
+
+  if (!isInit)
+  {
+    DEBUG_PRINT("Error while initializing sensor task\r\n");
+    testStatus = false;
+  }
+
+  // Try for 3 seconds so the quad has stabilized enough to pass the test
+  for (int i = 0; i < 300; i++)
+  {
+    if(mpu6500SelfTest() == true)
+    {
+      isMpu6500TestPassed = true;
+      break;
+    }
+    else
+    {
+      vTaskDelay(M2T(10));
+    }
+  }
+  testStatus &= isMpu6500TestPassed;
+
+#ifdef SENSORS_ENABLE_MAG_AK8963
+  testStatus &= isMagnetometerPresent;
+  if (testStatus)
+  {
+    isAK8963TestPassed = ak8963SelfTest();
+    testStatus = isAK8963TestPassed;
+  }
+#endif
+
+#ifdef SENSORS_ENABLE_PRESSURE_LPS25H
+  testStatus &= isBarometerPresent;
+  if (testStatus)
+  {
+    isLPS25HTestPassed = lps25hSelfTest();
+    testStatus = isLPS25HTestPassed;
+  }
+#endif
+
+  return testStatus;
+}
+
+/**
+ * Calculates accelerometer scale out of SENSORS_ACC_SCALE_SAMPLES samples. Should be called when
+ * platform is stable.
+ */
+static bool processAccScale(int16_t ax, int16_t ay, int16_t az)
+{
+  static bool accBiasFound = false;
+  static uint32_t accScaleSumCount = 0;
+
+  if (!accBiasFound)
+  {
+    accScaleSum += sqrtf(powf(ax * SENSORS_G_PER_LSB_CFG, 2) + powf(ay * SENSORS_G_PER_LSB_CFG, 2) + powf(az * SENSORS_G_PER_LSB_CFG, 2));
+    accScaleSumCount++;
+
+    if (accScaleSumCount == SENSORS_ACC_SCALE_SAMPLES)
+    {
+      accScale = accScaleSum / SENSORS_ACC_SCALE_SAMPLES;
+      accBiasFound = true;
+    }
+  }
+
+  return accBiasFound;
+}
+
+#ifdef GYRO_BIAS_LIGHT_WEIGHT
+/**
+ * Calculates the bias out of the first SENSORS_BIAS_SAMPLES gathered. Requires no buffer
+ * but needs platform to be stable during startup.
+ */
+static bool processGyroBiasNoBuffer(int16_t gx, int16_t gy, int16_t gz, Axis3f *gyroBiasOut)
+{
+  static uint32_t gyroBiasSampleCount = 0;
+  static bool gyroBiasNoBuffFound = false;
+  static Axis3i64 gyroBiasSampleSum;
+  static Axis3i64 gyroBiasSampleSumSquares;
+
+  if (!gyroBiasNoBuffFound)
+  {
+    // If the gyro has not yet been calibrated:
+    // Add the current sample to the running mean and variance
+    gyroBiasSampleSum.x += gx;
+    gyroBiasSampleSum.y += gy;
+    gyroBiasSampleSum.z += gz;
+#ifdef SENSORS_GYRO_BIAS_CALCULATE_STDDEV
+    gyroBiasSampleSumSquares.x += gx * gx;
+    gyroBiasSampleSumSquares.y += gy * gy;
+    gyroBiasSampleSumSquares.z += gz * gz;
+#endif
+    gyroBiasSampleCount += 1;
+
+    // If we then have enough samples, calculate the mean and standard deviation
+    if (gyroBiasSampleCount == SENSORS_BIAS_SAMPLES)
+    {
+      gyroBiasOut->x = (float)(gyroBiasSampleSum.x) / SENSORS_BIAS_SAMPLES;
+      gyroBiasOut->y = (float)(gyroBiasSampleSum.y) / SENSORS_BIAS_SAMPLES;
+      gyroBiasOut->z = (float)(gyroBiasSampleSum.z) / SENSORS_BIAS_SAMPLES;
+
+#ifdef SENSORS_GYRO_BIAS_CALCULATE_STDDEV
+      gyroBiasStdDev.x = sqrtf((float)(gyroBiasSampleSumSquares.x) / SENSORS_BIAS_SAMPLES - (gyroBiasOut->x * gyroBiasOut->x));
+      gyroBiasStdDev.y = sqrtf((float)(gyroBiasSampleSumSquares.y) / SENSORS_BIAS_SAMPLES - (gyroBiasOut->y * gyroBiasOut->y));
+      gyroBiasStdDev.z = sqrtf((float)(gyroBiasSampleSumSquares.z) / SENSORS_BIAS_SAMPLES - (gyroBiasOut->z * gyroBiasOut->z));
+#endif
+      gyroBiasNoBuffFound = true;
+    }
+  }
+
+  return gyroBiasNoBuffFound;
+}
+#else
+/**
+ * Calculates the bias first when the gyro variance is below threshold. Requires a buffer
+ * but calibrates platform first when it is stable.
+ */
+static bool processGyroBias(int16_t gx, int16_t gy, int16_t gz, Axis3f *gyroBiasOut)
+{
+  sensorsAddBiasValue(&gyroBiasRunning, gx, gy, gz);
+
+  if (!gyroBiasRunning.isBiasValueFound)
+  {
+    sensorsFindBiasValue(&gyroBiasRunning);
+    if (gyroBiasRunning.isBiasValueFound)
+    {
+      soundSetEffect(SND_CALIB);
+      ledseqRun(SYS_LED, seq_calibrated);
+    }
+  }
+
+  gyroBiasOut->x = gyroBiasRunning.bias.x;
+  gyroBiasOut->y = gyroBiasRunning.bias.y;
+  gyroBiasOut->z = gyroBiasRunning.bias.z;
+
+  return gyroBiasRunning.isBiasValueFound;
+}
+#endif
+
+static void sensorsBiasObjInit(BiasObj* bias)
+{
+  bias->isBufferFilled = false;
+  bias->bufHead = bias->buffer;
+}
+
+/**
+ * Calculates the variance and mean for the bias buffer.
+ */
+static void sensorsCalculateVarianceAndMean(BiasObj* bias, Axis3f* varOut, Axis3f* meanOut)
+{
+  uint32_t i;
+  int64_t sum[GYRO_NBR_OF_AXES] = {0};
+  int64_t sumSq[GYRO_NBR_OF_AXES] = {0};
+
+  for (i = 0; i < SENSORS_NBR_OF_BIAS_SAMPLES; i++)
+  {
+    sum[0] += bias->buffer[i].x;
+    sum[1] += bias->buffer[i].y;
+    sum[2] += bias->buffer[i].z;
+    sumSq[0] += bias->buffer[i].x * bias->buffer[i].x;
+    sumSq[1] += bias->buffer[i].y * bias->buffer[i].y;
+    sumSq[2] += bias->buffer[i].z * bias->buffer[i].z;
+  }
+
+  varOut->x = (sumSq[0] - ((int64_t)sum[0] * sum[0]) / SENSORS_NBR_OF_BIAS_SAMPLES);
+  varOut->y = (sumSq[1] - ((int64_t)sum[1] * sum[1]) / SENSORS_NBR_OF_BIAS_SAMPLES);
+  varOut->z = (sumSq[2] - ((int64_t)sum[2] * sum[2]) / SENSORS_NBR_OF_BIAS_SAMPLES);
+
+  meanOut->x = (float)sum[0] / SENSORS_NBR_OF_BIAS_SAMPLES;
+  meanOut->y = (float)sum[1] / SENSORS_NBR_OF_BIAS_SAMPLES;
+  meanOut->z = (float)sum[2] / SENSORS_NBR_OF_BIAS_SAMPLES;
+}
+
+/**
+ * Calculates the mean for the bias buffer.
+ */
+static void __attribute__((used)) sensorsCalculateBiasMean(BiasObj* bias, Axis3i32* meanOut)
+{
+  uint32_t i;
+  int32_t sum[GYRO_NBR_OF_AXES] = {0};
+
+  for (i = 0; i < SENSORS_NBR_OF_BIAS_SAMPLES; i++)
+  {
+    sum[0] += bias->buffer[i].x;
+    sum[1] += bias->buffer[i].y;
+    sum[2] += bias->buffer[i].z;
+  }
+
+  meanOut->x = sum[0] / SENSORS_NBR_OF_BIAS_SAMPLES;
+  meanOut->y = sum[1] / SENSORS_NBR_OF_BIAS_SAMPLES;
+  meanOut->z = sum[2] / SENSORS_NBR_OF_BIAS_SAMPLES;
+}
+
+/**
+ * Adds a new value to the variance buffer and if it is full
+ * replaces the oldest one. Thus a circular buffer.
+ */
+static void sensorsAddBiasValue(BiasObj* bias, int16_t x, int16_t y, int16_t z)
+{
+  bias->bufHead->x = x;
+  bias->bufHead->y = y;
+  bias->bufHead->z = z;
+  bias->bufHead++;
+
+  if (bias->bufHead >= &bias->buffer[SENSORS_NBR_OF_BIAS_SAMPLES])
+  {
+    bias->bufHead = bias->buffer;
+    bias->isBufferFilled = true;
+  }
+}
+
+/**
+ * Checks if the variances is below the predefined thresholds.
+ * The bias value should have been added before calling this.
+ * @param bias  The bias object
+ */
+static bool sensorsFindBiasValue(BiasObj* bias)
+{
+  static int32_t varianceSampleTime;
+  bool foundBias = false;
+
+  if (bias->isBufferFilled)
+  {
+    Axis3f variance;
+    Axis3f mean;
+
+    sensorsCalculateVarianceAndMean(bias, &variance, &mean);
+
+    if (variance.x < GYRO_VARIANCE_THRESHOLD_X &&
+        variance.y < GYRO_VARIANCE_THRESHOLD_Y &&
+        variance.z < GYRO_VARIANCE_THRESHOLD_Z &&
+        (varianceSampleTime + GYRO_MIN_BIAS_TIMEOUT_MS < xTaskGetTickCount()))
+    {
+      varianceSampleTime = xTaskGetTickCount();
+      bias->bias.x = mean.x;
+      bias->bias.y = mean.y;
+      bias->bias.z = mean.z;
+      foundBias = true;
+      bias->isBiasValueFound = true;
+    }
+  }
+
+  return foundBias;
+}
+
+bool sensorsManufacturingTest(void)
+{
+  bool testStatus = false;
+  Axis3i16 g;
+  Axis3i16 a;
+  Axis3f acc;  // Accelerometer axis data in mG
+  float pitch, roll;
+  uint32_t startTick = xTaskGetTickCount();
+
+  testStatus = mpu6500SelfTest();
+
+  if (testStatus)
+  {
+    sensorsBiasObjInit(&gyroBiasRunning);
+    while (xTaskGetTickCount() - startTick < SENSORS_VARIANCE_MAN_TEST_TIMEOUT)
+    {
+      mpu6500GetMotion6(&a.y, &a.x, &a.z, &g.y, &g.x, &g.z);
+
+      if (processGyroBias(g.x, g.y, g.z, &gyroBias))
+      {
+        gyroBiasFound = true;
+        DEBUG_PRINT("Gyro variance test [OK]\n");
+        break;
+      }
+    }
+
+    if (gyroBiasFound)
+    {
+      acc.x = -(a.x) * SENSORS_G_PER_LSB_CFG;
+      acc.y =  (a.y) * SENSORS_G_PER_LSB_CFG;
+      acc.z =  (a.z) * SENSORS_G_PER_LSB_CFG;
+
+      // Calculate pitch and roll based on accelerometer. Board must be level
+      pitch = tanf(-acc.x/(sqrtf(acc.y*acc.y + acc.z*acc.z))) * 180/(float) M_PI;
+      roll = tanf(acc.y/acc.z) * 180/(float) M_PI;
+
+      if ((fabsf(roll) < SENSORS_MAN_TEST_LEVEL_MAX) && (fabsf(pitch) < SENSORS_MAN_TEST_LEVEL_MAX))
+      {
+        DEBUG_PRINT("Acc level test [OK]\n");
+        testStatus = true;
+      }
+      else
+      {
+        DEBUG_PRINT("Acc level test Roll:%0.2f, Pitch:%0.2f [FAIL]\n", roll, pitch);
+        testStatus = false;
+      }
+    }
+    else
+    {
+      DEBUG_PRINT("Gyro variance test [FAIL]\n");
+      testStatus = false;
+    }
+  }
+
+  return testStatus;
+}
+
+void __attribute__((used)) EXTI13_Callback(void)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+  xSemaphoreGiveFromISR(sensorsDataReady, &xHigherPriorityTaskWoken);
+
+  if (xHigherPriorityTaskWoken)
+  {
+    portYIELD();
+  }
+}
+
+/**
+ * Compensate for a miss-aligned accelerometer. It uses the trim
+ * data gathered from the UI and written in the config-block to
+ * rotate the accelerometer to be aligned with gravity.
+ */
+static void sensorsAccAlignToGravity(Axis3f* in, Axis3f* out)
+{
+  Axis3f rx;
+  Axis3f ry;
+
+  // Rotate around x-axis
+  rx.x = in->x;
+  rx.y = in->y * cosRoll - in->z * sinRoll;
+  rx.z = in->y * sinRoll + in->z * cosRoll;
+
+  // Rotate around y-axis
+  ry.x = rx.x * cosPitch - rx.z * sinPitch;
+  ry.y = rx.y;
+  ry.z = -rx.x * sinPitch + rx.z * cosPitch;
+
+  out->x = ry.x;
+  out->y = ry.y;
+  out->z = ry.z;
+}
+
+static void applyAxis3fLpf(lpf2pData *data, Axis3f* in)
+{
+  for (uint8_t i = 0; i < 3; i++) {
+    in->axis[i] = lpf2pApply(&data[i], in->axis[i]);
+  }
+}
+
+PARAM_GROUP_START(imu_sensors)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, HMC5883L, &isMagnetometerPresent)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MS5611, &isBarometerPresent) // TODO: Rename MS5611 to LPS25H. Client needs to be updated at the same time.
+PARAM_GROUP_STOP(imu_sensors)
+
+PARAM_GROUP_START(imu_tests)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MPU6500, &isMpu6500TestPassed)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, HMC5883L, &isAK8963TestPassed)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, MS5611, &isLPS25HTestPassed) // TODO: Rename MS5611 to LPS25H. Client needs to be updated at the same time.
+PARAM_GROUP_STOP(imu_tests)
diff --git a/crazyflie-firmware-src/src/hal/src/syslink.c b/crazyflie-firmware-src/src/hal/src/syslink.c
new file mode 100644
index 0000000000000000000000000000000000000000..ac9a209a632be6314a2e4e90cc0b3db4fea74e9e
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/syslink.c
@@ -0,0 +1,220 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * syslink.c: Communication between NRF51 and STM32
+ */
+#define DEBUG_MODULE "SL"
+
+#include <stdbool.h>
+#include <string.h>
+#include <stdint.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "semphr.h"
+
+#include "config.h"
+#include "debug.h"
+#include "syslink.h"
+#include "radiolink.h"
+#include "uart_syslink.h"
+#include "configblock.h"
+#include "pm.h"
+#include "ow.h"
+
+static bool isInit = false;
+static uint8_t sendBuffer[64];
+
+static void syslinkRouteIncommingPacket(SyslinkPacket *slp);
+
+static xSemaphoreHandle syslinkAccess;
+
+/* Syslink task, handles communication between nrf and stm and dispatch messages
+ */
+static void syslinkTask(void *param)
+{
+  SyslinkRxState rxState = waitForFirstStart;
+  SyslinkPacket slp;
+  uint8_t c;
+  uint8_t dataIndex = 0;
+  uint8_t cksum[2] = {0};
+  uint8_t counter = 0;
+
+  while(1)
+  {
+    if (uartslkGetDataWithTimout(&c))
+    {
+      counter++;
+      switch(rxState)
+      {
+        case waitForFirstStart:
+          rxState = (c == SYSLINK_START_BYTE1) ? waitForSecondStart : waitForFirstStart;
+          break;
+        case waitForSecondStart:
+          rxState = (c == SYSLINK_START_BYTE2) ? waitForType : waitForFirstStart;
+          break;
+        case waitForType:
+          cksum[0] = c;
+          cksum[1] = c;
+          slp.type = c;
+          rxState = waitForLengt;
+          break;
+        case waitForLengt:
+          if (c <= SYSLINK_MTU)
+          {
+            slp.length = c;
+            cksum[0] += c;
+            cksum[1] += cksum[0];
+            dataIndex = 0;
+            rxState = (c > 0) ? waitForData : waitForChksum1;
+          }
+          else
+          {
+            rxState = waitForFirstStart;
+          }
+          break;
+        case waitForData:
+          slp.data[dataIndex] = c;
+          cksum[0] += c;
+          cksum[1] += cksum[0];
+          dataIndex++;
+          if (dataIndex == slp.length)
+          {
+            rxState = waitForChksum1;
+          }
+          break;
+        case waitForChksum1:
+          if (cksum[0] == c)
+          {
+            rxState = waitForChksum2;
+          }
+          else
+          {
+            rxState = waitForFirstStart; //Checksum error
+            IF_DEBUG_ASSERT(1);
+          }
+          break;
+        case waitForChksum2:
+          if (cksum[1] == c)
+          {
+            syslinkRouteIncommingPacket(&slp);
+          }
+          else
+          {
+            rxState = waitForFirstStart; //Checksum error
+            IF_DEBUG_ASSERT(1);
+          }
+          rxState = waitForFirstStart;
+          break;
+        default:
+          ASSERT(0);
+          break;
+      }
+    }
+    else
+    {
+      // Timeout
+      rxState = waitForFirstStart;
+    }
+  }
+}
+
+static void syslinkRouteIncommingPacket(SyslinkPacket *slp)
+{
+  uint8_t groupType;
+
+  groupType = slp->type & SYSLINK_GROUP_MASK;
+
+  switch (groupType)
+  {
+    case SYSLINK_RADIO_GROUP:
+      radiolinkSyslinkDispatch(slp);
+      break;
+    case SYSLINK_PM_GROUP:
+      pmSyslinkUpdate(slp);
+      break;
+    case SYSLINK_OW_GROUP:
+      owSyslinkRecieve(slp);
+      break;
+    default:
+      DEBUG_PRINT("Unknown packet:%X.\n", slp->type);
+      break;
+  }
+}
+
+/*
+ * Public functions
+ */
+
+void syslinkInit()
+{
+  if(isInit)
+    return;
+
+  vSemaphoreCreateBinary(syslinkAccess);
+
+  if (xTaskCreate(syslinkTask, SYSLINK_TASK_NAME,
+                  SYSLINK_TASK_STACKSIZE, NULL, SYSLINK_TASK_PRI, NULL) == pdPASS)
+  {
+    isInit = true;
+  }
+}
+
+bool syslinkTest()
+{
+  return isInit;
+}
+
+int syslinkSendPacket(SyslinkPacket *slp)
+{
+  int i = 0;
+  int dataSize;
+  uint8_t cksum[2] = {0};
+
+  xSemaphoreTake(syslinkAccess, portMAX_DELAY);
+
+  ASSERT(slp->length <= SYSLINK_MTU);
+
+  sendBuffer[0] = SYSLINK_START_BYTE1;
+  sendBuffer[1] = SYSLINK_START_BYTE2;
+  sendBuffer[2] = slp->type;
+  sendBuffer[3] = slp->length;
+
+  memcpy(&sendBuffer[4], slp->data, slp->length);
+  dataSize = slp->length + 6;
+  // Calculate checksum delux
+  for (i = 2; i < dataSize - 2; i++)
+  {
+    cksum[0] += sendBuffer[i];
+    cksum[1] += cksum[0];
+  }
+  sendBuffer[dataSize-2] = cksum[0];
+  sendBuffer[dataSize-1] = cksum[1];
+
+  uartslkSendDataDmaBlocking(dataSize, sendBuffer);
+
+  xSemaphoreGive(syslinkAccess);
+
+  return 0;
+}
diff --git a/crazyflie-firmware-src/src/hal/src/uart.c b/crazyflie-firmware-src/src/hal/src/uart.c
new file mode 100644
index 0000000000000000000000000000000000000000..03f7789446b6c9538983493d3c9a8a59be4b1e93
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/uart.c
@@ -0,0 +1,374 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart.c - uart CRTP link and raw access functions
+ */
+#include <string.h>
+
+/*ST includes */
+#include "stm32f10x.h"
+#include "stm32f10x_dma.h"
+#include "stm32f10x_rcc.h"
+#include "stm32f10x_usart.h"
+#include "stm32f10x_gpio.h"
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+#include "queue.h"
+
+#include "uart.h"
+#include "crtp.h"
+#include "cfassert.h"
+#include "nvicconf.h"
+#include "config.h"
+
+#define UART_DATA_TIMEOUT_MS 1000
+#define UART_DATA_TIMEOUT_TICKS (UART_DATA_TIMEOUT_MS / portTICK_RATE_MS)
+#define CRTP_START_BYTE 0xAA
+#define CCR_ENABLE_SET  ((uint32_t)0x00000001)
+
+static bool isInit = false;
+
+xSemaphoreHandle waitUntilSendDone = NULL;
+static uint8_t outBuffer[64];
+static uint8_t dataIndex;
+static uint8_t dataSize;
+static uint8_t crcIndex = 0;
+static bool    isUartDmaInitialized;
+static enum { notSentSecondStart, sentSecondStart} txState;
+static xQueueHandle packetDelivery;
+static xQueueHandle uartDataDelivery;
+static DMA_InitTypeDef DMA_InitStructureShare;
+
+void uartRxTask(void *param);
+
+/**
+  * Configures the UART DMA. Mainly used for FreeRTOS trace
+  * data transfer.
+  */
+void uartDmaInit(void)
+{
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  // USART TX DMA Channel Config
+  DMA_InitStructureShare.DMA_PeripheralBaseAddr = (uint32_t)&UART_TYPE->DR;
+  DMA_InitStructureShare.DMA_MemoryBaseAddr = (uint32_t)outBuffer;
+  DMA_InitStructureShare.DMA_DIR = DMA_DIR_PeripheralDST;
+  DMA_InitStructureShare.DMA_BufferSize = 0;
+  DMA_InitStructureShare.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+  DMA_InitStructureShare.DMA_MemoryInc = DMA_MemoryInc_Enable;
+  DMA_InitStructureShare.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+  DMA_InitStructureShare.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+  DMA_InitStructureShare.DMA_Mode = DMA_Mode_Normal;
+  DMA_InitStructureShare.DMA_Priority = DMA_Priority_High;
+  DMA_InitStructureShare.DMA_M2M = DMA_M2M_Disable;
+
+  NVIC_InitStructure.NVIC_IRQChannel = UART_DMA_IRQ;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_LOW_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  isUartDmaInitialized = TRUE;
+}
+
+void uartInit(void)
+{
+
+  USART_InitTypeDef USART_InitStructure;
+  GPIO_InitTypeDef GPIO_InitStructure;
+  #if !defined(UART_OUTPUT_TRACE_DATA) && !defined(ADC_OUTPUT_RAW_DATA)
+  NVIC_InitTypeDef NVIC_InitStructure;
+  #endif
+
+  /* Enable GPIO and USART clock */
+  RCC_APB2PeriphClockCmd(UART_GPIO_PERIF, ENABLE);
+  RCC_APB1PeriphClockCmd(UART_PERIF, ENABLE);
+
+  /* Configure USART Rx as input floating */
+  GPIO_InitStructure.GPIO_Pin   = UART_GPIO_RX;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_IN_FLOATING;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+/* Configure USART Tx as alternate function push-pull */
+  GPIO_InitStructure.GPIO_Pin   = UART_GPIO_TX;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_Mode  = GPIO_Mode_AF_PP;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+#if defined(UART_OUTPUT_TRACE_DATA) || defined(ADC_OUTPUT_RAW_DATA) || defined(IMU_OUTPUT_RAW_DATA_ON_UART)
+  USART_InitStructure.USART_BaudRate            = 2000000;
+  USART_InitStructure.USART_Mode                = USART_Mode_Tx;
+#else
+  USART_InitStructure.USART_BaudRate            = 115200;
+  USART_InitStructure.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
+#endif
+  USART_InitStructure.USART_WordLength          = USART_WordLength_8b;
+  USART_InitStructure.USART_StopBits            = USART_StopBits_1;
+  USART_InitStructure.USART_Parity              = USART_Parity_No ;
+  USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+  USART_Init(UART_TYPE, &USART_InitStructure);
+
+#if defined(UART_OUTPUT_TRACE_DATA) || defined(ADC_OUTPUT_RAW_DATA)
+  uartDmaInit();
+#else
+  // Configure Tx buffer empty interrupt
+  NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_HIGH_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  USART_ITConfig(UART_TYPE, USART_IT_RXNE, ENABLE);
+
+  vSemaphoreCreateBinary(waitUntilSendDone);
+
+  xTaskCreate(uartRxTask, UART_RX_TASK_NAME,
+              UART_RX_TASK_STACKSIZE, NULL, UART_RX_TASK_PRI, NULL);
+
+  packetDelivery = xQueueCreate(2, sizeof(CRTPPacket));
+  uartDataDelivery = xQueueCreate(1024, sizeof(uint8_t));
+#endif
+  //Enable it
+  USART_Cmd(UART_TYPE, ENABLE);
+
+  isInit = true;
+}
+
+bool uartTest(void)
+{
+  return isInit;
+}
+
+void uartRxTask(void *param)
+{
+  enum {waitForFirstStart, waitForSecondStart,
+        waitForPort, waitForSize, waitForData, waitForCRC } rxState;
+
+  uint8_t c;
+  uint8_t dataIndex = 0;
+  uint8_t crc = 0;
+  CRTPPacket p;
+  rxState = waitForFirstStart;
+  uint8_t counter = 0;
+  while(1)
+  {
+    if (xQueueReceive(uartDataDelivery, &c, UART_DATA_TIMEOUT_TICKS) == pdTRUE)
+    {
+      counter++;
+     /* if (counter > 4)
+        ledSetRed(1);*/
+      switch(rxState)
+      {
+        case waitForFirstStart:
+          rxState = (c == CRTP_START_BYTE) ? waitForSecondStart : waitForFirstStart;
+          break;
+        case waitForSecondStart:
+          rxState = (c == CRTP_START_BYTE) ? waitForPort : waitForFirstStart;
+          break;
+        case waitForPort:
+          p.header = c;
+          crc = c;
+          rxState = waitForSize;
+          break;
+        case waitForSize:
+          if (c < CRTP_MAX_DATA_SIZE)
+          {
+            p.size = c;
+            crc = (crc + c) % 0xFF;
+            dataIndex = 0;
+            rxState = (c > 0) ? waitForData : waitForCRC;
+          }
+          else
+          {
+            rxState = waitForFirstStart;
+          }
+          break;
+        case waitForData:
+          p.data[dataIndex] = c;
+          crc = (crc + c) % 0xFF;
+          dataIndex++;
+          if (dataIndex == p.size)
+          {
+            rxState = waitForCRC;
+          }
+          break;
+        case waitForCRC:
+          if (crc == c)
+          {
+            xQueueSend(packetDelivery, &p, 0);
+          }
+          rxState = waitForFirstStart;
+          break;
+        default:
+          ASSERT(0);
+          break;
+      }
+    }
+    else
+    {
+      // Timeout
+      rxState = waitForFirstStart;
+    }
+  }
+}
+
+static int uartReceiveCRTPPacket(CRTPPacket *p)
+{
+  if (xQueueReceive(packetDelivery, p, portMAX_DELAY) == pdTRUE)
+  {
+    return 0;
+  }
+
+  return -1;
+}
+
+static portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+static uint8_t rxDataInterrupt;
+
+void uartIsr(void)
+{
+  if (USART_GetITStatus(UART_TYPE, USART_IT_TXE))
+  {
+    if (dataIndex < dataSize)
+    {
+      USART_SendData(UART_TYPE, outBuffer[dataIndex] & 0xFF);
+      dataIndex++;
+      if (dataIndex < dataSize - 1 && dataIndex > 1)
+      {
+        outBuffer[crcIndex] = (outBuffer[crcIndex] + outBuffer[dataIndex]) % 0xFF;
+      }
+    }
+    else
+    {
+      USART_ITConfig(UART_TYPE, USART_IT_TXE, DISABLE);
+      xHigherPriorityTaskWoken = pdFALSE;
+      xSemaphoreGiveFromISR(waitUntilSendDone, &xHigherPriorityTaskWoken);
+    }
+    USART_ClearITPendingBit(UART_TYPE, USART_IT_TXE);
+  }
+
+  if (USART_GetITStatus(UART_TYPE, USART_IT_RXNE))
+  {
+    rxDataInterrupt = USART_ReceiveData(UART_TYPE) & 0xFF;
+    xQueueSendFromISR(uartDataDelivery, &rxDataInterrupt, &xHigherPriorityTaskWoken);
+
+    if (xHigherPriorityTaskWoken)
+    {
+      portYIELD();
+    }
+  }
+}
+
+static int uartSendCRTPPacket(CRTPPacket *p)
+{
+  outBuffer[0] = CRTP_START_BYTE;
+  outBuffer[1] = CRTP_START_BYTE;
+  outBuffer[2] = p->header;
+  outBuffer[3] = p->size;
+  memcpy(&outBuffer[4], p->data, p->size);
+  dataIndex = 1;
+  txState = notSentSecondStart;
+  dataSize = p->size + 5;
+  crcIndex = dataSize - 1;
+  outBuffer[crcIndex] = 0;
+
+  USART_SendData(UART_TYPE, outBuffer[0] & 0xFF);
+  USART_ITConfig(UART_TYPE, USART_IT_TXE, ENABLE);
+  xSemaphoreTake(waitUntilSendDone, portMAX_DELAY);
+
+  return 0;
+}
+
+static int uartSetEnable(bool enable)
+{
+  return 0;
+}
+
+static struct crtpLinkOperations uartOp =
+{
+  .setEnable         = uartSetEnable,
+  .sendPacket        = uartSendCRTPPacket,
+  .receivePacket     = uartReceiveCRTPPacket,
+};
+
+struct crtpLinkOperations * uartGetLink()
+{
+  return &uartOp;
+}
+
+void uartDmaIsr(void)
+{
+  DMA_ITConfig(UART_DMA_CH, DMA_IT_TC, DISABLE);
+  DMA_ClearITPendingBit(UART_DMA_IT_TC);
+  USART_DMACmd(UART_TYPE, USART_DMAReq_Tx, DISABLE);
+  DMA_Cmd(UART_DMA_CH, DISABLE);
+
+}
+
+void uartSendData(uint32_t size, uint8_t* data)
+{
+  uint32_t i;
+
+  for(i = 0; i < size; i++)
+  {
+    while (!(UART_TYPE->SR & USART_FLAG_TXE));
+    UART_TYPE->DR = (data[i] & 0xFF);
+  }
+}
+
+int uartPutchar(int ch)
+{
+    uartSendData(1, (uint8_t *)&ch);
+
+    return (unsigned char)ch;
+}
+
+void uartSendDataDma(uint32_t size, uint8_t* data)
+{
+  if (isUartDmaInitialized)
+  {
+    memcpy(outBuffer, data, size);
+    DMA_InitStructureShare.DMA_BufferSize = size;
+    // Wait for DMA to be free
+    while(UART_DMA_CH->CCR & CCR_ENABLE_SET);
+    DMA_Init(UART_DMA_CH, &DMA_InitStructureShare);
+    // Enable the Transfer Complete interrupt
+    DMA_ITConfig(UART_DMA_CH, DMA_IT_TC, ENABLE);
+    USART_DMACmd(UART_TYPE, USART_DMAReq_Tx, ENABLE);
+    DMA_Cmd(UART_DMA_CH, ENABLE);
+  }
+}
+
+void __attribute__((used)) USART3_IRQHandler(void)
+{
+  uartIsr();
+}
+
+void __attribute__((used)) DMA1_Channel2_IRQHandler(void)
+{
+#if defined(UART_OUTPUT_TRACE_DATA) || defined(ADC_OUTPUT_RAW_DATA)
+  uartDmaIsr();
+#endif
+}
diff --git a/crazyflie-firmware-src/src/hal/src/usb.c b/crazyflie-firmware-src/src/hal/src/usb.c
new file mode 100644
index 0000000000000000000000000000000000000000..e22a4a70c50b59e31e160e9cfd269b6db1b779fc
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/usb.c
@@ -0,0 +1,382 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * uart.c - uart CRTP link and raw access functions
+ */
+#include <string.h>
+
+/*ST includes */
+#include "stm32fxxx.h"
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+#include "queue.h"
+#include "queuemonitor.h"
+
+#include "config.h"
+#include "usblink.h"
+#include "radiolink.h"
+#include "usb.h"
+
+#include "usbd_usr.h"
+#include "usb_conf.h"
+#include "usbd_desc.h"
+#include "usb_dcd.h"
+
+#include "crtp.h"
+
+
+__ALIGN_BEGIN USB_OTG_CORE_HANDLE    USB_OTG_dev __ALIGN_END ;
+
+static bool isInit = false;
+
+static xQueueHandle usbDataRx;
+static xQueueHandle usbDataTx;
+
+/* Endpoints */
+#define IN_EP                       0x81  /* EP1 for data IN */
+#define OUT_EP                      0x01  /* EP1 for data OUT */
+
+#define DEVICE_DESCRIPTOR           0x01
+#define CONFIGURATION_DESCRIPTOR    0x02
+#define STRING_DESCRIPTOR           0x03
+#define INTERFACE_DESCRIPTOR        0x04
+#define ENDPOINT_DESCRIPTOR         0x05
+
+__ALIGN_BEGIN uint8_t  usbd_cf_CfgDesc[57] __ALIGN_END = {
+  /***** Configuration descriptor ******/
+  9,                         //bLength
+  CONFIGURATION_DESCRIPTOR,  //bDescriptorType
+  32,0x00,                   //wTotalLength
+  1,                         //bNumInterfaces
+  1,                         //bConfigurationValue
+  0,                         //iConfiguration
+  0x80,                      //bmAttribute (Bus powered, no remote wakeup)
+  50,                        //bMaxPower (100mA, shall be enough)
+  /***** Interface 0 descriptor: Crazyradio EPs ******/
+  9,                         //bLength
+  INTERFACE_DESCRIPTOR,      //bDescriptorType
+  0,                         //bInterfaceNumber
+  0,                         //bAlternateSetting
+  2,                         //bNumEndpoint (one in, one out)
+  0xFF,                      //bInterfaceClass (VENDOR=0xFF)
+  0xFF,                      //bInterfaceSubClass (VENDOR=0xFF)
+  0,                         //bInterfaceProtocol (None)
+  0,                         //iInterface
+  /***** Endpoint 1 IN descriptor ******/
+  7,                         //bLength
+  ENDPOINT_DESCRIPTOR,       //bDescriptorType
+  0x81,                      //bEndpointAddess (EP1 IN)
+  0x02,                      //bmAttributes (Bulk endpoint)
+  0x40, 0x00,                //wMaxPacketSize (64 bytes)
+  6,                         //bInterval (irrelevant for bulk endpoint)
+  /***** Endpoint 1 OUT descriptor ******/
+  7,                         //bLength
+  ENDPOINT_DESCRIPTOR,       //bDescriptorType
+  0x01,                      //bEndpointAddess (EP1 OUT)
+  0x02,                      //bmAttributes (Bulk endpoint)
+  0x40, 0x00,                //wMaxPacketSize (64 bytes)
+  6,                         //bInterval (irrelevant for bulk endpoint)
+};
+
+static uint8_t  usbd_cf_Init        (void  *pdev, uint8_t cfgidx);
+static uint8_t  usbd_cf_DeInit      (void  *pdev, uint8_t cfgidx);
+static uint8_t  usbd_cf_DataIn      (void *pdev, uint8_t epnum);
+static uint8_t  usbd_cf_DataOut     (void *pdev, uint8_t epnum);
+static uint8_t  *usbd_cf_GetCfgDesc (uint8_t speed, uint16_t *length);
+static uint8_t  usbd_cf_SOF         (void *pdev);
+static uint8_t usbd_cf_Setup        (void *pdev , USB_SETUP_REQ  *req);
+
+static USBPacket inPacket;
+static USBPacket outPacket;
+
+/* CDC interface class callbacks structure */
+USBD_Class_cb_TypeDef cf_usb_cb =
+{
+  usbd_cf_Init,
+  usbd_cf_DeInit,
+  usbd_cf_Setup,
+  NULL,
+  NULL,
+  usbd_cf_DataIn,
+  usbd_cf_DataOut,
+  usbd_cf_SOF,
+  NULL,
+  NULL,
+  usbd_cf_GetCfgDesc,
+};
+
+USBD_Usr_cb_TypeDef USR_cb =
+{
+  USBD_USR_Init,
+  USBD_USR_DeviceReset,
+  USBD_USR_DeviceConfigured,
+  USBD_USR_DeviceSuspended,
+  USBD_USR_DeviceResumed,
+  USBD_USR_DeviceConnected,
+  USBD_USR_DeviceDisconnected,
+};
+
+int command = 0xFF;
+
+static uint8_t usbd_cf_Setup(void *pdev , USB_SETUP_REQ  *req)
+{
+  command = req->wIndex;
+  if (command == 0x01) {
+    crtpSetLink(usblinkGetLink());
+  } else {
+    crtpSetLink(radiolinkGetLink());
+  }
+
+  return USBD_OK;
+}
+
+static uint8_t  usbd_cf_Init (void  *pdev,
+                               uint8_t cfgidx)
+{
+  /* Open EP IN */
+  DCD_EP_Open(pdev,
+              IN_EP,
+              USB_RX_TX_PACKET_SIZE,
+              USB_OTG_EP_BULK);
+
+  /* Open EP OUT */
+  DCD_EP_Open(pdev,
+              OUT_EP,
+              USB_RX_TX_PACKET_SIZE,
+              USB_OTG_EP_BULK);
+
+  /* Prepare Out endpoint to receive next packet */
+  DCD_EP_PrepareRx(pdev,
+                   OUT_EP,
+                   (uint8_t*)(inPacket.data),
+                   USB_RX_TX_PACKET_SIZE);
+
+  return USBD_OK;
+}
+
+/**
+  * @brief  usbd_cdc_Init
+  *         DeInitialize the CDC layer
+  * @param  pdev: device instance
+  * @param  cfgidx: Configuration index
+  * @retval status
+  */
+static uint8_t  usbd_cf_DeInit (void  *pdev,
+                                 uint8_t cfgidx)
+{
+  /* Open EP IN */
+  DCD_EP_Close(pdev, IN_EP);
+
+  /* Open EP OUT */
+  DCD_EP_Close(pdev, OUT_EP);
+
+  return USBD_OK;
+}
+
+/**
+  * @brief  usbd_audio_DataIn
+  *         Data sent on non-control IN endpoint
+  * @param  pdev: device instance
+  * @param  epnum: endpoint number
+  * @retval status
+  */
+static uint8_t  usbd_cf_DataIn (void *pdev, uint8_t epnum)
+{
+  portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+
+  if (xQueueReceiveFromISR(usbDataTx, &outPacket, &xTaskWokenByReceive) == pdTRUE)
+  {
+    DCD_EP_Tx (pdev,
+               IN_EP,
+               (uint8_t*)outPacket.data,
+               outPacket.size);
+  }
+
+  return USBD_OK;
+}
+
+static uint8_t  usbd_cf_SOF (void *pdev)
+{
+  portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+
+  if (xQueueReceiveFromISR(usbDataTx, &outPacket, &xTaskWokenByReceive) == pdTRUE)
+  {
+    DCD_EP_Tx (pdev,
+               IN_EP,
+               (uint8_t*)outPacket.data,
+               outPacket.size);
+  }
+
+  return USBD_OK;
+}
+
+/**
+  * @brief  usbd_cf_DataOut
+  *         Data received on non-control Out endpoint
+  * @param  pdev: device instance
+  * @param  epnum: endpoint number
+  * @retval status
+  */
+static uint8_t  usbd_cf_DataOut (void *pdev, uint8_t epnum)
+{
+  portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+
+  /* Get the received data buffer and update the counter */
+  inPacket.size = ((USB_OTG_CORE_HANDLE*)pdev)->dev.out_ep[epnum].xfer_count;
+
+  xQueueSendFromISR(usbDataRx, &inPacket, &xHigherPriorityTaskWoken);
+
+  /* Prepare Out endpoint to receive next packet */
+  DCD_EP_PrepareRx(pdev,
+                   OUT_EP,
+                   (uint8_t*)(inPacket.data),
+                   USB_RX_TX_PACKET_SIZE);
+
+  return USBD_OK;
+}
+
+/**
+  * @brief  USBD_cdc_GetCfgDesc
+  *         Return configuration descriptor
+  * @param  speed : current device speed
+  * @param  length : pointer data length
+  * @retval pointer to descriptor buffer
+  */
+static uint8_t  *usbd_cf_GetCfgDesc (uint8_t speed, uint16_t *length)
+{
+  *length = sizeof (usbd_cf_CfgDesc);
+  return usbd_cf_CfgDesc;
+}
+
+/**
+* @brief  USBD_USR_Init
+*         Displays the message on LCD for host lib initialization
+* @param  None
+* @retval None
+*/
+void USBD_USR_Init(void)
+{
+}
+
+/**
+* @brief  USBD_USR_DeviceReset
+* @param  speed : device speed
+* @retval None
+*/
+void USBD_USR_DeviceReset(uint8_t speed)
+{
+}
+
+
+/**
+* @brief  USBD_USR_DeviceConfigured
+* @param  None
+* @retval Staus
+*/
+void USBD_USR_DeviceConfigured(void)
+{
+}
+
+/**
+* @brief  USBD_USR_DeviceSuspended
+* @param  None
+* @retval None
+*/
+void USBD_USR_DeviceSuspended(void)
+{
+  /* USB communication suspended (probably USB unplugged). Switch back to radiolink */
+  crtpSetLink(radiolinkGetLink());
+}
+
+
+/**
+* @brief  USBD_USR_DeviceResumed
+* @param  None
+* @retval None
+*/
+void USBD_USR_DeviceResumed(void)
+{
+}
+
+
+/**
+* @brief  USBD_USR_DeviceConnected
+* @param  None
+* @retval Staus
+*/
+void USBD_USR_DeviceConnected(void)
+{
+}
+
+
+/**
+* @brief  USBD_USR_DeviceDisonnected
+* @param  None
+* @retval Staus
+*/
+void USBD_USR_DeviceDisconnected(void)
+{
+  crtpSetLink(radiolinkGetLink());
+}
+
+void usbInit(void)
+{
+  USBD_Init(&USB_OTG_dev,
+            USB_OTG_FS_CORE_ID,
+            &USR_desc,
+            &cf_usb_cb,
+            &USR_cb);
+
+  // This should probably be reduced to a CRTP packet size
+  usbDataRx = xQueueCreate(5, sizeof(USBPacket)); /* Buffer USB packets (max 64 bytes) */
+  DEBUG_QUEUE_MONITOR_REGISTER(usbDataRx);
+  usbDataTx = xQueueCreate(1, sizeof(USBPacket)); /* Buffer USB packets (max 64 bytes) */
+  DEBUG_QUEUE_MONITOR_REGISTER(usbDataTx);
+
+  isInit = true;
+}
+
+bool usbTest(void)
+{
+  return isInit;
+}
+
+bool usbGetDataBlocking(USBPacket *in)
+{
+  while (xQueueReceive(usbDataRx, in, portMAX_DELAY) != pdTRUE)
+    ; // Don't return until we get some data on the USB
+  return true;
+}
+
+static USBPacket outStage;
+
+bool usbSendData(uint32_t size, uint8_t* data)
+{
+  outStage.size = size;
+  memcpy(outStage.data, data, size);
+  // Dont' block when sending
+  return (xQueueSend(usbDataTx, &outStage, M2T(100)) == pdTRUE);
+}
diff --git a/crazyflie-firmware-src/src/hal/src/usb_bsp.c b/crazyflie-firmware-src/src/hal/src/usb_bsp.c
new file mode 100644
index 0000000000000000000000000000000000000000..b574b8c2d6c60bf67d4ee0aad0766904c336af95
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/usb_bsp.c
@@ -0,0 +1,328 @@
+/**
+  ******************************************************************************
+  * @file    usb_bsp.c
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   This file is responsible to offer board support package and is
+  *          configurable by user.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software
+  * distributed under the License is distributed on an "AS IS" BASIS,
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_bsp.h"
+#include "usbd_conf.h"
+
+#include "stm32fxxx.h"
+
+#include "config.h"
+#include "nvicconf.h"
+
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+* @{
+*/
+
+/** @defgroup USB_BSP
+* @brief This file is responsible to offer board support package
+* @{
+*/
+
+/** @defgroup USB_BSP_Private_Defines
+* @{
+*/
+/**
+* @}
+*/
+
+
+/** @defgroup USB_BSP_Private_TypesDefinitions
+* @{
+*/
+/**
+* @}
+*/
+
+
+
+
+
+/** @defgroup USB_BSP_Private_Macros
+* @{
+*/
+/**
+* @}
+*/
+
+/** @defgroup USBH_BSP_Private_Variables
+* @{
+*/
+
+/**
+* @}
+*/
+
+/** @defgroup USBH_BSP_Private_FunctionPrototypes
+* @{
+*/
+/**
+* @}
+*/
+
+/** @defgroup USB_BSP_Private_Functions
+* @{
+*/
+
+
+/**
+* @brief  USB_OTG_BSP_Init
+*         Initilizes BSP configurations
+* @param  None
+* @retval None
+*/
+
+void USB_OTG_BSP_Init(USB_OTG_CORE_HANDLE *pdev)
+{
+#ifdef USE_STM3210C_EVAL
+
+  RCC_OTGFSCLKConfig(RCC_OTGFSCLKSource_PLLVCO_Div3);
+  RCC_AHBPeriphClockCmd(RCC_AHBPeriph_OTG_FS, ENABLE) ;
+
+#else // USE_STM322xG_EVAL
+  GPIO_InitTypeDef GPIO_InitStructure;
+ #ifdef USE_USB_OTG_FS
+  RCC_AHB1PeriphClockCmd( RCC_AHB1Periph_GPIOA , ENABLE);
+
+   /* Configure SOF ID DM DP Pins */
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8  |
+                                GPIO_Pin_11 |
+                                GPIO_Pin_12;
+
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
+  GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+  // AF10
+
+  GPIO_PinAFConfig(GPIOA,GPIO_PinSource8,GPIO_AF_OTG1_FS) ;
+  GPIO_PinAFConfig(GPIOA,GPIO_PinSource11,GPIO_AF_OTG1_FS) ;
+  GPIO_PinAFConfig(GPIOA,GPIO_PinSource12,GPIO_AF_OTG1_FS) ;
+
+  /* Configure  VBUS Pin */
+  /*GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
+  GPIO_Init(GPIOA, &GPIO_InitStructure);    */
+
+  /* Configure ID pin */
+  GPIO_InitStructure.GPIO_Pin =  GPIO_Pin_10;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP ;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_Init(GPIOA, &GPIO_InitStructure);
+  GPIO_PinAFConfig(GPIOA,GPIO_PinSource10,GPIO_AF_OTG1_FS) ;
+
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
+  RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, ENABLE) ;
+ #else // USE_USB_OTG_HS
+
+  #ifdef USE_ULPI_PHY // ULPI
+  RCC_AHB1PeriphClockCmd( RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB |
+                         RCC_AHB1Periph_GPIOC | RCC_AHB1Periph_GPIOH |
+                           RCC_AHB1Periph_GPIOI, ENABLE);
+
+
+  GPIO_PinAFConfig(GPIOA,GPIO_PinSource3, GPIO_AF_OTG2_HS) ; // D0
+  GPIO_PinAFConfig(GPIOA,GPIO_PinSource5, GPIO_AF_OTG2_HS) ; // CLK
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource0, GPIO_AF_OTG2_HS) ; // D1
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource1, GPIO_AF_OTG2_HS) ; // D2
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource5, GPIO_AF_OTG2_HS) ; // D7
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource10,GPIO_AF_OTG2_HS) ; // D3
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource11,GPIO_AF_OTG2_HS) ; // D4
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource12,GPIO_AF_OTG2_HS) ; // D5
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource13,GPIO_AF_OTG2_HS) ; // D6
+  GPIO_PinAFConfig(GPIOH,GPIO_PinSource4, GPIO_AF_OTG2_HS) ; // NXT
+  GPIO_PinAFConfig(GPIOI,GPIO_PinSource11,GPIO_AF_OTG2_HS) ; // DIR
+  GPIO_PinAFConfig(GPIOC,GPIO_PinSource0, GPIO_AF_OTG2_HS) ; // STP
+
+  // CLK
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5 ;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+  // D0
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3  ;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
+  GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+
+
+  // D1 D2 D3 D4 D5 D6 D7
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1  |
+    GPIO_Pin_5 | GPIO_Pin_10 |
+      GPIO_Pin_11| GPIO_Pin_12 |
+        GPIO_Pin_13 ;
+
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+
+  // STP
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0  ;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_Init(GPIOC, &GPIO_InitStructure);
+
+  //NXT
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_Init(GPIOH, &GPIO_InitStructure);
+
+
+  //DIR
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 ;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_Init(GPIOI, &GPIO_InitStructure);
+
+
+  RCC_AHB1PeriphClockCmd( RCC_AHB1Periph_OTG_HS |
+                         RCC_AHB1Periph_OTG_HS_ULPI, ENABLE) ;
+
+  #else
+
+  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB , ENABLE);
+
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12 |
+                                GPIO_Pin_14 |
+                                GPIO_Pin_15;
+
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource12, GPIO_AF_OTG2_FS) ;
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource14,GPIO_AF_OTG2_FS) ;
+  GPIO_PinAFConfig(GPIOB,GPIO_PinSource15,GPIO_AF_OTG2_FS) ;
+
+  GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+
+  RCC_AHB1PeriphClockCmd( RCC_AHB1Periph_OTG_HS, ENABLE) ;
+
+  #endif
+ #endif //USB_OTG_HS
+#endif //USE_STM322xG_EVAL
+}
+/**
+* @brief  USB_OTG_BSP_EnableInterrupt
+*         Enabele USB Global interrupt
+* @param  None
+* @retval None
+*/
+void USB_OTG_BSP_EnableInterrupt(USB_OTG_CORE_HANDLE *pdev)
+{
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4);
+#ifdef USE_USB_OTG_HS
+  NVIC_InitStructure.NVIC_IRQChannel = OTG_HS_IRQn;
+#else
+  NVIC_InitStructure.NVIC_IRQChannel = OTG_FS_IRQn;
+#endif
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_MID_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
+  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4);
+  NVIC_InitStructure.NVIC_IRQChannel = OTG_HS_EP1_OUT_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_MID_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4);
+  NVIC_InitStructure.NVIC_IRQChannel = OTG_HS_EP1_IN_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_MID_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+#endif
+}
+/**
+* @brief  USB_OTG_BSP_uDelay
+*         This function provides delay time in micro sec
+* @param  usec : Value of delay required in micro sec
+* @retval None
+*/
+void USB_OTG_BSP_uDelay (const uint32_t usec)
+{
+  uint32_t count = 0;
+  const uint32_t utime = (120 * usec / 7);
+  do
+  {
+    if ( ++count > utime )
+    {
+      return ;
+    }
+  }
+  while (1);
+}
+
+
+/**
+* @brief  USB_OTG_BSP_mDelay
+*          This function provides delay time in milli sec
+* @param  msec : Value of delay required in milli sec
+* @retval None
+*/
+void USB_OTG_BSP_mDelay (const uint32_t msec)
+{
+  USB_OTG_BSP_uDelay(msec * 1000);
+}
+/**
+* @}
+*/
+
+/**
+* @}
+*/
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/hal/src/usbd_desc.c b/crazyflie-firmware-src/src/hal/src/usbd_desc.c
new file mode 100644
index 0000000000000000000000000000000000000000..991aff3dbbd9c0ee9a1aa2b1d4105dc19c0b6ca6
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/usbd_desc.c
@@ -0,0 +1,333 @@
+/**
+  ******************************************************************************
+  * @file    usbd_desc.c
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   This file provides the USBD descriptors and string formating method.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+#include "usbd_desc.h"
+#include "usbd_req.h"
+#include "usbd_conf.h"
+#include "usb_regs.h"
+
+#include "config.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+
+
+/** @defgroup USBD_DESC 
+  * @brief USBD descriptors module
+  * @{
+  */ 
+
+/** @defgroup USBD_DESC_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_DESC_Private_Defines
+  * @{
+  */ 
+#define USBD_VID                        0x0483
+
+#define USBD_PID                        0x5740
+
+/** @defgroup USB_String_Descriptors
+  * @{
+  */ 
+#define USBD_LANGID_STRING              0x409
+#define USBD_MANUFACTURER_STRING        "Bitcraze AB"
+
+#define USBD_PRODUCT_HS_STRING          "STM32 Virtual ComPort in HS mode"
+#define USBD_SERIALNUMBER_HS_STRING     "00000000050B"
+
+#define USBD_PRODUCT_FS_STRING          "Crazyflie 2.0"
+#define USBD_SERIALNUMBER_FS_STRING     "00000000050C"
+
+#define USBD_CONFIGURATION_HS_STRING    "VCP Config"
+#define USBD_INTERFACE_HS_STRING        "VCP Interface"
+
+#define USBD_CONFIGURATION_FS_STRING    "VCP Config"
+#define USBD_INTERFACE_FS_STRING        "Raw CRTP interface"
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_DESC_Private_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_DESC_Private_Variables
+  * @{
+  */ 
+
+USBD_DEVICE USR_desc =
+{
+  USBD_USR_DeviceDescriptor,
+  USBD_USR_LangIDStrDescriptor, 
+  USBD_USR_ManufacturerStrDescriptor,
+  USBD_USR_ProductStrDescriptor,
+  USBD_USR_SerialStrDescriptor,
+  USBD_USR_ConfigStrDescriptor,
+  USBD_USR_InterfaceStrDescriptor,
+  
+};
+
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+    #pragma data_alignment=4   
+  #endif
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_SIZ_DEVICE_DESC] __ALIGN_END =
+  {
+    0x12,                       /*bLength */
+    USB_DEVICE_DESCRIPTOR_TYPE, /*bDescriptorType*/
+    0x00,                       /*bcdUSB */
+    0x02,
+    0x00,                       /*bDeviceClass*/
+    0x00,                       /*bDeviceSubClass*/
+    0x00,                       /*bDeviceProtocol*/
+    USB_OTG_MAX_EP0_SIZE,      /*bMaxPacketSize*/
+    LOBYTE(USBD_VID),           /*idVendor*/
+    HIBYTE(USBD_VID),           /*idVendor*/
+    LOBYTE(USBD_PID),           /*idVendor*/
+    HIBYTE(USBD_PID),           /*idVendor*/
+    0x00,                       /*bcdDevice rel. 2.00*/
+    0x02,
+    USBD_IDX_MFC_STR,           /*Index of manufacturer  string*/
+    USBD_IDX_PRODUCT_STR,       /*Index of product string*/
+    USBD_IDX_SERIAL_STR,        /*Index of serial number string*/
+    USBD_CFG_MAX_NUM            /*bNumConfigurations*/
+  } ; /* USB_DeviceDescriptor */
+
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+    #pragma data_alignment=4   
+  #endif
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
+{
+  USB_LEN_DEV_QUALIFIER_DESC,
+  USB_DESC_TYPE_DEVICE_QUALIFIER,
+  0x00,
+  0x02,
+  0x00,
+  0x00,
+  0x00,
+  0x40,
+  0x01,
+  0x00,
+};
+
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+    #pragma data_alignment=4   
+  #endif
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+/* USB Standard Device Descriptor */
+__ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END =
+{
+     USB_SIZ_STRING_LANGID,         
+     USB_DESC_TYPE_STRING,       
+     LOBYTE(USBD_LANGID_STRING),
+     HIBYTE(USBD_LANGID_STRING), 
+};
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_DESC_Private_FunctionPrototypes
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_DESC_Private_Functions
+  * @{
+  */ 
+
+/**
+* @brief  USBD_USR_DeviceDescriptor 
+*         return the device descriptor
+* @param  speed : current device speed
+* @param  length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t *  USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length)
+{
+  *length = sizeof(USBD_DeviceDesc);
+  return USBD_DeviceDesc;
+}
+
+/**
+* @brief  USBD_USR_LangIDStrDescriptor 
+*         return the LangID string descriptor
+* @param  speed : current device speed
+* @param  length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t *  USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length)
+{
+  *length =  sizeof(USBD_LangIDDesc);  
+  return USBD_LangIDDesc;
+}
+
+
+/**
+* @brief  USBD_USR_ProductStrDescriptor 
+*         return the product string descriptor
+* @param  speed : current device speed
+* @param  length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t *  USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length)
+{
+ 
+  
+  if(speed == 0)
+  {   
+    USBD_GetString ((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
+  }
+  else
+  {
+    USBD_GetString ((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length);
+  }
+  return USBD_StrDesc;
+}
+
+/**
+* @brief  USBD_USR_ManufacturerStrDescriptor 
+*         return the manufacturer string descriptor
+* @param  speed : current device speed
+* @param  length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t *  USBD_USR_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length)
+{
+  USBD_GetString ((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
+  return USBD_StrDesc;
+}
+
+static const char bin2hex[] = {'0', '1', '2', '3', '4', '5', '6', '7',
+                               '8', '9', 'A', 'B', 'C', 'D', 'E', 'F'};
+
+/**
+* @brief  USBD_USR_SerialStrDescriptor 
+*         return the serial number string descriptor
+* @param  speed : current device speed
+* @param  length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t *  USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length)
+{
+  char serial_nr[25];
+  char *chip_id = (char*)MCU_ID_ADDRESS;
+  int i;
+
+  serial_nr[24] = 0;
+
+  for (i=0; i<12; i++)
+  {
+    serial_nr[0+(i*2)] = bin2hex[(chip_id[i]>>4)&0x0F];
+    serial_nr[1+(i*2)] = bin2hex[chip_id[i]&0x0F];
+  }
+
+  USBD_GetString ((uint8_t *)serial_nr, USBD_StrDesc, length);
+
+  return USBD_StrDesc;
+}
+
+/**
+* @brief  USBD_USR_ConfigStrDescriptor 
+*         return the configuration string descriptor
+* @param  speed : current device speed
+* @param  length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t *  USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length)
+{
+  if(speed  == USB_OTG_SPEED_HIGH)
+  {  
+    USBD_GetString ((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length);
+  }
+  else
+  {
+    USBD_GetString ((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
+  }
+  return USBD_StrDesc;  
+}
+
+
+/**
+* @brief  USBD_USR_InterfaceStrDescriptor 
+*         return the interface string descriptor
+* @param  speed : current device speed
+* @param  length : pointer to data length variable
+* @retval pointer to descriptor buffer
+*/
+uint8_t *  USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length)
+{
+  if(speed == 0)
+  {
+    USBD_GetString ((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length);
+  }
+  else
+  {
+    USBD_GetString ((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
+  }
+  return USBD_StrDesc;  
+}
+
+/**
+  * @}
+  */ 
+
+
+/**
+  * @}
+  */ 
+
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/hal/src/usblink.c b/crazyflie-firmware-src/src/hal/src/usblink.c
new file mode 100644
index 0000000000000000000000000000000000000000..4ee0663a48eddb572771cf6ba173411becbd05f2
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/usblink.c
@@ -0,0 +1,147 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * syslink.c: nRF24L01 implementation of the CRTP link
+ */
+
+#include <stdbool.h>
+#include <string.h>
+
+#include "config.h"
+#include "usblink.h"
+#include "crtp.h"
+#include "configblock.h"
+#include "ledseq.h"
+#include "pm.h"
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "queuemonitor.h"
+#include "semphr.h"
+
+#include "usb.h"
+
+static bool isInit = false;
+static xQueueHandle crtpPacketDelivery;
+static uint8_t sendBuffer[64];
+
+static int usblinkSendPacket(CRTPPacket *p);
+static int usblinkSetEnable(bool enable);
+static int usblinkReceiveCRTPPacket(CRTPPacket *p);
+
+
+static struct crtpLinkOperations usblinkOp =
+{
+  .setEnable         = usblinkSetEnable,
+  .sendPacket        = usblinkSendPacket,
+  .receivePacket     = usblinkReceiveCRTPPacket,
+};
+
+/* Radio task handles the CRTP packet transfers as well as the radio link
+ * specific communications (eg. Scann and ID ports, communication error handling
+ * and so much other cool things that I don't have time for it ...)
+ */
+static USBPacket usbIn;
+static CRTPPacket p;
+static void usblinkTask(void *param)
+{
+  while(1)
+  {
+    // Fetch a USB packet off the queue
+    usbGetDataBlocking(&usbIn);
+    p.size = usbIn.size - 1;
+    memcpy(&p.raw, usbIn.data, usbIn.size);
+    // This queuing will copy a CRTP packet size from usbIn
+    xQueueSend(crtpPacketDelivery, &p, 0);
+  }
+
+}
+
+static int usblinkReceiveCRTPPacket(CRTPPacket *p)
+{
+  if (xQueueReceive(crtpPacketDelivery, p, M2T(100)) == pdTRUE)
+  {
+    ledseqRun(LINK_LED, seq_linkup);
+    return 0;
+  }
+
+  return -1;
+}
+
+static int usblinkSendPacket(CRTPPacket *p)
+{
+  int dataSize;
+
+  ASSERT(p->size < SYSLINK_MTU);
+
+  sendBuffer[0] = p->header;
+
+  if (p->size <= CRTP_MAX_DATA_SIZE)
+  {
+    memcpy(&sendBuffer[1], p->data, p->size);
+  }
+  dataSize = p->size + 1;
+
+
+  ledseqRun(LINK_DOWN_LED, seq_linkup);
+
+  return usbSendData(dataSize, sendBuffer);
+}
+
+static int usblinkSetEnable(bool enable)
+{
+  return 0;
+}
+
+/*
+ * Public functions
+ */
+
+void usblinkInit()
+{
+  if(isInit)
+    return;
+
+  // Initialize the USB peripheral
+  usbInit();
+
+  crtpPacketDelivery = xQueueCreate(5, sizeof(CRTPPacket));
+  DEBUG_QUEUE_MONITOR_REGISTER(crtpPacketDelivery);
+
+  xTaskCreate(usblinkTask, USBLINK_TASK_NAME,
+              USBLINK_TASK_STACKSIZE, NULL, USBLINK_TASK_PRI, NULL);
+
+  isInit = true;
+}
+
+bool usblinkTest()
+{
+  return isInit;
+}
+
+struct crtpLinkOperations * usblinkGetLink()
+{
+  return &usblinkOp;
+}
+
diff --git a/crazyflie-firmware-src/src/hal/src/usec_time.c b/crazyflie-firmware-src/src/hal/src/usec_time.c
new file mode 100644
index 0000000000000000000000000000000000000000..810097e49ae65cbf24f650de6deafd84c571c08d
--- /dev/null
+++ b/crazyflie-firmware-src/src/hal/src/usec_time.c
@@ -0,0 +1,88 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2013 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * usec_time.c - microsecond-resolution timer and timestamps.
+ */
+
+#include "usec_time.h"
+
+#include "nvicconf.h"
+#include "stm32fxxx.h"
+
+static uint32_t usecTimerHighCount;
+
+void initUsecTimer(void)
+{
+  usecTimerHighCount = 0;
+
+  TIM_TimeBaseInitTypeDef  TIM_TimeBaseStructure;
+  NVIC_InitTypeDef NVIC_InitStructure;
+
+  //Enable the Timer
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE);
+
+  //Timer configuration
+  TIM_TimeBaseStructure.TIM_Period = 0xFFFF;
+  // APB1 clock is /4, but APB clock inputs to timers are doubled when
+  // the APB clock runs slower than /1, so APB1 timers see a /2 clock
+  TIM_TimeBaseStructure.TIM_Prescaler = SystemCoreClock / (1000 * 1000) / 2;
+  TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
+  TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
+  TIM_TimeBaseInit(TIM7, &TIM_TimeBaseStructure);
+
+  NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_TRACE_TIM_PRI;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  DBGMCU_Config(DBGMCU_TIM7_STOP, ENABLE);
+  TIM_ITConfig(TIM7, TIM_IT_Update, ENABLE);
+  TIM_Cmd(TIM7, ENABLE);
+}
+
+uint64_t usecTimestamp(void)
+{
+  uint32_t high0;
+  __atomic_load(&usecTimerHighCount, &high0, __ATOMIC_SEQ_CST);
+  uint32_t low = TIM7->CNT;
+  uint32_t high;
+  __atomic_load(&usecTimerHighCount, &high, __ATOMIC_SEQ_CST);
+
+  // There was no increment in between
+  if (high == high0)
+  {
+    return (((uint64_t)high) << 16) + low;
+  }
+  // There was an increment, but we don't expect another one soon
+  return (((uint64_t)high) << 16) + TIM7->CNT;
+}
+
+void __attribute__((used)) TIM7_IRQHandler(void)
+{
+  TIM_ClearITPendingBit(TIM7, TIM_IT_Update);
+
+  __sync_fetch_and_add(&usecTimerHighCount, 1);
+}
diff --git a/crazyflie-firmware-src/src/init/main.c b/crazyflie-firmware-src/src/init/main.c
new file mode 100644
index 0000000000000000000000000000000000000000..9db72a2d2244e3ed3f8710fe5546aa8dc297ec85
--- /dev/null
+++ b/crazyflie-firmware-src/src/init/main.c
@@ -0,0 +1,66 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * main.c - Containing the main function.
+ */
+
+/* Personal configs */
+#include "FreeRTOSConfig.h"
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+
+/* Project includes */
+#include "config.h"
+#include "platform.h"
+#include "system.h"
+#include "usec_time.h"
+
+#include "led.h"
+
+/* ST includes */
+#include "stm32fxxx.h"
+
+int main() 
+{
+  //Initialize the platform.
+  platformInit();
+
+  //Launch the system task that will initialize and start everything
+  systemLaunch();
+
+  //Start the FreeRTOS scheduler
+  vTaskStartScheduler();
+
+  //TODO: Move to platform launch failed
+  ledInit();
+  ledSet(0, 1);
+  ledSet(1, 1);
+
+  //Should never reach this point!
+  while(1);
+
+  return 0;
+}
+
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_cl.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_cl.s
new file mode 100644
index 0000000000000000000000000000000000000000..28c8775856c045938f6d0fbc3fd56ef854f2e019
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_cl.s
@@ -0,0 +1,364 @@
+;******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_cl.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x Connectivity line devices vector table for RVMDK 
+;*                      toolchain. 
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == Reset_Handler
+;*                      - Set the vector table entries with the exceptions ISR address
+;*                      - Branches to __main in the C library (which eventually
+;*                        calls main()).
+;*                      After Reset the CortexM3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;* <<< Use Configuration Wizard in Context Menu >>>   
+;*******************************************************************************
+; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************
+
+; Amount of memory (in bytes) allocated for Stack
+; Tailor this value to your application needs
+; <h> Stack Configuration
+;   <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Stack_Size      EQU     0x00000400
+
+                AREA    STACK, NOINIT, READWRITE, ALIGN=3
+Stack_Mem       SPACE   Stack_Size
+__initial_sp
+
+
+; <h> Heap Configuration
+;   <o>  Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Heap_Size       EQU     0x00000200
+
+                AREA    HEAP, NOINIT, READWRITE, ALIGN=3
+__heap_base
+Heap_Mem        SPACE   Heap_Size
+__heap_limit
+
+                PRESERVE8
+                THUMB
+
+
+; Vector Table Mapped to Address 0 at Reset
+                AREA    RESET, DATA, READONLY
+                EXPORT  __Vectors
+                EXPORT  __Vectors_End
+                EXPORT  __Vectors_Size
+
+__Vectors       DCD     __initial_sp              ; Top of Stack
+                DCD     Reset_Handler             ; Reset Handler
+                DCD     NMI_Handler               ; NMI Handler
+                DCD     HardFault_Handler         ; Hard Fault Handler
+                DCD     MemManage_Handler         ; MPU Fault Handler
+                DCD     BusFault_Handler          ; Bus Fault Handler
+                DCD     UsageFault_Handler        ; Usage Fault Handler
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     SVC_Handler               ; SVCall Handler
+                DCD     DebugMon_Handler          ; Debug Monitor Handler
+                DCD     0                         ; Reserved
+                DCD     PendSV_Handler            ; PendSV Handler
+                DCD     SysTick_Handler           ; SysTick Handler
+
+                ; External Interrupts
+                DCD     WWDG_IRQHandler            ; Window Watchdog
+                DCD     PVD_IRQHandler             ; PVD through EXTI Line detect
+                DCD     TAMPER_IRQHandler          ; Tamper
+                DCD     RTC_IRQHandler             ; RTC
+                DCD     FLASH_IRQHandler           ; Flash
+                DCD     RCC_IRQHandler             ; RCC
+                DCD     EXTI0_IRQHandler           ; EXTI Line 0
+                DCD     EXTI1_IRQHandler           ; EXTI Line 1
+                DCD     EXTI2_IRQHandler           ; EXTI Line 2
+                DCD     EXTI3_IRQHandler           ; EXTI Line 3
+                DCD     EXTI4_IRQHandler           ; EXTI Line 4
+                DCD     DMA1_Channel1_IRQHandler   ; DMA1 Channel 1
+                DCD     DMA1_Channel2_IRQHandler   ; DMA1 Channel 2
+                DCD     DMA1_Channel3_IRQHandler   ; DMA1 Channel 3
+                DCD     DMA1_Channel4_IRQHandler   ; DMA1 Channel 4
+                DCD     DMA1_Channel5_IRQHandler   ; DMA1 Channel 5
+                DCD     DMA1_Channel6_IRQHandler   ; DMA1 Channel 6
+                DCD     DMA1_Channel7_IRQHandler   ; DMA1 Channel 7
+                DCD     ADC1_2_IRQHandler          ; ADC1 and ADC2
+                DCD     CAN1_TX_IRQHandler         ; CAN1 TX
+                DCD     CAN1_RX0_IRQHandler        ; CAN1 RX0
+                DCD     CAN1_RX1_IRQHandler        ; CAN1 RX1
+                DCD     CAN1_SCE_IRQHandler        ; CAN1 SCE
+                DCD     EXTI9_5_IRQHandler         ; EXTI Line 9..5
+                DCD     TIM1_BRK_IRQHandler        ; TIM1 Break
+                DCD     TIM1_UP_IRQHandler         ; TIM1 Update
+                DCD     TIM1_TRG_COM_IRQHandler    ; TIM1 Trigger and Commutation
+                DCD     TIM1_CC_IRQHandler         ; TIM1 Capture Compare
+                DCD     TIM2_IRQHandler            ; TIM2
+                DCD     TIM3_IRQHandler            ; TIM3
+                DCD     TIM4_IRQHandler            ; TIM4
+                DCD     I2C1_EV_IRQHandler         ; I2C1 Event
+                DCD     I2C1_ER_IRQHandler         ; I2C1 Error
+                DCD     I2C2_EV_IRQHandler         ; I2C2 Event
+                DCD     I2C2_ER_IRQHandler         ; I2C1 Error
+                DCD     SPI1_IRQHandler            ; SPI1
+                DCD     SPI2_IRQHandler            ; SPI2
+                DCD     USART1_IRQHandler          ; USART1
+                DCD     USART2_IRQHandler          ; USART2
+                DCD     USART3_IRQHandler          ; USART3
+                DCD     EXTI15_10_IRQHandler       ; EXTI Line 15..10
+                DCD     RTCAlarm_IRQHandler        ; RTC alarm through EXTI line
+                DCD     OTG_FS_WKUP_IRQHandler     ; USB OTG FS Wakeup through EXTI line
+                DCD     0                          ; Reserved
+                DCD     0                          ; Reserved
+                DCD     0                          ; Reserved
+                DCD     0                          ; Reserved
+                DCD     0                          ; Reserved
+                DCD     0                          ; Reserved
+                DCD     0                          ; Reserved
+                DCD     TIM5_IRQHandler            ; TIM5
+                DCD     SPI3_IRQHandler            ; SPI3
+                DCD     UART4_IRQHandler           ; UART4
+                DCD     UART5_IRQHandler           ; UART5
+                DCD     TIM6_IRQHandler            ; TIM6
+                DCD     TIM7_IRQHandler            ; TIM7
+                DCD     DMA2_Channel1_IRQHandler   ; DMA2 Channel1
+                DCD     DMA2_Channel2_IRQHandler   ; DMA2 Channel2
+                DCD     DMA2_Channel3_IRQHandler   ; DMA2 Channel3
+                DCD     DMA2_Channel4_IRQHandler   ; DMA2 Channel4
+                DCD     DMA2_Channel5_IRQHandler   ; DMA2 Channel5
+                DCD     ETH_IRQHandler             ; Ethernet
+                DCD     ETH_WKUP_IRQHandler        ; Ethernet Wakeup through EXTI line
+                DCD     CAN2_TX_IRQHandler         ; CAN2 TX
+                DCD     CAN2_RX0_IRQHandler        ; CAN2 RX0
+                DCD     CAN2_RX1_IRQHandler        ; CAN2 RX1
+                DCD     CAN2_SCE_IRQHandler        ; CAN2 SCE
+                DCD     OTG_FS_IRQHandler          ; USB OTG FS
+__Vectors_End
+
+__Vectors_Size  EQU  __Vectors_End - __Vectors
+
+                AREA    |.text|, CODE, READONLY
+
+; Reset handler routine
+Reset_Handler    PROC
+                 EXPORT  Reset_Handler             [WEAK]
+        IMPORT  __main
+                 LDR     R0, =__main
+                 BX      R0
+                 ENDP
+
+; Dummy Exception Handlers (infinite loops which can be modified)
+
+NMI_Handler     PROC
+                EXPORT  NMI_Handler                [WEAK]
+                B       .
+                ENDP
+HardFault_Handler\
+                PROC
+                EXPORT  HardFault_Handler          [WEAK]
+                B       .
+                ENDP
+MemManage_Handler\
+                PROC
+                EXPORT  MemManage_Handler          [WEAK]
+                B       .
+                ENDP
+BusFault_Handler\
+                PROC
+                EXPORT  BusFault_Handler           [WEAK]
+                B       .
+                ENDP
+UsageFault_Handler\
+                PROC
+                EXPORT  UsageFault_Handler         [WEAK]
+                B       .
+                ENDP
+SVC_Handler     PROC
+                EXPORT  SVC_Handler                [WEAK]
+                B       .
+                ENDP
+DebugMon_Handler\
+                PROC
+                EXPORT  DebugMon_Handler           [WEAK]
+                B       .
+                ENDP
+PendSV_Handler  PROC
+                EXPORT  PendSV_Handler             [WEAK]
+                B       .
+                ENDP
+SysTick_Handler PROC
+                EXPORT  SysTick_Handler            [WEAK]
+                B       .
+                ENDP
+
+Default_Handler PROC
+
+                EXPORT  WWDG_IRQHandler            [WEAK]
+                EXPORT  PVD_IRQHandler             [WEAK]
+                EXPORT  TAMPER_IRQHandler          [WEAK]
+                EXPORT  RTC_IRQHandler             [WEAK]
+                EXPORT  FLASH_IRQHandler           [WEAK]
+                EXPORT  RCC_IRQHandler             [WEAK]
+                EXPORT  EXTI0_IRQHandler           [WEAK]
+                EXPORT  EXTI1_IRQHandler           [WEAK]
+                EXPORT  EXTI2_IRQHandler           [WEAK]
+                EXPORT  EXTI3_IRQHandler           [WEAK]
+                EXPORT  EXTI4_IRQHandler           [WEAK]
+                EXPORT  DMA1_Channel1_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel2_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel3_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel4_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel5_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel6_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel7_IRQHandler   [WEAK]
+                EXPORT  ADC1_2_IRQHandler          [WEAK]
+                EXPORT  CAN1_TX_IRQHandler         [WEAK]
+                EXPORT  CAN1_RX0_IRQHandler        [WEAK]
+                EXPORT  CAN1_RX1_IRQHandler        [WEAK]
+                EXPORT  CAN1_SCE_IRQHandler        [WEAK]
+                EXPORT  EXTI9_5_IRQHandler         [WEAK]
+                EXPORT  TIM1_BRK_IRQHandler        [WEAK]
+                EXPORT  TIM1_UP_IRQHandler         [WEAK]
+                EXPORT  TIM1_TRG_COM_IRQHandler    [WEAK]
+                EXPORT  TIM1_CC_IRQHandler         [WEAK]
+                EXPORT  TIM2_IRQHandler            [WEAK]
+                EXPORT  TIM3_IRQHandler            [WEAK]
+                EXPORT  TIM4_IRQHandler            [WEAK]
+                EXPORT  I2C1_EV_IRQHandler         [WEAK]
+                EXPORT  I2C1_ER_IRQHandler         [WEAK]
+                EXPORT  I2C2_EV_IRQHandler         [WEAK]
+                EXPORT  I2C2_ER_IRQHandler         [WEAK]
+                EXPORT  SPI1_IRQHandler            [WEAK]
+                EXPORT  SPI2_IRQHandler            [WEAK]
+                EXPORT  USART1_IRQHandler          [WEAK]
+                EXPORT  USART2_IRQHandler          [WEAK]
+                EXPORT  USART3_IRQHandler          [WEAK]
+                EXPORT  EXTI15_10_IRQHandler       [WEAK]
+                EXPORT  RTCAlarm_IRQHandler        [WEAK]
+                EXPORT  OTG_FS_WKUP_IRQHandler     [WEAK]
+                EXPORT  TIM5_IRQHandler            [WEAK]
+                EXPORT  SPI3_IRQHandler            [WEAK]
+                EXPORT  UART4_IRQHandler           [WEAK]
+                EXPORT  UART5_IRQHandler           [WEAK]
+                EXPORT  TIM6_IRQHandler            [WEAK]
+                EXPORT  TIM7_IRQHandler            [WEAK]
+                EXPORT  DMA2_Channel1_IRQHandler   [WEAK]
+                EXPORT  DMA2_Channel2_IRQHandler   [WEAK]
+                EXPORT  DMA2_Channel3_IRQHandler   [WEAK]
+                EXPORT  DMA2_Channel4_IRQHandler   [WEAK]
+                EXPORT  DMA2_Channel5_IRQHandler   [WEAK]
+                EXPORT  ETH_IRQHandler             [WEAK]
+                EXPORT  ETH_WKUP_IRQHandler        [WEAK]
+                EXPORT  CAN2_TX_IRQHandler         [WEAK]
+                EXPORT  CAN2_RX0_IRQHandler        [WEAK]
+                EXPORT  CAN2_RX1_IRQHandler        [WEAK]
+                EXPORT  CAN2_SCE_IRQHandler        [WEAK]
+                EXPORT  OTG_FS_IRQHandler          [WEAK]
+
+WWDG_IRQHandler
+PVD_IRQHandler
+TAMPER_IRQHandler
+RTC_IRQHandler
+FLASH_IRQHandler
+RCC_IRQHandler
+EXTI0_IRQHandler
+EXTI1_IRQHandler
+EXTI2_IRQHandler
+EXTI3_IRQHandler
+EXTI4_IRQHandler
+DMA1_Channel1_IRQHandler
+DMA1_Channel2_IRQHandler
+DMA1_Channel3_IRQHandler
+DMA1_Channel4_IRQHandler
+DMA1_Channel5_IRQHandler
+DMA1_Channel6_IRQHandler
+DMA1_Channel7_IRQHandler
+ADC1_2_IRQHandler
+CAN1_TX_IRQHandler
+CAN1_RX0_IRQHandler
+CAN1_RX1_IRQHandler
+CAN1_SCE_IRQHandler
+EXTI9_5_IRQHandler
+TIM1_BRK_IRQHandler
+TIM1_UP_IRQHandler
+TIM1_TRG_COM_IRQHandler
+TIM1_CC_IRQHandler
+TIM2_IRQHandler
+TIM3_IRQHandler
+TIM4_IRQHandler
+I2C1_EV_IRQHandler
+I2C1_ER_IRQHandler
+I2C2_EV_IRQHandler
+I2C2_ER_IRQHandler
+SPI1_IRQHandler
+SPI2_IRQHandler
+USART1_IRQHandler
+USART2_IRQHandler
+USART3_IRQHandler
+EXTI15_10_IRQHandler
+RTCAlarm_IRQHandler
+OTG_FS_WKUP_IRQHandler
+TIM5_IRQHandler
+SPI3_IRQHandler
+UART4_IRQHandler
+UART5_IRQHandler
+TIM6_IRQHandler
+TIM7_IRQHandler
+DMA2_Channel1_IRQHandler
+DMA2_Channel2_IRQHandler
+DMA2_Channel3_IRQHandler
+DMA2_Channel4_IRQHandler
+DMA2_Channel5_IRQHandler
+ETH_IRQHandler
+ETH_WKUP_IRQHandler
+CAN2_TX_IRQHandler
+CAN2_RX0_IRQHandler
+CAN2_RX1_IRQHandler
+CAN2_SCE_IRQHandler
+OTG_FS_IRQHandler
+
+                B       .
+
+                ENDP
+
+                ALIGN
+
+;*******************************************************************************
+; User Stack and Heap initialization
+;*******************************************************************************
+                 IF      :DEF:__MICROLIB
+                
+                 EXPORT  __initial_sp
+                 EXPORT  __heap_base
+                 EXPORT  __heap_limit
+                
+                 ELSE
+                
+                 IMPORT  __use_two_region_memory
+                 EXPORT  __user_initial_stackheap
+                 
+__user_initial_stackheap
+
+                 LDR     R0, =  Heap_Mem
+                 LDR     R1, =(Stack_Mem + Stack_Size)
+                 LDR     R2, = (Heap_Mem +  Heap_Size)
+                 LDR     R3, = Stack_Mem
+                 BX      LR
+
+                 ALIGN
+
+                 ENDIF
+
+                 END
+
+;******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE*****
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_hd.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_hd.s
new file mode 100644
index 0000000000000000000000000000000000000000..e7f99e2b84ecfad7370cc56f5adc9170f909e91e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_hd.s
@@ -0,0 +1,370 @@
+;******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_hd.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x High Density Devices vector table for RVMDK 
+;*                      toolchain. 
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == Reset_Handler
+;*                      - Set the vector table entries with the exceptions ISR address
+;*                      - Configure external SRAM mounted on STM3210E-EVAL board
+;*                        to be used as data memory (optional, to be enabled by user)
+;*                      - Branches to __main in the C library (which eventually
+;*                        calls main()).
+;*                      After Reset the CortexM3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;* <<< Use Configuration Wizard in Context Menu >>>   
+;*******************************************************************************
+; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************
+
+; Amount of memory (in bytes) allocated for Stack
+; Tailor this value to your application needs
+; <h> Stack Configuration
+;   <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Stack_Size      EQU     0x00000400
+
+                AREA    STACK, NOINIT, READWRITE, ALIGN=3
+Stack_Mem       SPACE   Stack_Size
+__initial_sp
+
+__initial_spTop EQU    0x20000400                 ; stack used for SystemInit_ExtMemCtl
+                                                  ; always internal RAM used 
+                                                  
+; <h> Heap Configuration
+;   <o>  Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Heap_Size       EQU     0x00000200
+
+                AREA    HEAP, NOINIT, READWRITE, ALIGN=3
+__heap_base
+Heap_Mem        SPACE   Heap_Size
+__heap_limit
+
+                PRESERVE8
+                THUMB
+
+
+; Vector Table Mapped to Address 0 at Reset
+                AREA    RESET, DATA, READONLY
+                EXPORT  __Vectors
+                EXPORT  __Vectors_End
+                EXPORT  __Vectors_Size
+
+__Vectors       DCD     __initial_spTop           ; Top of Stack
+                DCD     Reset_Handler             ; Reset Handler
+                DCD     NMI_Handler               ; NMI Handler
+                DCD     HardFault_Handler         ; Hard Fault Handler
+                DCD     MemManage_Handler         ; MPU Fault Handler
+                DCD     BusFault_Handler          ; Bus Fault Handler
+                DCD     UsageFault_Handler        ; Usage Fault Handler
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     SVC_Handler               ; SVCall Handler
+                DCD     DebugMon_Handler          ; Debug Monitor Handler
+                DCD     0                         ; Reserved
+                DCD     PendSV_Handler            ; PendSV Handler
+                DCD     SysTick_Handler           ; SysTick Handler
+
+                ; External Interrupts
+                DCD     WWDG_IRQHandler           ; Window Watchdog
+                DCD     PVD_IRQHandler            ; PVD through EXTI Line detect
+                DCD     TAMPER_IRQHandler         ; Tamper
+                DCD     RTC_IRQHandler            ; RTC
+                DCD     FLASH_IRQHandler          ; Flash
+                DCD     RCC_IRQHandler            ; RCC
+                DCD     EXTI0_IRQHandler          ; EXTI Line 0
+                DCD     EXTI1_IRQHandler          ; EXTI Line 1
+                DCD     EXTI2_IRQHandler          ; EXTI Line 2
+                DCD     EXTI3_IRQHandler          ; EXTI Line 3
+                DCD     EXTI4_IRQHandler          ; EXTI Line 4
+                DCD     DMA1_Channel1_IRQHandler  ; DMA1 Channel 1
+                DCD     DMA1_Channel2_IRQHandler  ; DMA1 Channel 2
+                DCD     DMA1_Channel3_IRQHandler  ; DMA1 Channel 3
+                DCD     DMA1_Channel4_IRQHandler  ; DMA1 Channel 4
+                DCD     DMA1_Channel5_IRQHandler  ; DMA1 Channel 5
+                DCD     DMA1_Channel6_IRQHandler  ; DMA1 Channel 6
+                DCD     DMA1_Channel7_IRQHandler  ; DMA1 Channel 7
+                DCD     ADC1_2_IRQHandler         ; ADC1 & ADC2
+                DCD     USB_HP_CAN1_TX_IRQHandler  ; USB High Priority or CAN1 TX
+                DCD     USB_LP_CAN1_RX0_IRQHandler ; USB Low  Priority or CAN1 RX0
+                DCD     CAN1_RX1_IRQHandler       ; CAN1 RX1
+                DCD     CAN1_SCE_IRQHandler       ; CAN1 SCE
+                DCD     EXTI9_5_IRQHandler        ; EXTI Line 9..5
+                DCD     TIM1_BRK_IRQHandler       ; TIM1 Break
+                DCD     TIM1_UP_IRQHandler        ; TIM1 Update
+                DCD     TIM1_TRG_COM_IRQHandler   ; TIM1 Trigger and Commutation
+                DCD     TIM1_CC_IRQHandler        ; TIM1 Capture Compare
+                DCD     TIM2_IRQHandler           ; TIM2
+                DCD     TIM3_IRQHandler           ; TIM3
+                DCD     TIM4_IRQHandler           ; TIM4
+                DCD     I2C1_EV_IRQHandler        ; I2C1 Event
+                DCD     I2C1_ER_IRQHandler        ; I2C1 Error
+                DCD     I2C2_EV_IRQHandler        ; I2C2 Event
+                DCD     I2C2_ER_IRQHandler        ; I2C2 Error
+                DCD     SPI1_IRQHandler           ; SPI1
+                DCD     SPI2_IRQHandler           ; SPI2
+                DCD     USART1_IRQHandler         ; USART1
+                DCD     USART2_IRQHandler         ; USART2
+                DCD     USART3_IRQHandler         ; USART3
+                DCD     EXTI15_10_IRQHandler      ; EXTI Line 15..10
+                DCD     RTCAlarm_IRQHandler       ; RTC Alarm through EXTI Line
+                DCD     USBWakeUp_IRQHandler      ; USB Wakeup from suspend
+                DCD     TIM8_BRK_IRQHandler       ; TIM8 Break
+                DCD     TIM8_UP_IRQHandler        ; TIM8 Update
+                DCD     TIM8_TRG_COM_IRQHandler   ; TIM8 Trigger and Commutation
+                DCD     TIM8_CC_IRQHandler        ; TIM8 Capture Compare
+                DCD     ADC3_IRQHandler           ; ADC3
+                DCD     FSMC_IRQHandler           ; FSMC
+                DCD     SDIO_IRQHandler           ; SDIO
+                DCD     TIM5_IRQHandler           ; TIM5
+                DCD     SPI3_IRQHandler           ; SPI3
+                DCD     UART4_IRQHandler          ; UART4
+                DCD     UART5_IRQHandler          ; UART5
+                DCD     TIM6_IRQHandler           ; TIM6
+                DCD     TIM7_IRQHandler           ; TIM7
+                DCD     DMA2_Channel1_IRQHandler  ; DMA2 Channel1
+                DCD     DMA2_Channel2_IRQHandler  ; DMA2 Channel2
+                DCD     DMA2_Channel3_IRQHandler  ; DMA2 Channel3
+                DCD     DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5
+__Vectors_End
+
+__Vectors_Size 	EQU 	__Vectors_End - __Vectors
+
+                AREA    |.text|, CODE, READONLY
+
+; Dummy SystemInit_ExtMemCtl function                
+SystemInit_ExtMemCtl     PROC
+                EXPORT  SystemInit_ExtMemCtl      [WEAK]
+                BX      LR
+                ENDP
+                
+; Reset handler routine
+Reset_Handler   PROC
+                EXPORT  Reset_Handler             [WEAK]
+                IMPORT  __main
+
+                LDR     R0, = SystemInit_ExtMemCtl ; initialize external memory controller
+                BLX     R0
+
+                LDR     R1, = __initial_sp        ; restore original stack pointer
+                MSR     MSP, R1                   
+
+                LDR     R0, =__main
+                BX      R0
+                ENDP
+                
+; Dummy Exception Handlers (infinite loops which can be modified)
+
+NMI_Handler     PROC
+                EXPORT  NMI_Handler                [WEAK]
+                B       .
+                ENDP
+HardFault_Handler\
+                PROC
+                EXPORT  HardFault_Handler          [WEAK]
+                B       .
+                ENDP
+MemManage_Handler\
+                PROC
+                EXPORT  MemManage_Handler          [WEAK]
+                B       .
+                ENDP
+BusFault_Handler\
+                PROC
+                EXPORT  BusFault_Handler           [WEAK]
+                B       .
+                ENDP
+UsageFault_Handler\
+                PROC
+                EXPORT  UsageFault_Handler         [WEAK]
+                B       .
+                ENDP
+SVC_Handler     PROC
+                EXPORT  SVC_Handler                [WEAK]
+                B       .
+                ENDP
+DebugMon_Handler\
+                PROC
+                EXPORT  DebugMon_Handler           [WEAK]
+                B       .
+                ENDP
+PendSV_Handler  PROC
+                EXPORT  PendSV_Handler             [WEAK]
+                B       .
+                ENDP
+SysTick_Handler PROC
+                EXPORT  SysTick_Handler            [WEAK]
+                B       .
+                ENDP
+
+Default_Handler PROC
+
+                EXPORT  WWDG_IRQHandler            [WEAK]
+                EXPORT  PVD_IRQHandler             [WEAK]
+                EXPORT  TAMPER_IRQHandler          [WEAK]
+                EXPORT  RTC_IRQHandler             [WEAK]
+                EXPORT  FLASH_IRQHandler           [WEAK]
+                EXPORT  RCC_IRQHandler             [WEAK]
+                EXPORT  EXTI0_IRQHandler           [WEAK]
+                EXPORT  EXTI1_IRQHandler           [WEAK]
+                EXPORT  EXTI2_IRQHandler           [WEAK]
+                EXPORT  EXTI3_IRQHandler           [WEAK]
+                EXPORT  EXTI4_IRQHandler           [WEAK]
+                EXPORT  DMA1_Channel1_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel2_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel3_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel4_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel5_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel6_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel7_IRQHandler   [WEAK]
+                EXPORT  ADC1_2_IRQHandler          [WEAK]
+                EXPORT  USB_HP_CAN1_TX_IRQHandler  [WEAK]
+                EXPORT  USB_LP_CAN1_RX0_IRQHandler [WEAK]
+                EXPORT  CAN1_RX1_IRQHandler        [WEAK]
+                EXPORT  CAN1_SCE_IRQHandler        [WEAK]
+                EXPORT  EXTI9_5_IRQHandler         [WEAK]
+                EXPORT  TIM1_BRK_IRQHandler        [WEAK]
+                EXPORT  TIM1_UP_IRQHandler         [WEAK]
+                EXPORT  TIM1_TRG_COM_IRQHandler    [WEAK]
+                EXPORT  TIM1_CC_IRQHandler         [WEAK]
+                EXPORT  TIM2_IRQHandler            [WEAK]
+                EXPORT  TIM3_IRQHandler            [WEAK]
+                EXPORT  TIM4_IRQHandler            [WEAK]
+                EXPORT  I2C1_EV_IRQHandler         [WEAK]
+                EXPORT  I2C1_ER_IRQHandler         [WEAK]
+                EXPORT  I2C2_EV_IRQHandler         [WEAK]
+                EXPORT  I2C2_ER_IRQHandler         [WEAK]
+                EXPORT  SPI1_IRQHandler            [WEAK]
+                EXPORT  SPI2_IRQHandler            [WEAK]
+                EXPORT  USART1_IRQHandler          [WEAK]
+                EXPORT  USART2_IRQHandler          [WEAK]
+                EXPORT  USART3_IRQHandler          [WEAK]
+                EXPORT  EXTI15_10_IRQHandler       [WEAK]
+                EXPORT  RTCAlarm_IRQHandler        [WEAK]
+                EXPORT  USBWakeUp_IRQHandler       [WEAK]
+                EXPORT  TIM8_BRK_IRQHandler        [WEAK]
+                EXPORT  TIM8_UP_IRQHandler         [WEAK]
+                EXPORT  TIM8_TRG_COM_IRQHandler    [WEAK]
+                EXPORT  TIM8_CC_IRQHandler         [WEAK]
+                EXPORT  ADC3_IRQHandler            [WEAK]
+                EXPORT  FSMC_IRQHandler            [WEAK]
+                EXPORT  SDIO_IRQHandler            [WEAK]
+                EXPORT  TIM5_IRQHandler            [WEAK]
+                EXPORT  SPI3_IRQHandler            [WEAK]
+                EXPORT  UART4_IRQHandler           [WEAK]
+                EXPORT  UART5_IRQHandler           [WEAK]
+                EXPORT  TIM6_IRQHandler            [WEAK]
+                EXPORT  TIM7_IRQHandler            [WEAK]
+                EXPORT  DMA2_Channel1_IRQHandler   [WEAK]
+                EXPORT  DMA2_Channel2_IRQHandler   [WEAK]
+                EXPORT  DMA2_Channel3_IRQHandler   [WEAK]
+                EXPORT  DMA2_Channel4_5_IRQHandler [WEAK]
+
+WWDG_IRQHandler
+PVD_IRQHandler
+TAMPER_IRQHandler
+RTC_IRQHandler
+FLASH_IRQHandler
+RCC_IRQHandler
+EXTI0_IRQHandler
+EXTI1_IRQHandler
+EXTI2_IRQHandler
+EXTI3_IRQHandler
+EXTI4_IRQHandler
+DMA1_Channel1_IRQHandler
+DMA1_Channel2_IRQHandler
+DMA1_Channel3_IRQHandler
+DMA1_Channel4_IRQHandler
+DMA1_Channel5_IRQHandler
+DMA1_Channel6_IRQHandler
+DMA1_Channel7_IRQHandler
+ADC1_2_IRQHandler
+USB_HP_CAN1_TX_IRQHandler
+USB_LP_CAN1_RX0_IRQHandler
+CAN1_RX1_IRQHandler
+CAN1_SCE_IRQHandler
+EXTI9_5_IRQHandler
+TIM1_BRK_IRQHandler
+TIM1_UP_IRQHandler
+TIM1_TRG_COM_IRQHandler
+TIM1_CC_IRQHandler
+TIM2_IRQHandler
+TIM3_IRQHandler
+TIM4_IRQHandler
+I2C1_EV_IRQHandler
+I2C1_ER_IRQHandler
+I2C2_EV_IRQHandler
+I2C2_ER_IRQHandler
+SPI1_IRQHandler
+SPI2_IRQHandler
+USART1_IRQHandler
+USART2_IRQHandler
+USART3_IRQHandler
+EXTI15_10_IRQHandler
+RTCAlarm_IRQHandler
+USBWakeUp_IRQHandler
+TIM8_BRK_IRQHandler
+TIM8_UP_IRQHandler
+TIM8_TRG_COM_IRQHandler
+TIM8_CC_IRQHandler
+ADC3_IRQHandler
+FSMC_IRQHandler
+SDIO_IRQHandler
+TIM5_IRQHandler
+SPI3_IRQHandler
+UART4_IRQHandler
+UART5_IRQHandler
+TIM6_IRQHandler
+TIM7_IRQHandler
+DMA2_Channel1_IRQHandler
+DMA2_Channel2_IRQHandler
+DMA2_Channel3_IRQHandler
+DMA2_Channel4_5_IRQHandler
+                B       .
+
+                ENDP
+
+                ALIGN
+
+;*******************************************************************************
+; User Stack and Heap initialization
+;*******************************************************************************
+                 IF      :DEF:__MICROLIB
+                
+                 EXPORT  __initial_sp
+                 EXPORT  __heap_base
+                 EXPORT  __heap_limit
+                
+                 ELSE
+                
+                 IMPORT  __use_two_region_memory
+                 EXPORT  __user_initial_stackheap
+                 
+__user_initial_stackheap
+
+                 LDR     R0, =  Heap_Mem
+                 LDR     R1, =(Stack_Mem + Stack_Size)
+                 LDR     R2, = (Heap_Mem +  Heap_Size)
+                 LDR     R3, = Stack_Mem
+                 BX      LR
+
+                 ALIGN
+
+                 ENDIF
+
+                 END
+
+;******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE*****
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_ld.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_ld.s
new file mode 100644
index 0000000000000000000000000000000000000000..5c897844adea0be2738fc6c024eb9afb39f3c04f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_ld.s
@@ -0,0 +1,293 @@
+;******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_ld.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x Low Density Devices vector table for RVMDK 
+;*                      toolchain. 
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == Reset_Handler
+;*                      - Set the vector table entries with the exceptions ISR address
+;*                      - Branches to __main in the C library (which eventually
+;*                        calls main()).
+;*                      After Reset the CortexM3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;* <<< Use Configuration Wizard in Context Menu >>>   
+;*******************************************************************************
+; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************
+
+; Amount of memory (in bytes) allocated for Stack
+; Tailor this value to your application needs
+; <h> Stack Configuration
+;   <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Stack_Size      EQU     0x00000400
+
+                AREA    STACK, NOINIT, READWRITE, ALIGN=3
+Stack_Mem       SPACE   Stack_Size
+__initial_sp
+
+
+; <h> Heap Configuration
+;   <o>  Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Heap_Size       EQU     0x00000200
+
+                AREA    HEAP, NOINIT, READWRITE, ALIGN=3
+__heap_base
+Heap_Mem        SPACE   Heap_Size
+__heap_limit
+
+                PRESERVE8
+                THUMB
+
+
+; Vector Table Mapped to Address 0 at Reset
+                AREA    RESET, DATA, READONLY
+                EXPORT  __Vectors
+                EXPORT  __Vectors_End
+                EXPORT  __Vectors_Size
+
+__Vectors       DCD     __initial_sp              ; Top of Stack
+                DCD     Reset_Handler             ; Reset Handler
+                DCD     NMI_Handler               ; NMI Handler
+                DCD     HardFault_Handler         ; Hard Fault Handler
+                DCD     MemManage_Handler         ; MPU Fault Handler
+                DCD     BusFault_Handler          ; Bus Fault Handler
+                DCD     UsageFault_Handler        ; Usage Fault Handler
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     SVC_Handler               ; SVCall Handler
+                DCD     DebugMon_Handler          ; Debug Monitor Handler
+                DCD     0                         ; Reserved
+                DCD     PendSV_Handler            ; PendSV Handler
+                DCD     SysTick_Handler           ; SysTick Handler
+
+                ; External Interrupts
+                DCD     WWDG_IRQHandler           ; Window Watchdog
+                DCD     PVD_IRQHandler            ; PVD through EXTI Line detect
+                DCD     TAMPER_IRQHandler         ; Tamper
+                DCD     RTC_IRQHandler            ; RTC
+                DCD     FLASH_IRQHandler          ; Flash
+                DCD     RCC_IRQHandler            ; RCC
+                DCD     EXTI0_IRQHandler          ; EXTI Line 0
+                DCD     EXTI1_IRQHandler          ; EXTI Line 1
+                DCD     EXTI2_IRQHandler          ; EXTI Line 2
+                DCD     EXTI3_IRQHandler          ; EXTI Line 3
+                DCD     EXTI4_IRQHandler          ; EXTI Line 4
+                DCD     DMA1_Channel1_IRQHandler  ; DMA1 Channel 1
+                DCD     DMA1_Channel2_IRQHandler  ; DMA1 Channel 2
+                DCD     DMA1_Channel3_IRQHandler  ; DMA1 Channel 3
+                DCD     DMA1_Channel4_IRQHandler  ; DMA1 Channel 4
+                DCD     DMA1_Channel5_IRQHandler  ; DMA1 Channel 5
+                DCD     DMA1_Channel6_IRQHandler  ; DMA1 Channel 6
+                DCD     DMA1_Channel7_IRQHandler  ; DMA1 Channel 7
+                DCD     ADC1_2_IRQHandler         ; ADC1_2
+                DCD     USB_HP_CAN1_TX_IRQHandler  ; USB High Priority or CAN1 TX
+                DCD     USB_LP_CAN1_RX0_IRQHandler ; USB Low  Priority or CAN1 RX0
+                DCD     CAN1_RX1_IRQHandler       ; CAN1 RX1
+                DCD     CAN1_SCE_IRQHandler       ; CAN1 SCE
+                DCD     EXTI9_5_IRQHandler        ; EXTI Line 9..5
+                DCD     TIM1_BRK_IRQHandler       ; TIM1 Break
+                DCD     TIM1_UP_IRQHandler        ; TIM1 Update
+                DCD     TIM1_TRG_COM_IRQHandler   ; TIM1 Trigger and Commutation
+                DCD     TIM1_CC_IRQHandler        ; TIM1 Capture Compare
+                DCD     TIM2_IRQHandler           ; TIM2
+                DCD     TIM3_IRQHandler           ; TIM3
+                DCD     0                         ; Reserved
+                DCD     I2C1_EV_IRQHandler        ; I2C1 Event
+                DCD     I2C1_ER_IRQHandler        ; I2C1 Error
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     SPI1_IRQHandler           ; SPI1
+                DCD     0                         ; Reserved
+                DCD     USART1_IRQHandler         ; USART1
+                DCD     USART2_IRQHandler         ; USART2
+                DCD     0                         ; Reserved
+                DCD     EXTI15_10_IRQHandler      ; EXTI Line 15..10
+                DCD     RTCAlarm_IRQHandler       ; RTC Alarm through EXTI Line
+                DCD     USBWakeUp_IRQHandler      ; USB Wakeup from suspend
+__Vectors_End
+
+__Vectors_Size  EQU  __Vectors_End - __Vectors
+
+                AREA    |.text|, CODE, READONLY
+
+; Reset handler routine
+Reset_Handler    PROC
+                 EXPORT  Reset_Handler             [WEAK]
+     IMPORT  __main
+                 LDR     R0, =__main
+                 BX      R0
+                 ENDP
+
+; Dummy Exception Handlers (infinite loops which can be modified)
+
+NMI_Handler     PROC
+                EXPORT  NMI_Handler                [WEAK]
+                B       .
+                ENDP
+HardFault_Handler\
+                PROC
+                EXPORT  HardFault_Handler          [WEAK]
+                B       .
+                ENDP
+MemManage_Handler\
+                PROC
+                EXPORT  MemManage_Handler          [WEAK]
+                B       .
+                ENDP
+BusFault_Handler\
+                PROC
+                EXPORT  BusFault_Handler           [WEAK]
+                B       .
+                ENDP
+UsageFault_Handler\
+                PROC
+                EXPORT  UsageFault_Handler         [WEAK]
+                B       .
+                ENDP
+SVC_Handler     PROC
+                EXPORT  SVC_Handler                [WEAK]
+                B       .
+                ENDP
+DebugMon_Handler\
+                PROC
+                EXPORT  DebugMon_Handler           [WEAK]
+                B       .
+                ENDP
+PendSV_Handler  PROC
+                EXPORT  PendSV_Handler             [WEAK]
+                B       .
+                ENDP
+SysTick_Handler PROC
+                EXPORT  SysTick_Handler            [WEAK]
+                B       .
+                ENDP
+
+Default_Handler PROC
+
+                EXPORT  WWDG_IRQHandler            [WEAK]
+                EXPORT  PVD_IRQHandler             [WEAK]
+                EXPORT  TAMPER_IRQHandler          [WEAK]
+                EXPORT  RTC_IRQHandler             [WEAK]
+                EXPORT  FLASH_IRQHandler           [WEAK]
+                EXPORT  RCC_IRQHandler             [WEAK]
+                EXPORT  EXTI0_IRQHandler           [WEAK]
+                EXPORT  EXTI1_IRQHandler           [WEAK]
+                EXPORT  EXTI2_IRQHandler           [WEAK]
+                EXPORT  EXTI3_IRQHandler           [WEAK]
+                EXPORT  EXTI4_IRQHandler           [WEAK]
+                EXPORT  DMA1_Channel1_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel2_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel3_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel4_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel5_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel6_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel7_IRQHandler   [WEAK]
+                EXPORT  ADC1_2_IRQHandler          [WEAK]
+                EXPORT  USB_HP_CAN1_TX_IRQHandler  [WEAK]
+                EXPORT  USB_LP_CAN1_RX0_IRQHandler [WEAK]
+                EXPORT  CAN1_RX1_IRQHandler        [WEAK]
+                EXPORT  CAN1_SCE_IRQHandler        [WEAK]
+                EXPORT  EXTI9_5_IRQHandler         [WEAK]
+                EXPORT  TIM1_BRK_IRQHandler        [WEAK]
+                EXPORT  TIM1_UP_IRQHandler         [WEAK]
+                EXPORT  TIM1_TRG_COM_IRQHandler    [WEAK]
+                EXPORT  TIM1_CC_IRQHandler         [WEAK]
+                EXPORT  TIM2_IRQHandler            [WEAK]
+                EXPORT  TIM3_IRQHandler            [WEAK]
+                EXPORT  I2C1_EV_IRQHandler         [WEAK]
+                EXPORT  I2C1_ER_IRQHandler         [WEAK]
+                EXPORT  SPI1_IRQHandler            [WEAK]
+                EXPORT  USART1_IRQHandler          [WEAK]
+                EXPORT  USART2_IRQHandler          [WEAK]
+                EXPORT  EXTI15_10_IRQHandler       [WEAK]
+                EXPORT  RTCAlarm_IRQHandler        [WEAK]
+                EXPORT  USBWakeUp_IRQHandler       [WEAK]
+
+WWDG_IRQHandler
+PVD_IRQHandler
+TAMPER_IRQHandler
+RTC_IRQHandler
+FLASH_IRQHandler
+RCC_IRQHandler
+EXTI0_IRQHandler
+EXTI1_IRQHandler
+EXTI2_IRQHandler
+EXTI3_IRQHandler
+EXTI4_IRQHandler
+DMA1_Channel1_IRQHandler
+DMA1_Channel2_IRQHandler
+DMA1_Channel3_IRQHandler
+DMA1_Channel4_IRQHandler
+DMA1_Channel5_IRQHandler
+DMA1_Channel6_IRQHandler
+DMA1_Channel7_IRQHandler
+ADC1_2_IRQHandler
+USB_HP_CAN1_TX_IRQHandler
+USB_LP_CAN1_RX0_IRQHandler
+CAN1_RX1_IRQHandler
+CAN1_SCE_IRQHandler
+EXTI9_5_IRQHandler
+TIM1_BRK_IRQHandler
+TIM1_UP_IRQHandler
+TIM1_TRG_COM_IRQHandler
+TIM1_CC_IRQHandler
+TIM2_IRQHandler
+TIM3_IRQHandler
+I2C1_EV_IRQHandler
+I2C1_ER_IRQHandler
+SPI1_IRQHandler
+USART1_IRQHandler
+USART2_IRQHandler
+EXTI15_10_IRQHandler
+RTCAlarm_IRQHandler
+USBWakeUp_IRQHandler
+
+                B       .
+
+                ENDP
+
+                ALIGN
+
+;*******************************************************************************
+; User Stack and Heap initialization
+;*******************************************************************************
+                 IF      :DEF:__MICROLIB
+                
+                 EXPORT  __initial_sp
+                 EXPORT  __heap_base
+                 EXPORT  __heap_limit
+                
+                 ELSE
+                
+                 IMPORT  __use_two_region_memory
+                 EXPORT  __user_initial_stackheap
+                 
+__user_initial_stackheap
+
+                 LDR     R0, =  Heap_Mem
+                 LDR     R1, =(Stack_Mem + Stack_Size)
+                 LDR     R2, = (Heap_Mem +  Heap_Size)
+                 LDR     R3, = Stack_Mem
+                 BX      LR
+
+                 ALIGN
+
+                 ENDIF
+
+                 END
+
+;******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE*****
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_md.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_md.s
new file mode 100644
index 0000000000000000000000000000000000000000..753cfe9c45394b13ec1dc6cd93f6012f1425fb13
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/arm/startup_stm32f10x_md.s
@@ -0,0 +1,303 @@
+;******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_md.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x Medium Density Devices vector table for RVMDK 
+;*                      toolchain.  
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == Reset_Handler
+;*                      - Set the vector table entries with the exceptions ISR address
+;*                      - Branches to __main in the C library (which eventually
+;*                        calls main()).
+;*                      After Reset the CortexM3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;* <<< Use Configuration Wizard in Context Menu >>>   
+;*******************************************************************************
+; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************
+
+; Amount of memory (in bytes) allocated for Stack
+; Tailor this value to your application needs
+; <h> Stack Configuration
+;   <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Stack_Size      EQU     0x00000400
+
+                AREA    STACK, NOINIT, READWRITE, ALIGN=3
+Stack_Mem       SPACE   Stack_Size
+__initial_sp
+
+
+; <h> Heap Configuration
+;   <o>  Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
+; </h>
+
+Heap_Size       EQU     0x00000200
+
+                AREA    HEAP, NOINIT, READWRITE, ALIGN=3
+__heap_base
+Heap_Mem        SPACE   Heap_Size
+__heap_limit
+
+                PRESERVE8
+                THUMB
+
+
+; Vector Table Mapped to Address 0 at Reset
+                AREA    RESET, DATA, READONLY
+                EXPORT  __Vectors
+                EXPORT  __Vectors_End
+                EXPORT  __Vectors_Size
+
+__Vectors       DCD     __initial_sp              ; Top of Stack
+                DCD     Reset_Handler             ; Reset Handler
+                DCD     NMI_Handler               ; NMI Handler
+                DCD     HardFault_Handler         ; Hard Fault Handler
+                DCD     MemManage_Handler         ; MPU Fault Handler
+                DCD     BusFault_Handler          ; Bus Fault Handler
+                DCD     UsageFault_Handler        ; Usage Fault Handler
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     SVC_Handler               ; SVCall Handler
+                DCD     DebugMon_Handler          ; Debug Monitor Handler
+                DCD     0                         ; Reserved
+                DCD     PendSV_Handler            ; PendSV Handler
+                DCD     SysTick_Handler           ; SysTick Handler
+
+                ; External Interrupts
+                DCD     WWDG_IRQHandler           ; Window Watchdog
+                DCD     PVD_IRQHandler            ; PVD through EXTI Line detect
+                DCD     TAMPER_IRQHandler         ; Tamper
+                DCD     RTC_IRQHandler            ; RTC
+                DCD     FLASH_IRQHandler          ; Flash
+                DCD     RCC_IRQHandler            ; RCC
+                DCD     EXTI0_IRQHandler          ; EXTI Line 0
+                DCD     EXTI1_IRQHandler          ; EXTI Line 1
+                DCD     EXTI2_IRQHandler          ; EXTI Line 2
+                DCD     EXTI3_IRQHandler          ; EXTI Line 3
+                DCD     EXTI4_IRQHandler          ; EXTI Line 4
+                DCD     DMA1_Channel1_IRQHandler  ; DMA1 Channel 1
+                DCD     DMA1_Channel2_IRQHandler  ; DMA1 Channel 2
+                DCD     DMA1_Channel3_IRQHandler  ; DMA1 Channel 3
+                DCD     DMA1_Channel4_IRQHandler  ; DMA1 Channel 4
+                DCD     DMA1_Channel5_IRQHandler  ; DMA1 Channel 5
+                DCD     DMA1_Channel6_IRQHandler  ; DMA1 Channel 6
+                DCD     DMA1_Channel7_IRQHandler  ; DMA1 Channel 7
+                DCD     ADC1_2_IRQHandler         ; ADC1_2
+                DCD     USB_HP_CAN1_TX_IRQHandler  ; USB High Priority or CAN1 TX
+                DCD     USB_LP_CAN1_RX0_IRQHandler ; USB Low  Priority or CAN1 RX0
+                DCD     CAN1_RX1_IRQHandler       ; CAN1 RX1
+                DCD     CAN1_SCE_IRQHandler       ; CAN1 SCE
+                DCD     EXTI9_5_IRQHandler        ; EXTI Line 9..5
+                DCD     TIM1_BRK_IRQHandler       ; TIM1 Break
+                DCD     TIM1_UP_IRQHandler        ; TIM1 Update
+                DCD     TIM1_TRG_COM_IRQHandler   ; TIM1 Trigger and Commutation
+                DCD     TIM1_CC_IRQHandler        ; TIM1 Capture Compare
+                DCD     TIM2_IRQHandler           ; TIM2
+                DCD     TIM3_IRQHandler           ; TIM3
+                DCD     TIM4_IRQHandler           ; TIM4
+                DCD     I2C1_EV_IRQHandler        ; I2C1 Event
+                DCD     I2C1_ER_IRQHandler        ; I2C1 Error
+                DCD     I2C2_EV_IRQHandler        ; I2C2 Event
+                DCD     I2C2_ER_IRQHandler        ; I2C2 Error
+                DCD     SPI1_IRQHandler           ; SPI1
+                DCD     SPI2_IRQHandler           ; SPI2
+                DCD     USART1_IRQHandler         ; USART1
+                DCD     USART2_IRQHandler         ; USART2
+                DCD     USART3_IRQHandler         ; USART3
+                DCD     EXTI15_10_IRQHandler      ; EXTI Line 15..10
+                DCD     RTCAlarm_IRQHandler       ; RTC Alarm through EXTI Line
+                DCD     USBWakeUp_IRQHandler      ; USB Wakeup from suspend
+__Vectors_End
+
+__Vectors_Size  EQU  __Vectors_End - __Vectors
+
+                AREA    |.text|, CODE, READONLY
+
+; Reset handler routine
+Reset_Handler    PROC
+                 EXPORT  Reset_Handler             [WEAK]
+        IMPORT  __main
+                 LDR     R0, =__main
+                 BX      R0
+                 ENDP
+
+; Dummy Exception Handlers (infinite loops which can be modified)
+
+NMI_Handler     PROC
+                EXPORT  NMI_Handler                [WEAK]
+                B       .
+                ENDP
+HardFault_Handler\
+                PROC
+                EXPORT  HardFault_Handler          [WEAK]
+                B       .
+                ENDP
+MemManage_Handler\
+                PROC
+                EXPORT  MemManage_Handler          [WEAK]
+                B       .
+                ENDP
+BusFault_Handler\
+                PROC
+                EXPORT  BusFault_Handler           [WEAK]
+                B       .
+                ENDP
+UsageFault_Handler\
+                PROC
+                EXPORT  UsageFault_Handler         [WEAK]
+                B       .
+                ENDP
+SVC_Handler     PROC
+                EXPORT  SVC_Handler                [WEAK]
+                B       .
+                ENDP
+DebugMon_Handler\
+                PROC
+                EXPORT  DebugMon_Handler           [WEAK]
+                B       .
+                ENDP
+PendSV_Handler  PROC
+                EXPORT  PendSV_Handler             [WEAK]
+                B       .
+                ENDP
+SysTick_Handler PROC
+                EXPORT  SysTick_Handler            [WEAK]
+                B       .
+                ENDP
+
+Default_Handler PROC
+
+                EXPORT  WWDG_IRQHandler            [WEAK]
+                EXPORT  PVD_IRQHandler             [WEAK]
+                EXPORT  TAMPER_IRQHandler          [WEAK]
+                EXPORT  RTC_IRQHandler             [WEAK]
+                EXPORT  FLASH_IRQHandler           [WEAK]
+                EXPORT  RCC_IRQHandler             [WEAK]
+                EXPORT  EXTI0_IRQHandler           [WEAK]
+                EXPORT  EXTI1_IRQHandler           [WEAK]
+                EXPORT  EXTI2_IRQHandler           [WEAK]
+                EXPORT  EXTI3_IRQHandler           [WEAK]
+                EXPORT  EXTI4_IRQHandler           [WEAK]
+                EXPORT  DMA1_Channel1_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel2_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel3_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel4_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel5_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel6_IRQHandler   [WEAK]
+                EXPORT  DMA1_Channel7_IRQHandler   [WEAK]
+                EXPORT  ADC1_2_IRQHandler          [WEAK]
+                EXPORT  USB_HP_CAN1_TX_IRQHandler  [WEAK]
+                EXPORT  USB_LP_CAN1_RX0_IRQHandler [WEAK]
+                EXPORT  CAN1_RX1_IRQHandler        [WEAK]
+                EXPORT  CAN1_SCE_IRQHandler        [WEAK]
+                EXPORT  EXTI9_5_IRQHandler         [WEAK]
+                EXPORT  TIM1_BRK_IRQHandler        [WEAK]
+                EXPORT  TIM1_UP_IRQHandler         [WEAK]
+                EXPORT  TIM1_TRG_COM_IRQHandler    [WEAK]
+                EXPORT  TIM1_CC_IRQHandler         [WEAK]
+                EXPORT  TIM2_IRQHandler            [WEAK]
+                EXPORT  TIM3_IRQHandler            [WEAK]
+                EXPORT  TIM4_IRQHandler            [WEAK]
+                EXPORT  I2C1_EV_IRQHandler         [WEAK]
+                EXPORT  I2C1_ER_IRQHandler         [WEAK]
+                EXPORT  I2C2_EV_IRQHandler         [WEAK]
+                EXPORT  I2C2_ER_IRQHandler         [WEAK]
+                EXPORT  SPI1_IRQHandler            [WEAK]
+                EXPORT  SPI2_IRQHandler            [WEAK]
+                EXPORT  USART1_IRQHandler          [WEAK]
+                EXPORT  USART2_IRQHandler          [WEAK]
+                EXPORT  USART3_IRQHandler          [WEAK]
+                EXPORT  EXTI15_10_IRQHandler       [WEAK]
+                EXPORT  RTCAlarm_IRQHandler        [WEAK]
+                EXPORT  USBWakeUp_IRQHandler       [WEAK]
+
+WWDG_IRQHandler
+PVD_IRQHandler
+TAMPER_IRQHandler
+RTC_IRQHandler
+FLASH_IRQHandler
+RCC_IRQHandler
+EXTI0_IRQHandler
+EXTI1_IRQHandler
+EXTI2_IRQHandler
+EXTI3_IRQHandler
+EXTI4_IRQHandler
+DMA1_Channel1_IRQHandler
+DMA1_Channel2_IRQHandler
+DMA1_Channel3_IRQHandler
+DMA1_Channel4_IRQHandler
+DMA1_Channel5_IRQHandler
+DMA1_Channel6_IRQHandler
+DMA1_Channel7_IRQHandler
+ADC1_2_IRQHandler
+USB_HP_CAN1_TX_IRQHandler
+USB_LP_CAN1_RX0_IRQHandler
+CAN1_RX1_IRQHandler
+CAN1_SCE_IRQHandler
+EXTI9_5_IRQHandler
+TIM1_BRK_IRQHandler
+TIM1_UP_IRQHandler
+TIM1_TRG_COM_IRQHandler
+TIM1_CC_IRQHandler
+TIM2_IRQHandler
+TIM3_IRQHandler
+TIM4_IRQHandler
+I2C1_EV_IRQHandler
+I2C1_ER_IRQHandler
+I2C2_EV_IRQHandler
+I2C2_ER_IRQHandler
+SPI1_IRQHandler
+SPI2_IRQHandler
+USART1_IRQHandler
+USART2_IRQHandler
+USART3_IRQHandler
+EXTI15_10_IRQHandler
+RTCAlarm_IRQHandler
+USBWakeUp_IRQHandler
+
+                B       .
+
+                ENDP
+
+                ALIGN
+
+;*******************************************************************************
+; User Stack and Heap initialization
+;*******************************************************************************
+                 IF      :DEF:__MICROLIB           
+                
+                 EXPORT  __initial_sp
+                 EXPORT  __heap_base
+                 EXPORT  __heap_limit
+                
+                 ELSE
+                
+                 IMPORT  __use_two_region_memory
+                 EXPORT  __user_initial_stackheap
+                 
+__user_initial_stackheap
+
+                 LDR     R0, =  Heap_Mem
+                 LDR     R1, =(Stack_Mem + Stack_Size)
+                 LDR     R2, = (Heap_Mem +  Heap_Size)
+                 LDR     R3, = Stack_Mem
+                 BX      LR
+
+                 ALIGN
+
+                 ENDIF
+
+                 END
+
+;******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE*****
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s
new file mode 100644
index 0000000000000000000000000000000000000000..621bf5180b93e1f0eda95b546c8a799ef8125c35
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s
@@ -0,0 +1,464 @@
+/**
+  ******************************************************************************
+  * @file    startup_stm32f10x_cl.s
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   STM32F10x Connectivity line Devices vector table for RIDE7 toolchain.
+  *          This module performs:
+  *                - Set the initial SP
+  *                - Set the initial PC == Reset_Handler,
+  *                - Set the vector table entries with the exceptions ISR 
+  *                  address.
+  *                - Branches to main in the C library (which eventually
+  *                  calls main()).
+  *          After Reset the Cortex-M3 processor is in Thread mode,
+  *          priority is Privileged, and the Stack is set to Main.
+  *******************************************************************************
+ * @copy
+ *
+ * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+ * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+ * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+ * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+ * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+ * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+ *
+ * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+ */  
+    
+  .syntax unified
+  .cpu cortex-m3
+  .fpu softvfp
+  .thumb
+
+.global  g_pfnVectors
+.global  Default_Handler
+
+/* start address for the initialization values of the .data section. 
+defined in linker script */
+.word  _sidata
+/* start address for the .data section. defined in linker script */  
+.word  _sdata
+/* end address for the .data section. defined in linker script */
+.word  _edata
+/* start address for the .bss section. defined in linker script */
+.word  _sbss
+/* end address for the .bss section. defined in linker script */
+.word  _ebss
+
+.equ  BootRAM, 0xF1E0F85F
+/**
+ * @brief  This is the code that gets called when the processor first
+ *          starts execution following a reset event. Only the absolutely
+ *          necessary set is performed, after which the application
+ *          supplied main() routine is called. 
+ * @param  None
+ * @retval : None
+*/
+
+    .section  .text.Reset_Handler
+  .weak  Reset_Handler
+  .type  Reset_Handler, %function
+Reset_Handler:  
+
+/* Copy the data segment initializers from flash to SRAM */  
+  movs  r1, #0
+  b  LoopCopyDataInit
+
+CopyDataInit:
+  ldr  r3, =_sidata
+  ldr  r3, [r3, r1]
+  str  r3, [r0, r1]
+  adds  r1, r1, #4
+    
+LoopCopyDataInit:
+  ldr  r0, =_sdata
+  ldr  r3, =_edata
+  adds  r2, r0, r1
+  cmp  r2, r3
+  bcc  CopyDataInit
+  ldr  r2, =_sbss
+  b  LoopFillZerobss
+
+/* Zero fill the bss segment. */  
+FillZerobss:
+  movs  r3, #0
+  str  r3, [r2], #4
+    
+LoopFillZerobss:
+  ldr  r3, = _ebss
+  cmp  r2, r3
+  bcc  FillZerobss
+/* Call the application's entry point.*/
+  bl  main
+  bx  lr    
+.size  Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief  This is the code that gets called when the processor receives an 
+ *         unexpected interrupt.  This simply enters an infinite loop, preserving
+ *         the system state for examination by a debugger.
+ *
+ * @param  None     
+ * @retval : None       
+*/
+    .section  .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+  b  Infinite_Loop
+  .size  Default_Handler, .-Default_Handler
+
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3.  Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/    
+   .section  .isr_vector,"a",%progbits
+  .type  g_pfnVectors, %object
+  .size  g_pfnVectors, .-g_pfnVectors
+    
+    
+g_pfnVectors:
+  .word  _estack
+  .word  Reset_Handler
+  .word  NMI_Handler
+  .word  HardFault_Handler
+  .word  MemManage_Handler
+  .word  BusFault_Handler
+  .word  UsageFault_Handler
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  SVC_Handler
+  .word  DebugMon_Handler
+  .word  0
+  .word  PendSV_Handler
+  .word  SysTick_Handler
+  .word  WWDG_IRQHandler
+  .word  PVD_IRQHandler
+  .word  TAMPER_IRQHandler
+  .word  RTC_IRQHandler
+  .word  FLASH_IRQHandler
+  .word  RCC_IRQHandler
+  .word  EXTI0_IRQHandler
+  .word  EXTI1_IRQHandler
+  .word  EXTI2_IRQHandler
+  .word  EXTI3_IRQHandler
+  .word  EXTI4_IRQHandler
+  .word  DMA1_Channel1_IRQHandler
+  .word  DMA1_Channel2_IRQHandler
+  .word  DMA1_Channel3_IRQHandler
+  .word  DMA1_Channel4_IRQHandler
+  .word  DMA1_Channel5_IRQHandler
+  .word  DMA1_Channel6_IRQHandler
+  .word  DMA1_Channel7_IRQHandler
+  .word  ADC1_2_IRQHandler
+  .word CAN1_TX_IRQHandler
+  .word CAN1_RX0_IRQHandler
+   .word  CAN1_RX1_IRQHandler
+  .word  CAN1_SCE_IRQHandler
+  .word  EXTI9_5_IRQHandler
+  .word  TIM1_BRK_IRQHandler
+  .word  TIM1_UP_IRQHandler
+  .word  TIM1_TRG_COM_IRQHandler
+  .word  TIM1_CC_IRQHandler
+  .word  TIM2_IRQHandler
+  .word  TIM3_IRQHandler
+  .word  TIM4_IRQHandler
+  .word  I2C1_EV_IRQHandler
+  .word  I2C1_ER_IRQHandler
+  .word  I2C2_EV_IRQHandler
+  .word  I2C2_ER_IRQHandler
+  .word  SPI1_IRQHandler
+  .word  SPI2_IRQHandler
+  .word  USART1_IRQHandler
+  .word  USART2_IRQHandler
+  .word  USART3_IRQHandler
+  .word  EXTI15_10_IRQHandler
+  .word  RTCAlarm_IRQHandler
+  .word  OTG_FS_WKUP_IRQHandler  
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word TIM5_IRQHandler            
+  .word SPI3_IRQHandler            
+  .word UART4_IRQHandler           
+  .word UART5_IRQHandler           
+  .word TIM6_IRQHandler           
+  .word TIM7_IRQHandler            
+  .word DMA2_Channel1_IRQHandler   
+  .word DMA2_Channel2_IRQHandler   
+  .word DMA2_Channel3_IRQHandler   
+  .word DMA2_Channel4_IRQHandler  
+  .word DMA2_Channel5_IRQHandler   
+  .word ETH_IRQHandler            
+  .word ETH_WKUP_IRQHandler        
+  .word CAN2_TX_IRQHandler         
+  .word CAN2_RX0_IRQHandler        
+  .word CAN2_RX1_IRQHandler        
+  .word CAN2_SCE_IRQHandler        
+  .word OTG_FS_IRQHandler          
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0           
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0            
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0            
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0
+  .word 0            
+  .word 0
+  .word 0
+  .word 0
+  .word 0               
+  .word BootRAM     /* @0x1E0. This is for boot in RAM mode for 
+                         STM32F10x Connectivity line Devices. */
+    
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler. 
+* As they are weak aliases, any function with the same name will override 
+* this definition.
+*
+*******************************************************************************/
+  .weak  NMI_Handler
+  .thumb_set NMI_Handler,Default_Handler
+  
+  .weak  HardFault_Handler
+  .thumb_set HardFault_Handler,Default_Handler
+  
+  .weak  MemManage_Handler
+  .thumb_set MemManage_Handler,Default_Handler
+  
+  .weak  BusFault_Handler
+  .thumb_set BusFault_Handler,Default_Handler
+
+  .weak  UsageFault_Handler
+  .thumb_set UsageFault_Handler,Default_Handler
+
+  .weak  SVC_Handler
+  .thumb_set SVC_Handler,Default_Handler
+
+  .weak  DebugMon_Handler
+  .thumb_set DebugMon_Handler,Default_Handler
+
+  .weak  PendSV_Handler
+  .thumb_set PendSV_Handler,Default_Handler
+
+  .weak  SysTick_Handler
+  .thumb_set SysTick_Handler,Default_Handler
+
+  .weak  WWDG_IRQHandler
+  .thumb_set WWDG_IRQHandler,Default_Handler
+
+  .weak  PVD_IRQHandler
+  .thumb_set PVD_IRQHandler,Default_Handler
+
+  .weak  TAMPER_IRQHandler
+  .thumb_set TAMPER_IRQHandler,Default_Handler
+
+  .weak  RTC_IRQHandler
+  .thumb_set RTC_IRQHandler,Default_Handler
+
+  .weak  FLASH_IRQHandler
+  .thumb_set FLASH_IRQHandler,Default_Handler
+
+  .weak  RCC_IRQHandler
+  .thumb_set RCC_IRQHandler,Default_Handler
+
+  .weak  EXTI0_IRQHandler
+  .thumb_set EXTI0_IRQHandler,Default_Handler
+
+  .weak  EXTI1_IRQHandler
+  .thumb_set EXTI1_IRQHandler,Default_Handler
+
+  .weak  EXTI2_IRQHandler
+  .thumb_set EXTI2_IRQHandler,Default_Handler
+
+  .weak  EXTI3_IRQHandler
+  .thumb_set EXTI3_IRQHandler,Default_Handler
+
+  .weak  EXTI4_IRQHandler
+  .thumb_set EXTI4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel1_IRQHandler
+  .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel2_IRQHandler
+  .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel3_IRQHandler
+  .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel4_IRQHandler
+  .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel5_IRQHandler
+  .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel6_IRQHandler
+  .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel7_IRQHandler
+  .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+  .weak  ADC1_2_IRQHandler
+  .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+  .weak  CAN1_TX_IRQHandler
+  .thumb_set CAN1_TX_IRQHandler,Default_Handler
+
+  .weak  CAN1_RX0_IRQHandler
+  .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+
+  .weak  CAN1_RX1_IRQHandler
+  .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+  .weak  CAN1_SCE_IRQHandler
+  .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+  .weak  EXTI9_5_IRQHandler
+  .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+  .weak  TIM1_BRK_IRQHandler
+  .thumb_set TIM1_BRK_IRQHandler,Default_Handler
+
+  .weak  TIM1_UP_IRQHandler
+  .thumb_set TIM1_UP_IRQHandler,Default_Handler
+
+  .weak  TIM1_TRG_COM_IRQHandler
+  .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+  .weak  TIM1_CC_IRQHandler
+  .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+  .weak  TIM2_IRQHandler
+  .thumb_set TIM2_IRQHandler,Default_Handler
+
+  .weak  TIM3_IRQHandler
+  .thumb_set TIM3_IRQHandler,Default_Handler
+
+  .weak  TIM4_IRQHandler
+  .thumb_set TIM4_IRQHandler,Default_Handler
+
+  .weak  I2C1_EV_IRQHandler
+  .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+  .weak  I2C1_ER_IRQHandler
+  .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+  .weak  I2C2_EV_IRQHandler
+  .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+  .weak  I2C2_ER_IRQHandler
+  .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+  .weak  SPI1_IRQHandler
+  .thumb_set SPI1_IRQHandler,Default_Handler
+
+  .weak  SPI2_IRQHandler
+  .thumb_set SPI2_IRQHandler,Default_Handler
+
+  .weak  USART1_IRQHandler
+  .thumb_set USART1_IRQHandler,Default_Handler
+
+  .weak  USART2_IRQHandler
+  .thumb_set USART2_IRQHandler,Default_Handler
+
+  .weak  USART3_IRQHandler
+  .thumb_set USART3_IRQHandler,Default_Handler
+
+  .weak  EXTI15_10_IRQHandler
+  .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+  .weak  RTCAlarm_IRQHandler
+  .thumb_set RTCAlarm_IRQHandler,Default_Handler
+
+  .weak  OTG_FS_WKUP_IRQHandler
+  .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
+
+  .weak  TIM5_IRQHandler
+  .thumb_set TIM5_IRQHandler,Default_Handler
+
+  .weak  SPI3_IRQHandler  
+  .thumb_set SPI3_IRQHandler,Default_Handler
+
+  .weak  UART4_IRQHandler  
+  .thumb_set UART4_IRQHandler,Default_Handler
+
+  .weak  UART5_IRQHandler  
+  .thumb_set UART5_IRQHandler,Default_Handler
+
+  .weak  TIM6_IRQHandler  
+  .thumb_set TIM6_IRQHandler,Default_Handler
+
+  .weak  TIM7_IRQHandler  
+  .thumb_set TIM7_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel1_IRQHandler  
+  .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel2_IRQHandler  
+  .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel3_IRQHandler  
+  .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel4_IRQHandler  
+  .thumb_set DMA2_Channel4_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel5_IRQHandler  
+  .thumb_set DMA2_Channel5_IRQHandler,Default_Handler
+
+  .weak  ETH_IRQHandler  
+  .thumb_set ETH_IRQHandler,Default_Handler
+
+  .weak  ETH_WKUP_IRQHandler  
+  .thumb_set ETH_WKUP_IRQHandler,Default_Handler
+
+  .weak  CAN2_TX_IRQHandler  
+  .thumb_set CAN2_TX_IRQHandler,Default_Handler
+
+  .weak  CAN2_RX0_IRQHandler  
+  .thumb_set CAN2_RX0_IRQHandler,Default_Handler
+
+  .weak  CAN2_RX1_IRQHandler  
+  .thumb_set CAN2_RX1_IRQHandler,Default_Handler
+
+  .weak  CAN2_SCE_IRQHandler  
+  .thumb_set CAN2_SCE_IRQHandler,Default_Handler
+
+  .weak  OTG_FS_IRQHandler  
+  .thumb_set OTG_FS_IRQHandler ,Default_Handler
+ 
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s
new file mode 100644
index 0000000000000000000000000000000000000000..78c10c3c49385e73282c5ffe310fbb8461834514
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s
@@ -0,0 +1,483 @@
+/**
+  ******************************************************************************
+  * @file      startup_stm32f10x_hd.s
+  * @author    MCD Application Team
+  * @version   V3.1.2
+  * @date      09/28/2009
+  * @brief     STM32F10x High Density Devices vector table for RIDE7 toolchain. 
+  *            This module performs:
+  *                - Set the initial SP
+  *                - Set the initial PC == Reset_Handler,
+  *                - Set the vector table entries with the exceptions ISR address,
+  *                - Configure external SRAM mounted on STM3210E-EVAL board
+  *                  to be used as data memory (optional, to be enabled by user)
+  *                - Branches to main in the C library (which eventually
+  *                  calls main()).
+  *            After Reset the Cortex-M3 processor is in Thread mode,
+  *            priority is Privileged, and the Stack is set to Main.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */  
+    
+    .syntax unified
+  .cpu cortex-m3
+  .fpu softvfp
+  .thumb
+
+.global  g_pfnVectors
+.global  SystemInit_ExtMemCtl_Dummy
+.global  Default_Handler
+
+/* start address for the initialization values of the .data section. 
+defined in linker script */
+.word  _sidata
+/* start address for the .data section. defined in linker script */  
+.word  _sdata
+/* end address for the .data section. defined in linker script */
+.word  _edata
+/* start address for the .bss section. defined in linker script */
+.word  _sbss
+/* end address for the .bss section. defined in linker script */
+.word  _ebss
+/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
+
+.equ  Initial_spTop,  0x20000400 
+.equ  BootRAM,        0xF1E0F85F
+/**
+ * @brief  This is the code that gets called when the processor first
+ *          starts execution following a reset event. Only the absolutely
+ *          necessary set is performed, after which the application
+ *          supplied main() routine is called. 
+ * @param  None
+ * @retval : None
+*/
+
+    .section  .text.Reset_Handler
+  .weak  Reset_Handler
+  .type  Reset_Handler, %function
+Reset_Handler:  
+
+/* FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is 
+  required, then adjust the Register Addresses */
+  bl  SystemInit_ExtMemCtl
+/* restore original stack pointer */  
+  LDR r0, =_estack
+  MSR msp, r0
+/* Copy the data segment initializers from flash to SRAM */  
+  movs  r1, #0
+  b  LoopCopyDataInit
+
+CopyDataInit:
+  ldr  r3, =_sidata
+  ldr  r3, [r3, r1]
+  str  r3, [r0, r1]
+  adds  r1, r1, #4
+    
+LoopCopyDataInit:
+  ldr  r0, =_sdata
+  ldr  r3, =_edata
+  adds  r2, r0, r1
+  cmp  r2, r3
+  bcc  CopyDataInit
+  ldr  r2, =_sbss
+  b  LoopFillZerobss
+/* Zero fill the bss segment. */  
+FillZerobss:
+  movs  r3, #0
+  str  r3, [r2], #4
+    
+LoopFillZerobss:
+  ldr  r3, = _ebss
+  cmp  r2, r3
+  bcc  FillZerobss
+/* Call the application's entry point.*/
+  bl  main
+  bx  lr    
+.size  Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief  Dummy SystemInit_ExtMemCtl function 
+ * @param  None     
+ * @retval : None       
+*/
+  .section  .text.SystemInit_ExtMemCtl_Dummy,"ax",%progbits
+SystemInit_ExtMemCtl_Dummy:
+  bx  lr
+  .size  SystemInit_ExtMemCtl_Dummy, .-SystemInit_ExtMemCtl_Dummy
+
+/**
+ * @brief  This is the code that gets called when the processor receives an 
+ *         unexpected interrupt.  This simply enters an infinite loop, preserving
+ *         the system state for examination by a debugger.
+ *
+ * @param  None     
+ * @retval : None       
+*/
+    .section  .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+  b  Infinite_Loop
+  .size  Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3.  Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/    
+   .section  .isr_vector,"a",%progbits
+  .type  g_pfnVectors, %object
+  .size  g_pfnVectors, .-g_pfnVectors
+    
+    
+g_pfnVectors:
+  .word  Initial_spTop
+  .word  Reset_Handler
+  .word  NMI_Handler
+  .word  HardFault_Handler
+  .word  MemManage_Handler
+  .word  BusFault_Handler
+  .word  UsageFault_Handler
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  SVC_Handler
+  .word  DebugMon_Handler
+  .word  0
+  .word  PendSV_Handler
+  .word  SysTick_Handler
+  .word  WWDG_IRQHandler
+  .word  PVD_IRQHandler
+  .word  TAMPER_IRQHandler
+  .word  RTC_IRQHandler
+  .word  FLASH_IRQHandler
+  .word  RCC_IRQHandler
+  .word  EXTI0_IRQHandler
+  .word  EXTI1_IRQHandler
+  .word  EXTI2_IRQHandler
+  .word  EXTI3_IRQHandler
+  .word  EXTI4_IRQHandler
+  .word  DMA1_Channel1_IRQHandler
+  .word  DMA1_Channel2_IRQHandler
+  .word  DMA1_Channel3_IRQHandler
+  .word  DMA1_Channel4_IRQHandler
+  .word  DMA1_Channel5_IRQHandler
+  .word  DMA1_Channel6_IRQHandler
+  .word  DMA1_Channel7_IRQHandler
+  .word  ADC1_2_IRQHandler
+  .word  USB_HP_CAN1_TX_IRQHandler
+  .word  USB_LP_CAN1_RX0_IRQHandler
+  .word  CAN1_RX1_IRQHandler
+  .word  CAN1_SCE_IRQHandler
+  .word  EXTI9_5_IRQHandler
+  .word  TIM1_BRK_IRQHandler
+  .word  TIM1_UP_IRQHandler
+  .word  TIM1_TRG_COM_IRQHandler
+  .word  TIM1_CC_IRQHandler
+  .word  TIM2_IRQHandler
+  .word  TIM3_IRQHandler
+  .word  TIM4_IRQHandler
+  .word  I2C1_EV_IRQHandler
+  .word  I2C1_ER_IRQHandler
+  .word  I2C2_EV_IRQHandler
+  .word  I2C2_ER_IRQHandler
+  .word  SPI1_IRQHandler
+  .word  SPI2_IRQHandler
+  .word  USART1_IRQHandler
+  .word  USART2_IRQHandler
+  .word  USART3_IRQHandler
+  .word  EXTI15_10_IRQHandler
+  .word  RTCAlarm_IRQHandler
+  .word  USBWakeUp_IRQHandler
+  .word  TIM8_BRK_IRQHandler
+  .word  TIM8_UP_IRQHandler
+  .word  TIM8_TRG_COM_IRQHandler
+  .word  TIM8_CC_IRQHandler
+  .word  ADC3_IRQHandler
+  .word  FSMC_IRQHandler
+  .word  SDIO_IRQHandler
+  .word  TIM5_IRQHandler
+  .word  SPI3_IRQHandler
+  .word  UART4_IRQHandler
+  .word  UART5_IRQHandler
+  .word  TIM6_IRQHandler
+  .word  TIM7_IRQHandler
+  .word  DMA2_Channel1_IRQHandler
+  .word  DMA2_Channel2_IRQHandler
+  .word  DMA2_Channel3_IRQHandler
+  .word  DMA2_Channel4_5_IRQHandler
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  BootRAM       /* @0x1E0. This is for boot in RAM mode for 
+                         STM32F10x High Density devices. */
+   
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler. 
+* As they are weak aliases, any function with the same name will override 
+* this definition.
+*
+*******************************************************************************/
+    
+  .weak  NMI_Handler
+  .thumb_set NMI_Handler,Default_Handler
+  
+  .weak  HardFault_Handler
+  .thumb_set HardFault_Handler,Default_Handler
+  
+  .weak  MemManage_Handler
+  .thumb_set MemManage_Handler,Default_Handler
+  
+  .weak  BusFault_Handler
+  .thumb_set BusFault_Handler,Default_Handler
+
+  .weak  UsageFault_Handler
+  .thumb_set UsageFault_Handler,Default_Handler
+
+  .weak  SVC_Handler
+  .thumb_set SVC_Handler,Default_Handler
+
+  .weak  DebugMon_Handler
+  .thumb_set DebugMon_Handler,Default_Handler
+
+  .weak  PendSV_Handler
+  .thumb_set PendSV_Handler,Default_Handler
+
+  .weak  SysTick_Handler
+  .thumb_set SysTick_Handler,Default_Handler
+
+  .weak  WWDG_IRQHandler
+  .thumb_set WWDG_IRQHandler,Default_Handler
+
+  .weak  PVD_IRQHandler
+  .thumb_set PVD_IRQHandler,Default_Handler
+
+  .weak  TAMPER_IRQHandler
+  .thumb_set TAMPER_IRQHandler,Default_Handler
+
+  .weak  RTC_IRQHandler
+  .thumb_set RTC_IRQHandler,Default_Handler
+
+  .weak  FLASH_IRQHandler
+  .thumb_set FLASH_IRQHandler,Default_Handler
+
+  .weak  RCC_IRQHandler
+  .thumb_set RCC_IRQHandler,Default_Handler
+
+  .weak  EXTI0_IRQHandler
+  .thumb_set EXTI0_IRQHandler,Default_Handler
+
+  .weak  EXTI1_IRQHandler
+  .thumb_set EXTI1_IRQHandler,Default_Handler
+
+  .weak  EXTI2_IRQHandler
+  .thumb_set EXTI2_IRQHandler,Default_Handler
+
+  .weak  EXTI3_IRQHandler
+  .thumb_set EXTI3_IRQHandler,Default_Handler
+
+  .weak  EXTI4_IRQHandler
+  .thumb_set EXTI4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel1_IRQHandler
+  .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel2_IRQHandler
+  .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel3_IRQHandler
+  .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel4_IRQHandler
+  .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel5_IRQHandler
+  .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel6_IRQHandler
+  .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel7_IRQHandler
+  .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+  .weak  ADC1_2_IRQHandler
+  .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+  .weak  USB_HP_CAN1_TX_IRQHandler
+  .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
+
+  .weak  USB_LP_CAN1_RX0_IRQHandler
+  .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
+
+  .weak  CAN1_RX1_IRQHandler
+  .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+  .weak  CAN1_SCE_IRQHandler
+  .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+  .weak  EXTI9_5_IRQHandler
+  .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+  .weak  TIM1_BRK_IRQHandler
+  .thumb_set TIM1_BRK_IRQHandler,Default_Handler
+
+  .weak  TIM1_UP_IRQHandler
+  .thumb_set TIM1_UP_IRQHandler,Default_Handler
+
+  .weak  TIM1_TRG_COM_IRQHandler
+  .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+  .weak  TIM1_CC_IRQHandler
+  .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+  .weak  TIM2_IRQHandler
+  .thumb_set TIM2_IRQHandler,Default_Handler
+
+  .weak  TIM3_IRQHandler
+  .thumb_set TIM3_IRQHandler,Default_Handler
+
+  .weak  TIM4_IRQHandler
+  .thumb_set TIM4_IRQHandler,Default_Handler
+
+  .weak  I2C1_EV_IRQHandler
+  .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+  .weak  I2C1_ER_IRQHandler
+  .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+  .weak  I2C2_EV_IRQHandler
+  .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+  .weak  I2C2_ER_IRQHandler
+  .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+  .weak  SPI1_IRQHandler
+  .thumb_set SPI1_IRQHandler,Default_Handler
+
+  .weak  SPI2_IRQHandler
+  .thumb_set SPI2_IRQHandler,Default_Handler
+
+  .weak  USART1_IRQHandler
+  .thumb_set USART1_IRQHandler,Default_Handler
+
+  .weak  USART2_IRQHandler
+  .thumb_set USART2_IRQHandler,Default_Handler
+
+  .weak  USART3_IRQHandler
+  .thumb_set USART3_IRQHandler,Default_Handler
+
+  .weak  EXTI15_10_IRQHandler
+  .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+  .weak  RTCAlarm_IRQHandler
+  .thumb_set RTCAlarm_IRQHandler,Default_Handler
+
+  .weak  USBWakeUp_IRQHandler
+  .thumb_set USBWakeUp_IRQHandler,Default_Handler
+
+  .weak  TIM8_BRK_IRQHandler
+  .thumb_set TIM8_BRK_IRQHandler,Default_Handler
+
+  .weak  TIM8_UP_IRQHandler
+  .thumb_set TIM8_UP_IRQHandler,Default_Handler
+
+  .weak  TIM8_TRG_COM_IRQHandler
+  .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
+
+  .weak  TIM8_CC_IRQHandler
+  .thumb_set TIM8_CC_IRQHandler,Default_Handler
+
+  .weak  ADC3_IRQHandler
+  .thumb_set ADC3_IRQHandler,Default_Handler
+
+  .weak  FSMC_IRQHandler
+  .thumb_set FSMC_IRQHandler,Default_Handler
+
+  .weak  SDIO_IRQHandler
+  .thumb_set SDIO_IRQHandler,Default_Handler
+
+  .weak  TIM5_IRQHandler
+  .thumb_set TIM5_IRQHandler,Default_Handler
+
+  .weak  SPI3_IRQHandler
+  .thumb_set SPI3_IRQHandler,Default_Handler
+
+  .weak  UART4_IRQHandler
+  .thumb_set UART4_IRQHandler,Default_Handler
+
+  .weak  UART5_IRQHandler
+  .thumb_set UART5_IRQHandler,Default_Handler
+
+  .weak  TIM6_IRQHandler
+  .thumb_set TIM6_IRQHandler,Default_Handler
+
+  .weak  TIM7_IRQHandler
+  .thumb_set TIM7_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel1_IRQHandler
+  .thumb_set DMA2_Channel1_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel2_IRQHandler
+  .thumb_set DMA2_Channel2_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel3_IRQHandler
+  .thumb_set DMA2_Channel3_IRQHandler,Default_Handler
+
+  .weak  DMA2_Channel4_5_IRQHandler
+  .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler
+
+  .weak  SystemInit_ExtMemCtl
+  .thumb_set SystemInit_ExtMemCtl,SystemInit_ExtMemCtl_Dummy
+
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s
new file mode 100644
index 0000000000000000000000000000000000000000..373f94cc6ab0af51ee31a6dd18ae7194abad3357
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s
@@ -0,0 +1,339 @@
+/**
+  ******************************************************************************
+  * @file      startup_stm32f10x_ld.s
+  * @author    MCD Application Team
+  * @version   V3.1.2
+  * @date      09/28/2009
+  * @brief     STM32F10x Low Density Devices vector table for RIDE7 toolchain.
+  *            This module performs:
+  *                - Set the initial SP
+  *                - Set the initial PC == Reset_Handler,
+  *                - Set the vector table entries with the exceptions ISR address.
+  *                - Branches to main in the C library (which eventually
+  *                  calls main()).
+  *            After Reset the Cortex-M3 processor is in Thread mode,
+  *            priority is Privileged, and the Stack is set to Main.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */  
+    
+  .syntax unified
+  .cpu cortex-m3
+  .fpu softvfp
+  .thumb
+
+.global  g_pfnVectors
+.global  Default_Handler
+
+/* start address for the initialization values of the .data section. 
+defined in linker script */
+.word  _sidata
+/* start address for the .data section. defined in linker script */  
+.word  _sdata
+/* end address for the .data section. defined in linker script */
+.word  _edata
+/* start address for the .bss section. defined in linker script */
+.word  _sbss
+/* end address for the .bss section. defined in linker script */
+.word  _ebss
+
+.equ  BootRAM, 0xF108F85F
+/**
+ * @brief  This is the code that gets called when the processor first
+ *          starts execution following a reset event. Only the absolutely
+ *          necessary set is performed, after which the application
+ *          supplied main() routine is called. 
+ * @param  None
+ * @retval : None
+*/
+
+    .section  .text.Reset_Handler
+  .weak  Reset_Handler
+  .type  Reset_Handler, %function
+Reset_Handler:  
+
+/* Copy the data segment initializers from flash to SRAM */  
+  movs  r1, #0
+  b  LoopCopyDataInit
+
+CopyDataInit:
+  ldr  r3, =_sidata
+  ldr  r3, [r3, r1]
+  str  r3, [r0, r1]
+  adds  r1, r1, #4
+    
+LoopCopyDataInit:
+  ldr  r0, =_sdata
+  ldr  r3, =_edata
+  adds  r2, r0, r1
+  cmp  r2, r3
+  bcc  CopyDataInit
+  ldr  r2, =_sbss
+  b  LoopFillZerobss
+/* Zero fill the bss segment. */  
+FillZerobss:
+  movs  r3, #0
+  str  r3, [r2], #4
+    
+LoopFillZerobss:
+  ldr  r3, = _ebss
+  cmp  r2, r3
+  bcc  FillZerobss
+/* Call the application's entry point.*/
+  bl  main
+  bx  lr    
+.size  Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief  This is the code that gets called when the processor receives an 
+ *         unexpected interrupt.  This simply enters an infinite loop, preserving
+ *         the system state for examination by a debugger.
+ *
+ * @param  None     
+ * @retval : None       
+*/
+    .section  .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+  b  Infinite_Loop
+  .size  Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3.  Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/    
+   .section  .isr_vector,"a",%progbits
+  .type  g_pfnVectors, %object
+  .size  g_pfnVectors, .-g_pfnVectors
+    
+    
+g_pfnVectors:
+  .word  _estack
+  .word  Reset_Handler
+  .word  NMI_Handler
+  .word  HardFault_Handler
+  .word  MemManage_Handler
+  .word  BusFault_Handler
+  .word  UsageFault_Handler
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  SVC_Handler
+  .word  DebugMon_Handler
+  .word  0
+  .word  PendSV_Handler
+  .word  SysTick_Handler
+  .word  WWDG_IRQHandler
+  .word  PVD_IRQHandler
+  .word  TAMPER_IRQHandler
+  .word  RTC_IRQHandler
+  .word  FLASH_IRQHandler
+  .word  RCC_IRQHandler
+  .word  EXTI0_IRQHandler
+  .word  EXTI1_IRQHandler
+  .word  EXTI2_IRQHandler
+  .word  EXTI3_IRQHandler
+  .word  EXTI4_IRQHandler
+  .word  DMA1_Channel1_IRQHandler
+  .word  DMA1_Channel2_IRQHandler
+  .word  DMA1_Channel3_IRQHandler
+  .word  DMA1_Channel4_IRQHandler
+  .word  DMA1_Channel5_IRQHandler
+  .word  DMA1_Channel6_IRQHandler
+  .word  DMA1_Channel7_IRQHandler
+  .word  ADC1_2_IRQHandler
+  .word  USB_HP_CAN1_TX_IRQHandler
+  .word  USB_LP_CAN1_RX0_IRQHandler
+  .word  CAN1_RX1_IRQHandler
+  .word  CAN1_SCE_IRQHandler
+  .word  EXTI9_5_IRQHandler
+  .word  TIM1_BRK_IRQHandler
+  .word  TIM1_UP_IRQHandler
+  .word  TIM1_TRG_COM_IRQHandler
+  .word  TIM1_CC_IRQHandler
+  .word  TIM2_IRQHandler
+  .word  TIM3_IRQHandler
+  0
+  .word  I2C1_EV_IRQHandler
+  .word  I2C1_ER_IRQHandler
+  0
+  0
+  .word  SPI1_IRQHandler
+  0
+  .word  USART1_IRQHandler
+  .word  USART2_IRQHandler
+  0
+  .word  EXTI15_10_IRQHandler
+  .word  RTCAlarm_IRQHandler
+  .word  USBWakeUp_IRQHandler  
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  BootRAM        /* @0x108. This is for boot in RAM mode for 
+                          STM32F10x Low Density devices.*/
+   
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler. 
+* As they are weak aliases, any function with the same name will override 
+* this definition.
+*
+*******************************************************************************/
+    
+  .weak  NMI_Handler
+  .thumb_set NMI_Handler,Default_Handler
+  
+  .weak  HardFault_Handler
+  .thumb_set HardFault_Handler,Default_Handler
+  
+  .weak  MemManage_Handler
+  .thumb_set MemManage_Handler,Default_Handler
+  
+  .weak  BusFault_Handler
+  .thumb_set BusFault_Handler,Default_Handler
+
+  .weak  UsageFault_Handler
+  .thumb_set UsageFault_Handler,Default_Handler
+
+  .weak  SVC_Handler
+  .thumb_set SVC_Handler,Default_Handler
+
+  .weak  DebugMon_Handler
+  .thumb_set DebugMon_Handler,Default_Handler
+
+  .weak  PendSV_Handler
+  .thumb_set PendSV_Handler,Default_Handler
+
+  .weak  SysTick_Handler
+  .thumb_set SysTick_Handler,Default_Handler
+
+  .weak  WWDG_IRQHandler
+  .thumb_set WWDG_IRQHandler,Default_Handler
+
+  .weak  PVD_IRQHandler
+  .thumb_set PVD_IRQHandler,Default_Handler
+
+  .weak  TAMPER_IRQHandler
+  .thumb_set TAMPER_IRQHandler,Default_Handler
+
+  .weak  RTC_IRQHandler
+  .thumb_set RTC_IRQHandler,Default_Handler
+
+  .weak  FLASH_IRQHandler
+  .thumb_set FLASH_IRQHandler,Default_Handler
+
+  .weak  RCC_IRQHandler
+  .thumb_set RCC_IRQHandler,Default_Handler
+
+  .weak  EXTI0_IRQHandler
+  .thumb_set EXTI0_IRQHandler,Default_Handler
+
+  .weak  EXTI1_IRQHandler
+  .thumb_set EXTI1_IRQHandler,Default_Handler
+
+  .weak  EXTI2_IRQHandler
+  .thumb_set EXTI2_IRQHandler,Default_Handler
+
+  .weak  EXTI3_IRQHandler
+  .thumb_set EXTI3_IRQHandler,Default_Handler
+
+  .weak  EXTI4_IRQHandler
+  .thumb_set EXTI4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel1_IRQHandler
+  .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel2_IRQHandler
+  .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel3_IRQHandler
+  .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel4_IRQHandler
+  .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel5_IRQHandler
+  .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel6_IRQHandler
+  .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel7_IRQHandler
+  .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+  .weak  ADC1_2_IRQHandler
+  .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+  .weak  USB_HP_CAN1_TX_IRQHandler
+  .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
+
+  .weak  USB_LP_CAN1_RX0_IRQHandler
+  .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
+
+  .weak  CAN1_RX1_IRQHandler
+  .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+  .weak  CAN1_SCE_IRQHandler
+  .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+  .weak  EXTI9_5_IRQHandler
+  .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+  .weak  TIM1_BRK_IRQHandler
+  .thumb_set TIM1_BRK_IRQHandler,Default_Handler
+
+  .weak  TIM1_UP_IRQHandler
+  .thumb_set TIM1_UP_IRQHandler,Default_Handler
+
+  .weak  TIM1_TRG_COM_IRQHandler
+  .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+  .weak  TIM1_CC_IRQHandler
+  .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+  .weak  TIM2_IRQHandler
+  .thumb_set TIM2_IRQHandler,Default_Handler
+
+  .weak  TIM3_IRQHandler
+  .thumb_set TIM3_IRQHandler,Default_Handler
+
+  .weak  I2C1_EV_IRQHandler
+  .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+  .weak  I2C1_ER_IRQHandler
+  .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+  .weak  SPI1_IRQHandler
+  .thumb_set SPI1_IRQHandler,Default_Handler
+
+  .weak  USART1_IRQHandler
+  .thumb_set USART1_IRQHandler,Default_Handler
+
+  .weak  USART2_IRQHandler
+  .thumb_set USART2_IRQHandler,Default_Handler
+
+  .weak  EXTI15_10_IRQHandler
+  .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+  .weak  RTCAlarm_IRQHandler
+  .thumb_set RTCAlarm_IRQHandler,Default_Handler
+
+  .weak  USBWakeUp_IRQHandler
+  .thumb_set USBWakeUp_IRQHandler,Default_Handler  
+
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s
new file mode 100644
index 0000000000000000000000000000000000000000..5bf5827962e46bced35ea7632d8ca6ecef12d730
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s
@@ -0,0 +1,371 @@
+/**
+  ******************************************************************************
+  * @file      startup_stm32f10x_md.s
+  * @author    MCD Application Team
+  * @version   V3.1.2
+  * @date      09/28/2009
+  * @brief     STM32F10x Medium Density Devices vector table for RIDE7 toolchain.
+  *            This module performs:
+  *                - Set the initial SP
+  *                - Set the initial PC == Reset_Handler,
+  *                - Set the vector table entries with the exceptions ISR address
+  *                - Branches to main in the C library (which eventually
+  *                  calls main()).
+  *            After Reset the Cortex-M3 processor is in Thread mode,
+  *            priority is Privileged, and the Stack is set to Main.
+  *******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */  
+    
+  .syntax unified
+  .cpu cortex-m3
+  .fpu softvfp
+  .thumb
+
+#include "stm32f10x.h"
+
+.global  g_pfnVectors
+.global  Default_Handler
+
+/* start address for the initialization values of the .data section. 
+defined in linker script */
+.word  _sidata
+/* start address for the .data section. defined in linker script */  
+.word  _sdata
+/* end address for the .data section. defined in linker script */
+.word  _edata
+/* start address for the .bss section. defined in linker script */
+.word  _sbss
+/* end address for the .bss section. defined in linker script */
+.word  _ebss
+
+.equ  BootRAM, 0xF108F85F
+/**
+ * @brief  This is the code that gets called when the processor first
+ *          starts execution following a reset event. Only the absolutely
+ *          necessary set is performed, after which the application
+ *          supplied main() routine is called. 
+ * @param  None
+ * @retval : None
+*/
+
+    .section  .text.Reset_Handler
+  .weak  Reset_Handler
+  .type  Reset_Handler, %function
+Reset_Handler:  
+/* Power the AFIO block 
+  mov   r1, #0x01
+  movw  r0, #(0x1000+0x18)
+  movt  r0, #(0x4000+0x2)
+  str   r1, [r0]*/
+
+/* Disable the JTAG NJRST pin 
+  mov   r1, #0x01000000
+  mov   r0, #(0x0000+0x04)
+  movt  r0, #(0x4000+0x1)
+  str   r1, [r0]*/
+
+/* Copy the data segment initializers from flash to SRAM */  
+  movs  r1, #0
+  b  LoopCopyDataInit
+
+CopyDataInit:
+  ldr  r3, =_sidata
+  ldr  r3, [r3, r1]
+  str  r3, [r0, r1]
+  adds  r1, r1, #4
+    
+LoopCopyDataInit:
+  ldr  r0, =_sdata
+  ldr  r3, =_edata
+  adds  r2, r0, r1
+  cmp  r2, r3
+  bcc  CopyDataInit
+  ldr  r2, =_sbss
+  b  LoopFillZerobss
+/* Zero fill the bss segment. */  
+FillZerobss:
+  movs  r3, #0
+  str  r3, [r2], #4
+    
+LoopFillZerobss:
+  ldr  r3, = _ebss
+  cmp  r2, r3
+  bcc  FillZerobss
+
+/* Call the clock system intitialization function.*/
+  bl  SystemInit
+/* Call the application's entry point.*/
+  bl  main
+  bx  lr    
+.size  Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief  This is the code that gets called when the processor receives an 
+ *         unexpected interrupt.  This simply enters an infinite loop, preserving
+ *         the system state for examination by a debugger.
+ *
+ * @param  None     
+ * @retval : None       
+*/
+    .section  .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+  b  Infinite_Loop
+  .size  Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3.  Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/    
+   .section  .isr_vector,"a",%progbits
+  .type  g_pfnVectors, %object
+  .size  g_pfnVectors, .-g_pfnVectors
+    
+    
+g_pfnVectors:
+  .word  _estack
+  .word  Reset_Handler
+  .word  NMI_Handler
+  .word  HardFault_Handler
+  .word  MemManage_Handler
+  .word  BusFault_Handler
+  .word  UsageFault_Handler
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  SVC_Handler
+  .word  DebugMon_Handler
+  .word  0
+  .word  PendSV_Handler
+  .word  SysTick_Handler
+  .word  WWDG_IRQHandler
+  .word  PVD_IRQHandler
+  .word  TAMPER_IRQHandler
+  .word  RTC_IRQHandler
+  .word  FLASH_IRQHandler
+  .word  RCC_IRQHandler
+  .word  EXTI0_IRQHandler
+  .word  EXTI1_IRQHandler
+  .word  EXTI2_IRQHandler
+  .word  EXTI3_IRQHandler
+  .word  EXTI4_IRQHandler
+  .word  DMA1_Channel1_IRQHandler
+  .word  DMA1_Channel2_IRQHandler
+  .word  DMA1_Channel3_IRQHandler
+  .word  DMA1_Channel4_IRQHandler
+  .word  DMA1_Channel5_IRQHandler
+  .word  DMA1_Channel6_IRQHandler
+  .word  DMA1_Channel7_IRQHandler
+  .word  ADC1_2_IRQHandler
+  .word  USB_HP_CAN1_TX_IRQHandler
+  .word  USB_LP_CAN1_RX0_IRQHandler
+  .word  CAN1_RX1_IRQHandler
+  .word  CAN1_SCE_IRQHandler
+  .word  EXTI9_5_IRQHandler
+  .word  TIM1_BRK_IRQHandler
+  .word  TIM1_UP_IRQHandler
+  .word  TIM1_TRG_COM_IRQHandler
+  .word  TIM1_CC_IRQHandler
+  .word  TIM2_IRQHandler
+  .word  TIM3_IRQHandler
+  .word  TIM4_IRQHandler
+  .word  I2C1_EV_IRQHandler
+  .word  I2C1_ER_IRQHandler
+  .word  I2C2_EV_IRQHandler
+  .word  I2C2_ER_IRQHandler
+  .word  SPI1_IRQHandler
+  .word  SPI2_IRQHandler
+  .word  USART1_IRQHandler
+  .word  USART2_IRQHandler
+  .word  USART3_IRQHandler
+  .word  EXTI15_10_IRQHandler
+  .word  RTCAlarm_IRQHandler
+  .word  USBWakeUp_IRQHandler  
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  BootRAM          /* @0x108. This is for boot in RAM mode for 
+                            STM32F10x Medium Density devices. */
+   
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler. 
+* As they are weak aliases, any function with the same name will override 
+* this definition.
+*
+*******************************************************************************/
+    
+  .weak  NMI_Handler
+  .thumb_set NMI_Handler,Default_Handler
+  
+  .weak  HardFault_Handler
+  .thumb_set HardFault_Handler,Default_Handler
+  
+  .weak  MemManage_Handler
+  .thumb_set MemManage_Handler,Default_Handler
+  
+  .weak  BusFault_Handler
+  .thumb_set BusFault_Handler,Default_Handler
+
+  .weak  UsageFault_Handler
+  .thumb_set UsageFault_Handler,Default_Handler
+
+  .weak  SVC_Handler
+  .thumb_set SVC_Handler,Default_Handler
+
+  .weak  DebugMon_Handler
+  .thumb_set DebugMon_Handler,Default_Handler
+
+  .weak  PendSV_Handler
+  .thumb_set PendSV_Handler,Default_Handler
+
+  .weak  SysTick_Handler
+  .thumb_set SysTick_Handler,Default_Handler
+
+  .weak  WWDG_IRQHandler
+  .thumb_set WWDG_IRQHandler,Default_Handler
+
+  .weak  PVD_IRQHandler
+  .thumb_set PVD_IRQHandler,Default_Handler
+
+  .weak  TAMPER_IRQHandler
+  .thumb_set TAMPER_IRQHandler,Default_Handler
+
+  .weak  RTC_IRQHandler
+  .thumb_set RTC_IRQHandler,Default_Handler
+
+  .weak  FLASH_IRQHandler
+  .thumb_set FLASH_IRQHandler,Default_Handler
+
+  .weak  RCC_IRQHandler
+  .thumb_set RCC_IRQHandler,Default_Handler
+
+  .weak  EXTI0_IRQHandler
+  .thumb_set EXTI0_IRQHandler,Default_Handler
+
+  .weak  EXTI1_IRQHandler
+  .thumb_set EXTI1_IRQHandler,Default_Handler
+
+  .weak  EXTI2_IRQHandler
+  .thumb_set EXTI2_IRQHandler,Default_Handler
+
+  .weak  EXTI3_IRQHandler
+  .thumb_set EXTI3_IRQHandler,Default_Handler
+
+  .weak  EXTI4_IRQHandler
+  .thumb_set EXTI4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel1_IRQHandler
+  .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel2_IRQHandler
+  .thumb_set DMA1_Channel2_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel3_IRQHandler
+  .thumb_set DMA1_Channel3_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel4_IRQHandler
+  .thumb_set DMA1_Channel4_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel5_IRQHandler
+  .thumb_set DMA1_Channel5_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel6_IRQHandler
+  .thumb_set DMA1_Channel6_IRQHandler,Default_Handler
+
+  .weak  DMA1_Channel7_IRQHandler
+  .thumb_set DMA1_Channel7_IRQHandler,Default_Handler
+
+  .weak  ADC1_2_IRQHandler
+  .thumb_set ADC1_2_IRQHandler,Default_Handler
+
+  .weak  USB_HP_CAN1_TX_IRQHandler
+  .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler
+
+  .weak  USB_LP_CAN1_RX0_IRQHandler
+  .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler
+
+  .weak  CAN1_RX1_IRQHandler
+  .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+
+  .weak  CAN1_SCE_IRQHandler
+  .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+
+  .weak  EXTI9_5_IRQHandler
+  .thumb_set EXTI9_5_IRQHandler,Default_Handler
+
+  .weak  TIM1_BRK_IRQHandler
+  .thumb_set TIM1_BRK_IRQHandler,Default_Handler
+
+  .weak  TIM1_UP_IRQHandler
+  .thumb_set TIM1_UP_IRQHandler,Default_Handler
+
+  .weak  TIM1_TRG_COM_IRQHandler
+  .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
+
+  .weak  TIM1_CC_IRQHandler
+  .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+  .weak  TIM2_IRQHandler
+  .thumb_set TIM2_IRQHandler,Default_Handler
+
+  .weak  TIM3_IRQHandler
+  .thumb_set TIM3_IRQHandler,Default_Handler
+
+  .weak  TIM4_IRQHandler
+  .thumb_set TIM4_IRQHandler,Default_Handler
+
+  .weak  I2C1_EV_IRQHandler
+  .thumb_set I2C1_EV_IRQHandler,Default_Handler
+
+  .weak  I2C1_ER_IRQHandler
+  .thumb_set I2C1_ER_IRQHandler,Default_Handler
+
+  .weak  I2C2_EV_IRQHandler
+  .thumb_set I2C2_EV_IRQHandler,Default_Handler
+
+  .weak  I2C2_ER_IRQHandler
+  .thumb_set I2C2_ER_IRQHandler,Default_Handler
+
+  .weak  SPI1_IRQHandler
+  .thumb_set SPI1_IRQHandler,Default_Handler
+
+  .weak  SPI2_IRQHandler
+  .thumb_set SPI2_IRQHandler,Default_Handler
+
+  .weak  USART1_IRQHandler
+  .thumb_set USART1_IRQHandler,Default_Handler
+
+  .weak  USART2_IRQHandler
+  .thumb_set USART2_IRQHandler,Default_Handler
+
+  .weak  USART3_IRQHandler
+  .thumb_set USART3_IRQHandler,Default_Handler
+
+  .weak  EXTI15_10_IRQHandler
+  .thumb_set EXTI15_10_IRQHandler,Default_Handler
+
+  .weak  RTCAlarm_IRQHandler
+  .thumb_set RTCAlarm_IRQHandler,Default_Handler
+
+  .weak  USBWakeUp_IRQHandler
+  .thumb_set USBWakeUp_IRQHandler,Default_Handler
+
+
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_cl.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_cl.s
new file mode 100644
index 0000000000000000000000000000000000000000..42c5fd920f0701f2d9f7cbf3bcd0283af002fc07
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_cl.s
@@ -0,0 +1,498 @@
+;/******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_cl.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x Connectivity line devices vector table for 
+;*                      EWARM5.x toolchain.
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == __iar_program_start,
+;*                      - Set the vector table entries with the exceptions ISR 
+;*                        address.
+;*                      After Reset the Cortex-M3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;********************************************************************************
+;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************/
+;
+;
+; The modules in this file are included in the libraries, and may be replaced
+; by any user-defined modules that define the PUBLIC symbol _program_start or
+; a user defined start symbol.
+; To override the cstartup defined in the library, simply add your modified
+; version to the workbench project.
+;
+; The vector table is normally located at address 0.
+; When debugging in RAM, it can be located in RAM, aligned to at least 2^6.
+; The name "__vector_table" has special meaning for C-SPY:
+; it is where the SP start value is found, and the NVIC vector
+; table register (VTOR) is initialized to this address if != 0.
+;
+; Cortex-M version
+;
+
+        MODULE  ?cstartup
+
+        ;; Forward declaration of sections.
+        SECTION CSTACK:DATA:NOROOT(3)
+
+        SECTION .intvec:CODE:NOROOT(2)
+
+        EXTERN  __iar_program_start
+        PUBLIC  __vector_table
+
+        DATA
+__vector_table
+        DCD     sfe(CSTACK)
+        DCD     __iar_program_start
+
+        DCD     NMI_Handler               ; NMI Handler
+        DCD     HardFault_Handler         ; Hard Fault Handler
+        DCD     MemManage_Handler         ; MPU Fault Handler
+        DCD     BusFault_Handler          ; Bus Fault Handler
+        DCD     UsageFault_Handler        ; Usage Fault Handler
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     SVC_Handler               ; SVCall Handler
+        DCD     DebugMon_Handler          ; Debug Monitor Handler
+        DCD     0                         ; Reserved
+        DCD     PendSV_Handler            ; PendSV Handler
+        DCD     SysTick_Handler           ; SysTick Handler
+
+         ; External Interrupts
+        DCD     WWDG_IRQHandler            ; Window Watchdog
+        DCD     PVD_IRQHandler             ; PVD through EXTI Line detect
+        DCD     TAMPER_IRQHandler          ; Tamper
+        DCD     RTC_IRQHandler             ; RTC
+        DCD     FLASH_IRQHandler           ; Flash
+        DCD     RCC_IRQHandler             ; RCC
+        DCD     EXTI0_IRQHandler           ; EXTI Line 0
+        DCD     EXTI1_IRQHandler           ; EXTI Line 1
+        DCD     EXTI2_IRQHandler           ; EXTI Line 2
+        DCD     EXTI3_IRQHandler           ; EXTI Line 3
+        DCD     EXTI4_IRQHandler           ; EXTI Line 4
+        DCD     DMA1_Channel1_IRQHandler   ; DMA1 Channel 1
+        DCD     DMA1_Channel2_IRQHandler   ; DMA1 Channel 2
+        DCD     DMA1_Channel3_IRQHandler   ; DMA1 Channel 3
+        DCD     DMA1_Channel4_IRQHandler   ; DMA1 Channel 4
+        DCD     DMA1_Channel5_IRQHandler   ; DMA1 Channel 5
+        DCD     DMA1_Channel6_IRQHandler   ; DMA1 Channel 6
+        DCD     DMA1_Channel7_IRQHandler   ; DMA1 Channel 7
+        DCD     ADC1_2_IRQHandler          ; ADC1 and ADC2
+        DCD     CAN1_TX_IRQHandler         ; CAN1 TX
+        DCD     CAN1_RX0_IRQHandler        ; CAN1 RX0
+        DCD     CAN1_RX1_IRQHandler        ; CAN1 RX1
+        DCD     CAN1_SCE_IRQHandler        ; CAN1 SCE
+        DCD     EXTI9_5_IRQHandler         ; EXTI Line 9..5
+        DCD     TIM1_BRK_IRQHandler        ; TIM1 Break
+        DCD     TIM1_UP_IRQHandler         ; TIM1 Update
+        DCD     TIM1_TRG_COM_IRQHandler    ; TIM1 Trigger and Commutation
+        DCD     TIM1_CC_IRQHandler         ; TIM1 Capture Compare
+        DCD     TIM2_IRQHandler            ; TIM2
+        DCD     TIM3_IRQHandler            ; TIM3
+        DCD     TIM4_IRQHandler            ; TIM4
+        DCD     I2C1_EV_IRQHandler         ; I2C1 Event
+        DCD     I2C1_ER_IRQHandler         ; I2C1 Error
+        DCD     I2C2_EV_IRQHandler         ; I2C2 Event
+        DCD     I2C2_ER_IRQHandler         ; I2C1 Error
+        DCD     SPI1_IRQHandler            ; SPI1
+        DCD     SPI2_IRQHandler            ; SPI2
+        DCD     USART1_IRQHandler          ; USART1
+        DCD     USART2_IRQHandler          ; USART2
+        DCD     USART3_IRQHandler          ; USART3
+        DCD     EXTI15_10_IRQHandler       ; EXTI Line 15..10
+        DCD     RTCAlarm_IRQHandler        ; RTC alarm through EXTI line
+        DCD     OTG_FS_WKUP_IRQHandler     ; USB OTG FS Wakeup through EXTI line
+        DCD     0                          ; Reserved
+        DCD     0                          ; Reserved
+        DCD     0                          ; Reserved
+        DCD     0                          ; Reserved
+        DCD     0                          ; Reserved
+        DCD     0                          ; Reserved
+        DCD     0                          ; Reserved
+        DCD     TIM5_IRQHandler            ; TIM5
+        DCD     SPI3_IRQHandler            ; SPI3
+        DCD     UART4_IRQHandler           ; UART4
+        DCD     UART5_IRQHandler           ; UART5
+        DCD     TIM6_IRQHandler            ; TIM6
+        DCD     TIM7_IRQHandler            ; TIM7
+        DCD     DMA2_Channel1_IRQHandler   ; DMA2 Channel1
+        DCD     DMA2_Channel2_IRQHandler   ; DMA2 Channel2
+        DCD     DMA2_Channel3_IRQHandler   ; DMA2 Channel3
+        DCD     DMA2_Channel4_IRQHandler   ; DMA2 Channel4
+        DCD     DMA2_Channel5_IRQHandler   ; DMA2 Channel5
+        DCD     ETH_IRQHandler             ; Ethernet
+        DCD     ETH_WKUP_IRQHandler        ; Ethernet Wakeup through EXTI line
+        DCD     CAN2_TX_IRQHandler         ; CAN2 TX
+        DCD     CAN2_RX0_IRQHandler        ; CAN2 RX0
+        DCD     CAN2_RX1_IRQHandler        ; CAN2 RX1
+        DCD     CAN2_SCE_IRQHandler        ; CAN2 SCE
+        DCD     OTG_FS_IRQHandler          ; USB OTG FS
+
+;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
+;;
+;; Default interrupt handlers.
+;;
+        THUMB
+
+        PUBWEAK NMI_Handler
+        SECTION .text:CODE:REORDER(1)
+NMI_Handler
+        B NMI_Handler
+
+        PUBWEAK HardFault_Handler
+        SECTION .text:CODE:REORDER(1)
+HardFault_Handler
+        B HardFault_Handler
+
+        PUBWEAK MemManage_Handler
+        SECTION .text:CODE:REORDER(1)
+MemManage_Handler
+        B MemManage_Handler
+
+        PUBWEAK BusFault_Handler
+        SECTION .text:CODE:REORDER(1)
+BusFault_Handler
+        B BusFault_Handler
+
+        PUBWEAK UsageFault_Handler
+        SECTION .text:CODE:REORDER(1)
+UsageFault_Handler
+        B UsageFault_Handler
+
+        PUBWEAK SVC_Handler
+        SECTION .text:CODE:REORDER(1)
+SVC_Handler
+        B SVC_Handler
+
+        PUBWEAK DebugMon_Handler
+        SECTION .text:CODE:REORDER(1)
+DebugMon_Handler
+        B DebugMon_Handler
+
+        PUBWEAK PendSV_Handler
+        SECTION .text:CODE:REORDER(1)
+PendSV_Handler
+        B PendSV_Handler
+
+        PUBWEAK SysTick_Handler
+        SECTION .text:CODE:REORDER(1)
+SysTick_Handler
+        B SysTick_Handler
+
+        PUBWEAK WWDG_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+WWDG_IRQHandler
+        B WWDG_IRQHandler
+
+        PUBWEAK PVD_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+PVD_IRQHandler
+        B PVD_IRQHandler
+
+        PUBWEAK TAMPER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TAMPER_IRQHandler
+        B TAMPER_IRQHandler
+
+        PUBWEAK RTC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTC_IRQHandler
+        B RTC_IRQHandler
+
+        PUBWEAK FLASH_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+FLASH_IRQHandler
+        B FLASH_IRQHandler
+
+        PUBWEAK RCC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RCC_IRQHandler
+        B RCC_IRQHandler
+
+        PUBWEAK EXTI0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI0_IRQHandler
+        B EXTI0_IRQHandler
+
+        PUBWEAK EXTI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI1_IRQHandler
+        B EXTI1_IRQHandler
+
+        PUBWEAK EXTI2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI2_IRQHandler
+        B EXTI2_IRQHandler
+
+        PUBWEAK EXTI3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI3_IRQHandler
+        B EXTI3_IRQHandler
+
+
+        PUBWEAK EXTI4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI4_IRQHandler
+        B EXTI4_IRQHandler
+
+        PUBWEAK DMA1_Channel1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel1_IRQHandler
+        B DMA1_Channel1_IRQHandler
+
+        PUBWEAK DMA1_Channel2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel2_IRQHandler
+        B DMA1_Channel2_IRQHandler
+
+        PUBWEAK DMA1_Channel3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel3_IRQHandler
+        B DMA1_Channel3_IRQHandler
+
+        PUBWEAK DMA1_Channel4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel4_IRQHandler
+        B DMA1_Channel4_IRQHandler
+
+        PUBWEAK DMA1_Channel5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel5_IRQHandler
+        B DMA1_Channel5_IRQHandler
+
+        PUBWEAK DMA1_Channel6_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel6_IRQHandler
+        B DMA1_Channel6_IRQHandler
+
+        PUBWEAK DMA1_Channel7_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel7_IRQHandler
+        B DMA1_Channel7_IRQHandler
+
+        PUBWEAK ADC1_2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+ADC1_2_IRQHandler
+        B ADC1_2_IRQHandler
+
+        PUBWEAK CAN1_TX_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_TX_IRQHandler
+        B CAN1_TX_IRQHandler
+
+        PUBWEAK CAN1_RX0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_RX0_IRQHandler
+        B CAN1_RX0_IRQHandler
+
+        PUBWEAK CAN1_RX1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_RX1_IRQHandler
+        B CAN1_RX1_IRQHandler
+
+        PUBWEAK CAN1_SCE_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_SCE_IRQHandler
+        B CAN1_SCE_IRQHandler
+
+        PUBWEAK EXTI9_5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI9_5_IRQHandler
+        B EXTI9_5_IRQHandler
+
+        PUBWEAK TIM1_BRK_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_BRK_IRQHandler
+        B TIM1_BRK_IRQHandler
+
+        PUBWEAK TIM1_UP_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_UP_IRQHandler
+        B TIM1_UP_IRQHandler
+
+        PUBWEAK TIM1_TRG_COM_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_TRG_COM_IRQHandler
+        B TIM1_TRG_COM_IRQHandler
+
+        PUBWEAK TIM1_CC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_CC_IRQHandler
+        B TIM1_CC_IRQHandler
+
+        PUBWEAK TIM2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM2_IRQHandler
+        B TIM2_IRQHandler
+
+        PUBWEAK TIM3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM3_IRQHandler
+        B TIM3_IRQHandler
+
+        PUBWEAK TIM4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM4_IRQHandler
+        B TIM4_IRQHandler
+
+        PUBWEAK I2C1_EV_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_EV_IRQHandler
+        B I2C1_EV_IRQHandler
+
+        PUBWEAK I2C1_ER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_ER_IRQHandler
+        B I2C1_ER_IRQHandler
+
+        PUBWEAK I2C2_EV_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C2_EV_IRQHandler
+        B I2C2_EV_IRQHandler
+
+        PUBWEAK I2C2_ER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C2_ER_IRQHandler
+        B I2C2_ER_IRQHandler
+
+        PUBWEAK SPI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI1_IRQHandler
+        B SPI1_IRQHandler    
+
+        PUBWEAK SPI2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI2_IRQHandler
+        B SPI2_IRQHandler
+
+        PUBWEAK USART1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART1_IRQHandler
+        B USART1_IRQHandler
+
+        PUBWEAK USART2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART2_IRQHandler
+        B USART2_IRQHandler
+
+        PUBWEAK USART3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART3_IRQHandler
+        B USART3_IRQHandler
+
+        PUBWEAK EXTI15_10_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI15_10_IRQHandler
+        B EXTI15_10_IRQHandler
+
+        PUBWEAK RTCAlarm_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTCAlarm_IRQHandler
+        B RTCAlarm_IRQHandler
+
+        PUBWEAK OTG_FS_WKUP_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+OTG_FS_WKUP_IRQHandler
+        B OTG_FS_WKUP_IRQHandler
+
+        PUBWEAK TIM5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM5_IRQHandler
+        B TIM5_IRQHandler
+
+        PUBWEAK SPI3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI3_IRQHandler
+        B SPI3_IRQHandler
+
+        PUBWEAK UART4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+UART4_IRQHandler
+        B UART4_IRQHandler
+
+        PUBWEAK UART5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+UART5_IRQHandler
+        B UART5_IRQHandler
+
+        PUBWEAK TIM6_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM6_IRQHandler
+        B TIM6_IRQHandler
+
+        PUBWEAK TIM7_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM7_IRQHandler
+        B TIM7_IRQHandler
+
+        PUBWEAK DMA2_Channel1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel1_IRQHandler
+        B DMA2_Channel1_IRQHandler
+
+        PUBWEAK DMA2_Channel2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel2_IRQHandler
+        B DMA2_Channel2_IRQHandler
+
+        PUBWEAK DMA2_Channel3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel3_IRQHandler
+        B DMA2_Channel3_IRQHandler
+
+        PUBWEAK DMA2_Channel4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel4_IRQHandler
+        B DMA2_Channel4_IRQHandler
+
+        PUBWEAK DMA2_Channel5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel5_IRQHandler
+        B DMA2_Channel5_IRQHandler
+
+        PUBWEAK ETH_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+ETH_IRQHandler
+        B ETH_IRQHandler
+
+        PUBWEAK ETH_WKUP_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+ETH_WKUP_IRQHandler
+        B ETH_WKUP_IRQHandler
+
+        PUBWEAK CAN2_TX_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN2_TX_IRQHandler
+        B CAN2_TX_IRQHandler
+
+        PUBWEAK CAN2_RX0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN2_RX0_IRQHandler
+        B CAN2_RX0_IRQHandler
+
+        PUBWEAK CAN2_RX1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN2_RX1_IRQHandler
+        B CAN2_RX1_IRQHandler
+
+        PUBWEAK CAN2_SCE_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN2_SCE_IRQHandler
+        B CAN2_SCE_IRQHandler
+
+        PUBWEAK OTG_FS_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+OTG_FS_IRQHandler
+        B OTG_FS_IRQHandler
+
+        END
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_hd.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_hd.s
new file mode 100644
index 0000000000000000000000000000000000000000..5882cd58797349e4191daa796611849368d2267e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_hd.s
@@ -0,0 +1,510 @@
+;/******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_hd.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x High Density Devices vector table for EWARM5.x 
+;*                      toolchain.
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == __iar_program_start,
+;*                      - Set the vector table entries with the exceptions ISR address,
+;*                      - Configure external SRAM mounted on STM3210E-EVAL board
+;*                       to be used as data memory (optional, to be enabled by user)
+;*                      After Reset the Cortex-M3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;********************************************************************************
+;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************/
+;
+;
+; The modules in this file are included in the libraries, and may be replaced
+; by any user-defined modules that define the PUBLIC symbol _program_start or
+; a user defined start symbol.
+; To override the cstartup defined in the library, simply add your modified
+; version to the workbench project.
+;
+; The vector table is normally located at address 0.
+; When debugging in RAM, it can be located in RAM, aligned to at least 2^6.
+; The name "__vector_table" has special meaning for C-SPY:
+; it is where the SP start value is found, and the NVIC vector
+; table register (VTOR) is initialized to this address if != 0.
+;
+; Cortex-M version
+;     
+  
+    MODULE  ?cstartup
+        
+  ;; ICODE is the same segment as cstartup. By placing __low_level_init
+  ;; in the same segment, we make sure it can be reached with BL. */
+
+    SECTION	   CSTACK:DATA:NOROOT(3)
+    SECTION .icode:CODE:NOROOT(2)
+    PUBLIC  __low_level_init
+
+       PUBWEAK SystemInit_ExtMemCtl
+       SECTION .text:CODE:REORDER(2)
+        THUMB
+SystemInit_ExtMemCtl
+        BX LR 
+   
+__low_level_init:
+
+  ;;  Initialize hardware.
+                LDR  R0, = SystemInit_ExtMemCtl ; initialize external memory controller
+                MOV  R11, LR
+                BLX  R0 
+                LDR  R1, =sfe(CSTACK)        ; restore original stack pointer
+                MSR  MSP, R1   
+                MOV  R0,#1
+   ;; Return with BX to be independent of mode of caller
+                BX    R11
+
+        ;; Forward declaration of sections.
+        SECTION .intvec:CODE:NOROOT(2)
+
+        EXTERN  __iar_program_start
+        PUBLIC  __vector_table
+
+        DATA
+__intial_sp      EQU     0x20000400        
+__vector_table
+        DCD     __intial_sp
+        DCD     __iar_program_start
+
+        DCD     NMI_Handler               ; NMI Handler
+        DCD     HardFault_Handler         ; Hard Fault Handler
+        DCD     MemManage_Handler         ; MPU Fault Handler
+        DCD     BusFault_Handler          ; Bus Fault Handler
+        DCD     UsageFault_Handler        ; Usage Fault Handler
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     SVC_Handler               ; SVCall Handler
+        DCD     DebugMon_Handler          ; Debug Monitor Handler
+        DCD     0                         ; Reserved
+        DCD     PendSV_Handler            ; PendSV Handler
+        DCD     SysTick_Handler           ; SysTick Handler
+
+         ; External Interrupts
+        DCD     WWDG_IRQHandler           ; Window Watchdog
+        DCD     PVD_IRQHandler            ; PVD through EXTI Line detect
+        DCD     TAMPER_IRQHandler         ; Tamper
+        DCD     RTC_IRQHandler            ; RTC
+        DCD     FLASH_IRQHandler          ; Flash
+        DCD     RCC_IRQHandler            ; RCC
+        DCD     EXTI0_IRQHandler          ; EXTI Line 0
+        DCD     EXTI1_IRQHandler          ; EXTI Line 1
+        DCD     EXTI2_IRQHandler          ; EXTI Line 2
+        DCD     EXTI3_IRQHandler          ; EXTI Line 3
+        DCD     EXTI4_IRQHandler          ; EXTI Line 4
+        DCD     DMA1_Channel1_IRQHandler  ; DMA1 Channel 1
+        DCD     DMA1_Channel2_IRQHandler  ; DMA1 Channel 2
+        DCD     DMA1_Channel3_IRQHandler  ; DMA1 Channel 3
+        DCD     DMA1_Channel4_IRQHandler  ; DMA1 Channel 4
+        DCD     DMA1_Channel5_IRQHandler  ; DMA1 Channel 5
+        DCD     DMA1_Channel6_IRQHandler  ; DMA1 Channel 6
+        DCD     DMA1_Channel7_IRQHandler  ; DMA1 Channel 7
+        DCD     ADC1_2_IRQHandler         ; ADC1 & ADC2
+        DCD     USB_HP_CAN1_TX_IRQHandler  ; USB High Priority or CAN1 TX
+        DCD     USB_LP_CAN1_RX0_IRQHandler ; USB Low  Priority or CAN1 RX0
+        DCD     CAN1_RX1_IRQHandler       ; CAN1 RX1
+        DCD     CAN1_SCE_IRQHandler       ; CAN1 SCE
+        DCD     EXTI9_5_IRQHandler        ; EXTI Line 9..5
+        DCD     TIM1_BRK_IRQHandler       ; TIM1 Break
+        DCD     TIM1_UP_IRQHandler        ; TIM1 Update
+        DCD     TIM1_TRG_COM_IRQHandler   ; TIM1 Trigger and Commutation
+        DCD     TIM1_CC_IRQHandler        ; TIM1 Capture Compare
+        DCD     TIM2_IRQHandler           ; TIM2
+        DCD     TIM3_IRQHandler           ; TIM3
+        DCD     TIM4_IRQHandler           ; TIM4
+        DCD     I2C1_EV_IRQHandler        ; I2C1 Event
+        DCD     I2C1_ER_IRQHandler        ; I2C1 Error
+        DCD     I2C2_EV_IRQHandler        ; I2C2 Event
+        DCD     I2C2_ER_IRQHandler        ; I2C2 Error
+        DCD     SPI1_IRQHandler           ; SPI1
+        DCD     SPI2_IRQHandler           ; SPI2
+        DCD     USART1_IRQHandler         ; USART1
+        DCD     USART2_IRQHandler         ; USART2
+        DCD     USART3_IRQHandler         ; USART3
+        DCD     EXTI15_10_IRQHandler      ; EXTI Line 15..10
+        DCD     RTCAlarm_IRQHandler       ; RTC Alarm through EXTI Line
+        DCD     USBWakeUp_IRQHandler      ; USB Wakeup from suspend
+        DCD     TIM8_BRK_IRQHandler       ; TIM8 Break
+        DCD     TIM8_UP_IRQHandler        ; TIM8 Update
+        DCD     TIM8_TRG_COM_IRQHandler   ; TIM8 Trigger and Commutation
+        DCD     TIM8_CC_IRQHandler        ; TIM8 Capture Compare
+        DCD     ADC3_IRQHandler           ; ADC3
+        DCD     FSMC_IRQHandler           ; FSMC
+        DCD     SDIO_IRQHandler           ; SDIO
+        DCD     TIM5_IRQHandler           ; TIM5
+        DCD     SPI3_IRQHandler           ; SPI3
+        DCD     UART4_IRQHandler          ; UART4
+        DCD     UART5_IRQHandler          ; UART5
+        DCD     TIM6_IRQHandler           ; TIM6
+        DCD     TIM7_IRQHandler           ; TIM7
+        DCD     DMA2_Channel1_IRQHandler  ; DMA2 Channel1
+        DCD     DMA2_Channel2_IRQHandler  ; DMA2 Channel2
+        DCD     DMA2_Channel3_IRQHandler  ; DMA2 Channel3
+        DCD     DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5
+;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
+;;
+;; Default interrupt handlers.
+;;
+        THUMB
+       
+        PUBWEAK NMI_Handler
+        SECTION .text:CODE:REORDER(1)
+NMI_Handler
+        B NMI_Handler
+
+        PUBWEAK HardFault_Handler
+        SECTION .text:CODE:REORDER(1)
+HardFault_Handler
+        B HardFault_Handler
+
+        PUBWEAK MemManage_Handler
+        SECTION .text:CODE:REORDER(1)
+MemManage_Handler
+        B MemManage_Handler
+
+        PUBWEAK BusFault_Handler
+        SECTION .text:CODE:REORDER(1)
+BusFault_Handler
+        B BusFault_Handler
+
+        PUBWEAK UsageFault_Handler
+        SECTION .text:CODE:REORDER(1)
+UsageFault_Handler
+        B UsageFault_Handler
+
+        PUBWEAK SVC_Handler
+        SECTION .text:CODE:REORDER(1)
+SVC_Handler
+        B SVC_Handler
+
+        PUBWEAK DebugMon_Handler
+        SECTION .text:CODE:REORDER(1)
+DebugMon_Handler
+        B DebugMon_Handler
+
+        PUBWEAK PendSV_Handler
+        SECTION .text:CODE:REORDER(1)
+PendSV_Handler
+        B PendSV_Handler
+
+        PUBWEAK SysTick_Handler
+        SECTION .text:CODE:REORDER(1)
+SysTick_Handler
+        B SysTick_Handler
+
+        PUBWEAK WWDG_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+WWDG_IRQHandler
+        B WWDG_IRQHandler
+
+        PUBWEAK PVD_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+PVD_IRQHandler
+        B PVD_IRQHandler
+
+        PUBWEAK TAMPER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TAMPER_IRQHandler
+        B TAMPER_IRQHandler
+
+        PUBWEAK RTC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTC_IRQHandler
+        B RTC_IRQHandler
+
+        PUBWEAK FLASH_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+FLASH_IRQHandler
+        B FLASH_IRQHandler
+
+        PUBWEAK RCC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RCC_IRQHandler
+        B RCC_IRQHandler
+
+        PUBWEAK EXTI0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI0_IRQHandler
+        B EXTI0_IRQHandler
+
+        PUBWEAK EXTI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI1_IRQHandler
+        B EXTI1_IRQHandler
+
+        PUBWEAK EXTI2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI2_IRQHandler
+        B EXTI2_IRQHandler
+
+        PUBWEAK EXTI3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI3_IRQHandler
+        B EXTI3_IRQHandler
+
+        PUBWEAK EXTI4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI4_IRQHandler
+        B EXTI4_IRQHandler
+
+        PUBWEAK DMA1_Channel1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel1_IRQHandler
+        B DMA1_Channel1_IRQHandler
+
+        PUBWEAK DMA1_Channel2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel2_IRQHandler
+        B DMA1_Channel2_IRQHandler
+
+        PUBWEAK DMA1_Channel3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel3_IRQHandler
+        B DMA1_Channel3_IRQHandler
+
+        PUBWEAK DMA1_Channel4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel4_IRQHandler
+        B DMA1_Channel4_IRQHandler
+
+        PUBWEAK DMA1_Channel5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel5_IRQHandler
+        B DMA1_Channel5_IRQHandler
+
+        PUBWEAK DMA1_Channel6_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel6_IRQHandler
+        B DMA1_Channel6_IRQHandler
+
+        PUBWEAK DMA1_Channel7_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel7_IRQHandler
+        B DMA1_Channel7_IRQHandler
+
+        PUBWEAK ADC1_2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+ADC1_2_IRQHandler
+        B ADC1_2_IRQHandler
+
+        PUBWEAK USB_HP_CAN1_TX_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USB_HP_CAN1_TX_IRQHandler
+        B USB_HP_CAN1_TX_IRQHandler
+
+        PUBWEAK USB_LP_CAN1_RX0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USB_LP_CAN1_RX0_IRQHandler
+        B USB_LP_CAN1_RX0_IRQHandler
+
+        PUBWEAK CAN1_RX1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_RX1_IRQHandler
+        B CAN1_RX1_IRQHandler
+
+        PUBWEAK CAN1_SCE_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_SCE_IRQHandler
+        B CAN1_SCE_IRQHandler
+
+        PUBWEAK EXTI9_5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI9_5_IRQHandler
+        B EXTI9_5_IRQHandler
+
+        PUBWEAK TIM1_BRK_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_BRK_IRQHandler
+        B TIM1_BRK_IRQHandler
+
+        PUBWEAK TIM1_UP_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_UP_IRQHandler
+        B TIM1_UP_IRQHandler
+
+        PUBWEAK TIM1_TRG_COM_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_TRG_COM_IRQHandler
+        B TIM1_TRG_COM_IRQHandler
+
+        PUBWEAK TIM1_CC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_CC_IRQHandler
+        B TIM1_CC_IRQHandler
+
+        PUBWEAK TIM2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM2_IRQHandler
+        B TIM2_IRQHandler
+
+        PUBWEAK TIM3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM3_IRQHandler
+        B TIM3_IRQHandler
+
+        PUBWEAK TIM4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM4_IRQHandler
+        B TIM4_IRQHandler
+
+        PUBWEAK I2C1_EV_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_EV_IRQHandler
+        B I2C1_EV_IRQHandler
+
+        PUBWEAK I2C1_ER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_ER_IRQHandler
+        B I2C1_ER_IRQHandler
+
+        PUBWEAK I2C2_EV_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C2_EV_IRQHandler
+        B I2C2_EV_IRQHandler
+
+        PUBWEAK I2C2_ER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C2_ER_IRQHandler
+        B I2C2_ER_IRQHandler
+
+        PUBWEAK SPI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI1_IRQHandler
+        B SPI1_IRQHandler
+
+        PUBWEAK SPI2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI2_IRQHandler
+        B SPI2_IRQHandler
+
+        PUBWEAK USART1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART1_IRQHandler
+        B USART1_IRQHandler
+
+        PUBWEAK USART2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART2_IRQHandler
+        B USART2_IRQHandler
+
+        PUBWEAK USART3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART3_IRQHandler
+        B USART3_IRQHandler
+
+        PUBWEAK EXTI15_10_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI15_10_IRQHandler
+        B EXTI15_10_IRQHandler
+
+        PUBWEAK RTCAlarm_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTCAlarm_IRQHandler
+        B RTCAlarm_IRQHandler
+
+        PUBWEAK USBWakeUp_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USBWakeUp_IRQHandler
+        B USBWakeUp_IRQHandler
+
+        PUBWEAK TIM8_BRK_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM8_BRK_IRQHandler
+        B TIM8_BRK_IRQHandler
+
+        PUBWEAK TIM8_UP_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM8_UP_IRQHandler
+        B TIM8_UP_IRQHandler
+
+        PUBWEAK TIM8_TRG_COM_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM8_TRG_COM_IRQHandler
+        B TIM8_TRG_COM_IRQHandler
+
+        PUBWEAK TIM8_CC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM8_CC_IRQHandler
+        B TIM8_CC_IRQHandler
+
+        PUBWEAK ADC3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+ADC3_IRQHandler
+        B ADC3_IRQHandler
+
+        PUBWEAK FSMC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+FSMC_IRQHandler
+        B FSMC_IRQHandler
+
+        PUBWEAK SDIO_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SDIO_IRQHandler
+        B SDIO_IRQHandler
+
+        PUBWEAK TIM5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM5_IRQHandler
+        B TIM5_IRQHandler
+
+        PUBWEAK SPI3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI3_IRQHandler
+        B SPI3_IRQHandler
+
+        PUBWEAK UART4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+UART4_IRQHandler
+        B UART4_IRQHandler
+
+        PUBWEAK UART5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+UART5_IRQHandler
+        B UART5_IRQHandler
+
+        PUBWEAK TIM6_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM6_IRQHandler
+        B TIM6_IRQHandler
+
+        PUBWEAK TIM7_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM7_IRQHandler
+        B TIM7_IRQHandler
+
+        PUBWEAK DMA2_Channel1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel1_IRQHandler
+        B DMA2_Channel1_IRQHandler
+
+        PUBWEAK DMA2_Channel2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel2_IRQHandler
+        B DMA2_Channel2_IRQHandler
+
+        PUBWEAK DMA2_Channel3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel3_IRQHandler
+        B DMA2_Channel3_IRQHandler
+
+        PUBWEAK DMA2_Channel4_5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA2_Channel4_5_IRQHandler
+        B DMA2_Channel4_5_IRQHandler
+        
+        
+        END
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_ld.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_ld.s
new file mode 100644
index 0000000000000000000000000000000000000000..13046d8df000b02cca3c37a54ed80d06638fa82e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_ld.s
@@ -0,0 +1,357 @@
+;/******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_ld.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x Low Density Devices vector table for EWARM5.x 
+;*                      toolchain.
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == __iar_program_start,
+;*                      - Set the vector table entries with the exceptions ISR 
+;*                        address.
+;*                      After Reset the Cortex-M3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;********************************************************************************
+;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************/
+;
+;
+; The modules in this file are included in the libraries, and may be replaced
+; by any user-defined modules that define the PUBLIC symbol _program_start or
+; a user defined start symbol.
+; To override the cstartup defined in the library, simply add your modified
+; version to the workbench project.
+;
+; The vector table is normally located at address 0.
+; When debugging in RAM, it can be located in RAM, aligned to at least 2^6.
+; The name "__vector_table" has special meaning for C-SPY:
+; it is where the SP start value is found, and the NVIC vector
+; table register (VTOR) is initialized to this address if != 0.
+;
+; Cortex-M version
+;
+
+        MODULE  ?cstartup
+
+        ;; Forward declaration of sections.
+        SECTION CSTACK:DATA:NOROOT(3)
+
+        SECTION .intvec:CODE:NOROOT(2)
+
+        EXTERN  __iar_program_start
+        PUBLIC  __vector_table
+
+        DATA
+__vector_table
+        DCD     sfe(CSTACK)
+        DCD     __iar_program_start
+
+        DCD     NMI_Handler               ; NMI Handler
+        DCD     HardFault_Handler         ; Hard Fault Handler
+        DCD     MemManage_Handler         ; MPU Fault Handler
+        DCD     BusFault_Handler          ; Bus Fault Handler
+        DCD     UsageFault_Handler        ; Usage Fault Handler
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     SVC_Handler               ; SVCall Handler
+        DCD     DebugMon_Handler          ; Debug Monitor Handler
+        DCD     0                         ; Reserved
+        DCD     PendSV_Handler            ; PendSV Handler
+        DCD     SysTick_Handler           ; SysTick Handler
+
+         ; External Interrupts
+        DCD     WWDG_IRQHandler           ; Window Watchdog
+        DCD     PVD_IRQHandler            ; PVD through EXTI Line detect
+        DCD     TAMPER_IRQHandler         ; Tamper
+        DCD     RTC_IRQHandler            ; RTC
+        DCD     FLASH_IRQHandler          ; Flash
+        DCD     RCC_IRQHandler            ; RCC
+        DCD     EXTI0_IRQHandler          ; EXTI Line 0
+        DCD     EXTI1_IRQHandler          ; EXTI Line 1
+        DCD     EXTI2_IRQHandler          ; EXTI Line 2
+        DCD     EXTI3_IRQHandler          ; EXTI Line 3
+        DCD     EXTI4_IRQHandler          ; EXTI Line 4
+        DCD     DMA1_Channel1_IRQHandler  ; DMA1 Channel 1
+        DCD     DMA1_Channel2_IRQHandler  ; DMA1 Channel 2
+        DCD     DMA1_Channel3_IRQHandler  ; DMA1 Channel 3
+        DCD     DMA1_Channel4_IRQHandler  ; DMA1 Channel 4
+        DCD     DMA1_Channel5_IRQHandler  ; DMA1 Channel 5
+        DCD     DMA1_Channel6_IRQHandler  ; DMA1 Channel 6
+        DCD     DMA1_Channel7_IRQHandler  ; DMA1 Channel 7
+        DCD     ADC1_2_IRQHandler         ; ADC1 & ADC2
+        DCD     USB_HP_CAN1_TX_IRQHandler  ; USB High Priority or CAN1 TX
+        DCD     USB_LP_CAN1_RX0_IRQHandler ; USB Low  Priority or CAN1 RX0
+        DCD     CAN1_RX1_IRQHandler       ; CAN1 RX1
+        DCD     CAN1_SCE_IRQHandler       ; CAN1 SCE
+        DCD     EXTI9_5_IRQHandler        ; EXTI Line 9..5
+        DCD     TIM1_BRK_IRQHandler       ; TIM1 Break
+        DCD     TIM1_UP_IRQHandler        ; TIM1 Update
+        DCD     TIM1_TRG_COM_IRQHandler   ; TIM1 Trigger and Commutation
+        DCD     TIM1_CC_IRQHandler        ; TIM1 Capture Compare
+        DCD     TIM2_IRQHandler           ; TIM2
+        DCD     TIM3_IRQHandler           ; TIM3
+        DCD     0                         ; Reserved
+        DCD     I2C1_EV_IRQHandler        ; I2C1 Event
+        DCD     I2C1_ER_IRQHandler        ; I2C1 Error
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     SPI1_IRQHandler           ; SPI1
+        DCD     0                         ; Reserved
+        DCD     USART1_IRQHandler         ; USART1
+        DCD     USART2_IRQHandler         ; USART2
+        DCD     0                         ; Reserved
+        DCD     EXTI15_10_IRQHandler      ; EXTI Line 15..10
+        DCD     RTCAlarm_IRQHandler       ; RTC Alarm through EXTI Line
+        DCD     USBWakeUp_IRQHandler      ; USB Wakeup from suspend
+
+;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
+;;
+;; Default interrupt handlers.
+;;
+        THUMB
+
+        PUBWEAK NMI_Handler
+        SECTION .text:CODE:REORDER(1)
+NMI_Handler
+        B NMI_Handler
+        
+        PUBWEAK HardFault_Handler
+        SECTION .text:CODE:REORDER(1)
+HardFault_Handler
+        B HardFault_Handler
+        
+        PUBWEAK MemManage_Handler
+        SECTION .text:CODE:REORDER(1)
+MemManage_Handler
+        B MemManage_Handler
+        
+        PUBWEAK BusFault_Handler
+        SECTION .text:CODE:REORDER(1)
+BusFault_Handler
+        B BusFault_Handler
+        
+        PUBWEAK UsageFault_Handler
+        SECTION .text:CODE:REORDER(1)
+UsageFault_Handler
+        B UsageFault_Handler
+        
+        PUBWEAK SVC_Handler
+        SECTION .text:CODE:REORDER(1)
+SVC_Handler
+        B SVC_Handler
+        
+        PUBWEAK DebugMon_Handler
+        SECTION .text:CODE:REORDER(1)
+DebugMon_Handler
+        B DebugMon_Handler
+        
+        PUBWEAK PendSV_Handler
+        SECTION .text:CODE:REORDER(1)
+PendSV_Handler
+        B PendSV_Handler
+        
+        PUBWEAK SysTick_Handler
+        SECTION .text:CODE:REORDER(1)
+SysTick_Handler
+        B SysTick_Handler
+        
+        PUBWEAK WWDG_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+WWDG_IRQHandler
+        B WWDG_IRQHandler
+        
+        PUBWEAK PVD_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+PVD_IRQHandler
+        B PVD_IRQHandler
+        
+        PUBWEAK TAMPER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TAMPER_IRQHandler
+        B TAMPER_IRQHandler
+        
+        PUBWEAK RTC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTC_IRQHandler
+        B RTC_IRQHandler
+        
+        PUBWEAK FLASH_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+FLASH_IRQHandler
+        B FLASH_IRQHandler
+        
+        PUBWEAK RCC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RCC_IRQHandler
+        B RCC_IRQHandler
+        
+        PUBWEAK EXTI0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI0_IRQHandler
+        B EXTI0_IRQHandler
+        
+        PUBWEAK EXTI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI1_IRQHandler
+        B EXTI1_IRQHandler
+        
+        PUBWEAK EXTI2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI2_IRQHandler
+        B EXTI2_IRQHandler
+        
+        PUBWEAK EXTI3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI3_IRQHandler
+        B EXTI3_IRQHandler
+        
+        PUBWEAK EXTI4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI4_IRQHandler
+        B EXTI4_IRQHandler
+        
+        PUBWEAK DMA1_Channel1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel1_IRQHandler
+        B DMA1_Channel1_IRQHandler
+        
+        PUBWEAK DMA1_Channel2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel2_IRQHandler
+        B DMA1_Channel2_IRQHandler
+        
+        PUBWEAK DMA1_Channel3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel3_IRQHandler
+        B DMA1_Channel3_IRQHandler
+        
+        PUBWEAK DMA1_Channel4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel4_IRQHandler
+        B DMA1_Channel4_IRQHandler
+        
+        PUBWEAK DMA1_Channel5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel5_IRQHandler
+        B DMA1_Channel5_IRQHandler
+        
+        PUBWEAK DMA1_Channel6_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel6_IRQHandler
+        B DMA1_Channel6_IRQHandler
+        
+        PUBWEAK DMA1_Channel7_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel7_IRQHandler
+        B DMA1_Channel7_IRQHandler
+        
+        PUBWEAK ADC1_2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+ADC1_2_IRQHandler
+        B ADC1_2_IRQHandler
+        
+        PUBWEAK USB_HP_CAN1_TX_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USB_HP_CAN1_TX_IRQHandler
+        B USB_HP_CAN1_TX_IRQHandler
+        
+        PUBWEAK USB_LP_CAN1_RX0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USB_LP_CAN1_RX0_IRQHandler
+        B USB_LP_CAN1_RX0_IRQHandler
+        
+        PUBWEAK CAN1_RX1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_RX1_IRQHandler
+        B CAN1_RX1_IRQHandler
+        
+        PUBWEAK CAN1_SCE_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_SCE_IRQHandler
+        B CAN1_SCE_IRQHandler
+        
+        PUBWEAK EXTI9_5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI9_5_IRQHandler
+        B EXTI9_5_IRQHandler
+        
+        PUBWEAK TIM1_BRK_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_BRK_IRQHandler
+        B TIM1_BRK_IRQHandler
+        
+        PUBWEAK TIM1_UP_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_UP_IRQHandler
+        B TIM1_UP_IRQHandler
+        
+        PUBWEAK TIM1_TRG_COM_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_TRG_COM_IRQHandler
+        B TIM1_TRG_COM_IRQHandler
+        
+        PUBWEAK TIM1_CC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_CC_IRQHandler
+        B TIM1_CC_IRQHandler
+        
+        PUBWEAK TIM2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM2_IRQHandler
+        B TIM2_IRQHandler
+        
+        PUBWEAK TIM3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM3_IRQHandler
+        B TIM3_IRQHandler
+        
+        PUBWEAK I2C1_EV_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_EV_IRQHandler
+        B I2C1_EV_IRQHandler
+        
+        PUBWEAK I2C1_ER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_ER_IRQHandler
+        B I2C1_ER_IRQHandler
+        
+        PUBWEAK SPI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI1_IRQHandler
+        B SPI1_IRQHandler
+                      
+        PUBWEAK USART1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART1_IRQHandler
+        B USART1_IRQHandler
+
+        PUBWEAK USART2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART2_IRQHandler
+        B USART2_IRQHandler
+
+        PUBWEAK EXTI15_10_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI15_10_IRQHandler
+        B EXTI15_10_IRQHandler
+
+        PUBWEAK RTCAlarm_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTCAlarm_IRQHandler
+        B RTCAlarm_IRQHandler
+
+        PUBWEAK USBWakeUp_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USBWakeUp_IRQHandler
+        B USBWakeUp_IRQHandler
+
+        END
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_md.s b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_md.s
new file mode 100644
index 0000000000000000000000000000000000000000..e28a3ba727ba02600d2a5c0cb43456f3e121a92d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/startup/iar/startup_stm32f10x_md.s
@@ -0,0 +1,382 @@
+;/******************** (C) COPYRIGHT 2009 STMicroelectronics ********************
+;* File Name          : startup_stm32f10x_md.s
+;* Author             : MCD Application Team
+;* Version            : V3.1.2
+;* Date               : 09/28/2009
+;* Description        : STM32F10x Medium Density Devices vector table for 
+;*                      EWARM5.x toolchain.
+;*                      This module performs:
+;*                      - Set the initial SP
+;*                      - Set the initial PC == __iar_program_start,
+;*                      - Set the vector table entries with the exceptions ISR 
+;*                        address.
+;*                      After Reset the Cortex-M3 processor is in Thread mode,
+;*                      priority is Privileged, and the Stack is set to Main.
+;********************************************************************************
+;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
+;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
+;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
+;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
+;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+;*******************************************************************************/
+;
+;
+; The modules in this file are included in the libraries, and may be replaced
+; by any user-defined modules that define the PUBLIC symbol _program_start or
+; a user defined start symbol.
+; To override the cstartup defined in the library, simply add your modified
+; version to the workbench project.
+;
+; The vector table is normally located at address 0.
+; When debugging in RAM, it can be located in RAM, aligned to at least 2^6.
+; The name "__vector_table" has special meaning for C-SPY:
+; it is where the SP start value is found, and the NVIC vector
+; table register (VTOR) is initialized to this address if != 0.
+;
+; Cortex-M version
+;
+
+        MODULE  ?cstartup
+
+        ;; Forward declaration of sections.
+        SECTION CSTACK:DATA:NOROOT(3)
+
+        SECTION .intvec:CODE:NOROOT(2)
+
+        EXTERN  __iar_program_start
+        PUBLIC  __vector_table
+
+        DATA
+__vector_table
+        DCD     sfe(CSTACK)
+        DCD     __iar_program_start
+
+        DCD     NMI_Handler               ; NMI Handler
+        DCD     HardFault_Handler         ; Hard Fault Handler
+        DCD     MemManage_Handler         ; MPU Fault Handler
+        DCD     BusFault_Handler          ; Bus Fault Handler
+        DCD     UsageFault_Handler        ; Usage Fault Handler
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     0                         ; Reserved
+        DCD     SVC_Handler               ; SVCall Handler
+        DCD     DebugMon_Handler          ; Debug Monitor Handler
+        DCD     0                         ; Reserved
+        DCD     PendSV_Handler            ; PendSV Handler
+        DCD     SysTick_Handler           ; SysTick Handler
+
+         ; External Interrupts
+        DCD     WWDG_IRQHandler           ; Window Watchdog
+        DCD     PVD_IRQHandler            ; PVD through EXTI Line detect
+        DCD     TAMPER_IRQHandler         ; Tamper
+        DCD     RTC_IRQHandler            ; RTC
+        DCD     FLASH_IRQHandler          ; Flash
+        DCD     RCC_IRQHandler            ; RCC
+        DCD     EXTI0_IRQHandler          ; EXTI Line 0
+        DCD     EXTI1_IRQHandler          ; EXTI Line 1
+        DCD     EXTI2_IRQHandler          ; EXTI Line 2
+        DCD     EXTI3_IRQHandler          ; EXTI Line 3
+        DCD     EXTI4_IRQHandler          ; EXTI Line 4
+        DCD     DMA1_Channel1_IRQHandler  ; DMA1 Channel 1
+        DCD     DMA1_Channel2_IRQHandler  ; DMA1 Channel 2
+        DCD     DMA1_Channel3_IRQHandler  ; DMA1 Channel 3
+        DCD     DMA1_Channel4_IRQHandler  ; DMA1 Channel 4
+        DCD     DMA1_Channel5_IRQHandler  ; DMA1 Channel 5
+        DCD     DMA1_Channel6_IRQHandler  ; DMA1 Channel 6
+        DCD     DMA1_Channel7_IRQHandler  ; DMA1 Channel 7
+        DCD     ADC1_2_IRQHandler         ; ADC1 & ADC2
+        DCD     USB_HP_CAN1_TX_IRQHandler  ; USB High Priority or CAN1 TX
+        DCD     USB_LP_CAN1_RX0_IRQHandler ; USB Low  Priority or CAN1 RX0
+        DCD     CAN1_RX1_IRQHandler       ; CAN1 RX1
+        DCD     CAN1_SCE_IRQHandler       ; CAN1 SCE
+        DCD     EXTI9_5_IRQHandler        ; EXTI Line 9..5
+        DCD     TIM1_BRK_IRQHandler       ; TIM1 Break
+        DCD     TIM1_UP_IRQHandler        ; TIM1 Update
+        DCD     TIM1_TRG_COM_IRQHandler   ; TIM1 Trigger and Commutation
+        DCD     TIM1_CC_IRQHandler        ; TIM1 Capture Compare
+        DCD     TIM2_IRQHandler           ; TIM2
+        DCD     TIM3_IRQHandler           ; TIM3
+        DCD     TIM4_IRQHandler           ; TIM4
+        DCD     I2C1_EV_IRQHandler        ; I2C1 Event
+        DCD     I2C1_ER_IRQHandler        ; I2C1 Error
+        DCD     I2C2_EV_IRQHandler        ; I2C2 Event
+        DCD     I2C2_ER_IRQHandler        ; I2C2 Error
+        DCD     SPI1_IRQHandler           ; SPI1
+        DCD     SPI2_IRQHandler           ; SPI2
+        DCD     USART1_IRQHandler         ; USART1
+        DCD     USART2_IRQHandler         ; USART2
+        DCD     USART3_IRQHandler         ; USART3
+        DCD     EXTI15_10_IRQHandler      ; EXTI Line 15..10
+        DCD     RTCAlarm_IRQHandler       ; RTC Alarm through EXTI Line
+        DCD     USBWakeUp_IRQHandler      ; USB Wakeup from suspend
+
+;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
+;;
+;; Default interrupt handlers.
+;;
+        THUMB
+
+        PUBWEAK NMI_Handler
+        SECTION .text:CODE:REORDER(1)
+NMI_Handler
+        B NMI_Handler
+
+        PUBWEAK HardFault_Handler
+        SECTION .text:CODE:REORDER(1)
+HardFault_Handler
+        B HardFault_Handler
+
+        PUBWEAK MemManage_Handler
+        SECTION .text:CODE:REORDER(1)
+MemManage_Handler
+        B MemManage_Handler
+
+        PUBWEAK BusFault_Handler
+        SECTION .text:CODE:REORDER(1)
+BusFault_Handler
+        B BusFault_Handler
+
+        PUBWEAK UsageFault_Handler
+        SECTION .text:CODE:REORDER(1)
+UsageFault_Handler
+        B UsageFault_Handler
+
+        PUBWEAK SVC_Handler
+        SECTION .text:CODE:REORDER(1)
+SVC_Handler
+        B SVC_Handler
+
+        PUBWEAK DebugMon_Handler
+        SECTION .text:CODE:REORDER(1)
+DebugMon_Handler
+        B DebugMon_Handler
+
+        PUBWEAK PendSV_Handler
+        SECTION .text:CODE:REORDER(1)
+PendSV_Handler
+        B PendSV_Handler
+
+        PUBWEAK SysTick_Handler
+        SECTION .text:CODE:REORDER(1)
+SysTick_Handler
+        B SysTick_Handler
+
+        PUBWEAK WWDG_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+WWDG_IRQHandler
+        B WWDG_IRQHandler
+
+        PUBWEAK PVD_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+PVD_IRQHandler
+        B PVD_IRQHandler
+
+        PUBWEAK TAMPER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TAMPER_IRQHandler
+        B TAMPER_IRQHandler
+
+        PUBWEAK RTC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTC_IRQHandler
+        B RTC_IRQHandler
+
+        PUBWEAK FLASH_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+FLASH_IRQHandler
+        B FLASH_IRQHandler
+
+        PUBWEAK RCC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RCC_IRQHandler
+        B RCC_IRQHandler
+
+        PUBWEAK EXTI0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI0_IRQHandler
+        B EXTI0_IRQHandler
+
+        PUBWEAK EXTI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI1_IRQHandler
+        B EXTI1_IRQHandler
+
+        PUBWEAK EXTI2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI2_IRQHandler
+        B EXTI2_IRQHandler
+
+        PUBWEAK EXTI3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI3_IRQHandler
+        B EXTI3_IRQHandler
+
+        PUBWEAK EXTI4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI4_IRQHandler
+        B EXTI4_IRQHandler
+
+        PUBWEAK DMA1_Channel1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel1_IRQHandler
+        B DMA1_Channel1_IRQHandler
+
+        PUBWEAK DMA1_Channel2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel2_IRQHandler
+        B DMA1_Channel2_IRQHandler
+
+        PUBWEAK DMA1_Channel3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel3_IRQHandler
+        B DMA1_Channel3_IRQHandler
+
+        PUBWEAK DMA1_Channel4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel4_IRQHandler
+        B DMA1_Channel4_IRQHandler
+
+        PUBWEAK DMA1_Channel5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel5_IRQHandler
+        B DMA1_Channel5_IRQHandler
+
+        PUBWEAK DMA1_Channel6_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel6_IRQHandler
+        B DMA1_Channel6_IRQHandler
+
+        PUBWEAK DMA1_Channel7_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+DMA1_Channel7_IRQHandler
+        B DMA1_Channel7_IRQHandler
+
+        PUBWEAK ADC1_2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+ADC1_2_IRQHandler
+        B ADC1_2_IRQHandler
+
+        PUBWEAK USB_HP_CAN1_TX_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USB_HP_CAN1_TX_IRQHandler
+        B USB_HP_CAN1_TX_IRQHandler
+
+        PUBWEAK USB_LP_CAN1_RX0_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USB_LP_CAN1_RX0_IRQHandler
+        B USB_LP_CAN1_RX0_IRQHandler
+
+        PUBWEAK CAN1_RX1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_RX1_IRQHandler
+        B CAN1_RX1_IRQHandler
+
+        PUBWEAK CAN1_SCE_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+CAN1_SCE_IRQHandler
+        B CAN1_SCE_IRQHandler
+
+        PUBWEAK EXTI9_5_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI9_5_IRQHandler
+        B EXTI9_5_IRQHandler
+
+        PUBWEAK TIM1_BRK_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_BRK_IRQHandler
+        B TIM1_BRK_IRQHandler
+
+        PUBWEAK TIM1_UP_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_UP_IRQHandler
+        B TIM1_UP_IRQHandler
+
+        PUBWEAK TIM1_TRG_COM_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_TRG_COM_IRQHandler
+        B TIM1_TRG_COM_IRQHandler
+
+        PUBWEAK TIM1_CC_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM1_CC_IRQHandler
+        B TIM1_CC_IRQHandler
+
+        PUBWEAK TIM2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM2_IRQHandler
+        B TIM2_IRQHandler
+
+        PUBWEAK TIM3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM3_IRQHandler
+        B TIM3_IRQHandler
+
+        PUBWEAK TIM4_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+TIM4_IRQHandler
+        B TIM4_IRQHandler
+
+        PUBWEAK I2C1_EV_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_EV_IRQHandler
+        B I2C1_EV_IRQHandler
+
+        PUBWEAK I2C1_ER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C1_ER_IRQHandler
+        B I2C1_ER_IRQHandler
+
+        PUBWEAK I2C2_EV_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C2_EV_IRQHandler
+        B I2C2_EV_IRQHandler
+
+        PUBWEAK I2C2_ER_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+I2C2_ER_IRQHandler
+        B I2C2_ER_IRQHandler
+
+        PUBWEAK SPI1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI1_IRQHandler
+        B SPI1_IRQHandler
+
+        PUBWEAK SPI2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+SPI2_IRQHandler
+        B SPI2_IRQHandler
+
+        PUBWEAK USART1_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART1_IRQHandler
+        B USART1_IRQHandler
+
+        PUBWEAK USART2_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART2_IRQHandler
+        B USART2_IRQHandler
+
+        PUBWEAK USART3_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USART3_IRQHandler
+        B USART3_IRQHandler
+
+        PUBWEAK EXTI15_10_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+EXTI15_10_IRQHandler
+        B EXTI15_10_IRQHandler
+
+        PUBWEAK RTCAlarm_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+RTCAlarm_IRQHandler
+        B RTCAlarm_IRQHandler
+
+        PUBWEAK USBWakeUp_IRQHandler
+        SECTION .text:CODE:REORDER(1)
+USBWakeUp_IRQHandler
+        B USBWakeUp_IRQHandler
+
+        END
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/stm32f10x.h b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/stm32f10x.h
new file mode 100644
index 0000000000000000000000000000000000000000..c49071ebc96fcfbdba181641636bb74fa00cc8a6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/stm32f10x.h
@@ -0,0 +1,7851 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   CMSIS Cortex-M3 Device Peripheral Access Layer Header File. 
+  *          This file contains all the peripheral register's definitions, bits 
+  *          definitions and memory mapping for STM32F10x Connectivity line, High
+  *          density, Medium density and Low density devices.
+  ******************************************************************************     
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */
+
+/** @addtogroup CMSIS
+  * @{
+  */
+
+/** @addtogroup stm32f10x
+  * @{
+  */
+    
+#ifndef __STM32F10x_H
+#define __STM32F10x_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif 
+  
+/** @addtogroup Library_configuration_section
+  * @{
+  */
+  
+/* Uncomment the line below according to the target STM32 device used in your
+   application 
+  */
+
+#if !defined (STM32F10X_LD) && !defined (STM32F10X_MD) && !defined (STM32F10X_HD) && !defined (STM32F10X_CL)
+  /* #define STM32F10X_LD */   /*!< STM32F10X_LD: STM32 Low density devices */
+  /* #define STM32F10X_MD */   /*!< STM32F10X_MD: STM32 Medium density devices */
+  /* #define STM32F10X_HD */   /*!< STM32F10X_HD: STM32 High density devices */
+  #define STM32F10X_CL  /*!< STM32F10X_CL: STM32 Connectivity line devices */
+#endif
+/*  Tip: To avoid modifying this file each time you need to switch between these
+        devices, you can define the device in your toolchain compiler preprocessor.
+
+ - Low density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers
+   where the Flash memory density ranges between 16 and 32 Kbytes.
+ - Medium density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers
+   where the Flash memory density ranges between 64 and 128 Kbytes.
+ - High density devices are STM32F101xx and STM32F103xx microcontrollers where
+   the Flash memory density ranges between 256 and 512 Kbytes.
+ - Connectivity line devices are STM32F105xx and STM32F107xx microcontrollers.
+  */
+
+#if !defined  USE_STDPERIPH_DRIVER
+/**
+ * @brief Comment the line below if you will not use the peripherals drivers.
+   In this case, these drivers will not be included and the application code will 
+   be based on direct access to peripherals registers 
+   */
+  /*#define USE_STDPERIPH_DRIVER*/
+#endif
+
+/**
+ * @brief In the following line adjust the value of External High Speed oscillator (HSE)
+   used in your application 
+   
+   Tip: To avoid modifying this file each time you need to use different HSE, you
+        can define the HSE value in your toolchain compiler preprocessor.
+  */           
+#if !defined  HSE_Value
+ #ifdef STM32F10X_CL   
+  #define HSE_Value    ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
+ #else 
+  #define HSE_Value    ((uint32_t)16000000) /*!< Value of the External oscillator in Hz */
+ #endif /* STM32F10X_CL */
+#endif /* HSE_Value */
+
+
+/**
+ * @brief In the following line adjust the External High Speed oscillator (HSE) Startup 
+   Timeout value 
+   */
+#define HSEStartUp_TimeOut   ((uint16_t)0x0500) /*!< Time out for HSE start up */
+
+#define HSI_Value    ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/
+
+/**
+ * @brief STM32F10x Standard Peripheral Library version number
+   */
+#define __STM32F10X_STDPERIPH_VERSION_MAIN   (0x03) /*!< [31:16] STM32F10x Standard Peripheral Library main version */
+#define __STM32F10X_STDPERIPH_VERSION_SUB1   (0x01) /*!< [15:8]  STM32F10x Standard Peripheral Library sub1 version */
+#define __STM32F10X_STDPERIPH_VERSION_SUB2   (0x02) /*!< [7:0]  STM32F10x Standard Peripheral Library sub2 version */
+#define __STM32F10X_STDPERIPH_VERSION       ((__STM32F10X_STDPERIPH_VERSION_MAIN << 16)\
+                                             | (__STM32F10X_STDPERIPH_VERSION_SUB1 << 8)\
+                                             | __STM32F10X_STDPERIPH_VERSION_SUB2)
+
+/**
+  * @}
+  */
+
+/** @addtogroup Configuration_section_for_CMSIS
+  * @{
+  */
+
+/**
+ * @brief Configuration of the Cortex-M3 Processor and Core Peripherals 
+ */
+#define __MPU_PRESENT             0 /*!< STM32 does not provide an MPU */
+#define __NVIC_PRIO_BITS          4 /*!< STM32 uses 4 Bits for the Priority Levels    */
+#define __Vendor_SysTickConfig    0 /*!< Set to 1 if different SysTick Config is used */
+
+/**
+ * @brief STM32F10x Interrupt Number Definition, according to the selected device 
+ *        in @ref Library_configuration_section 
+ */
+typedef enum IRQn
+{
+/******  Cortex-M3 Processor Exceptions Numbers ***************************************************/
+  NonMaskableInt_IRQn         = -14,    /*!< 2 Non Maskable Interrupt                             */
+  MemoryManagement_IRQn       = -12,    /*!< 4 Cortex-M3 Memory Management Interrupt              */
+  BusFault_IRQn               = -11,    /*!< 5 Cortex-M3 Bus Fault Interrupt                      */
+  UsageFault_IRQn             = -10,    /*!< 6 Cortex-M3 Usage Fault Interrupt                    */
+  SVCall_IRQn                 = -5,     /*!< 11 Cortex-M3 SV Call Interrupt                       */
+  DebugMonitor_IRQn           = -4,     /*!< 12 Cortex-M3 Debug Monitor Interrupt                 */
+  PendSV_IRQn                 = -2,     /*!< 14 Cortex-M3 Pend SV Interrupt                       */
+  SysTick_IRQn                = -1,     /*!< 15 Cortex-M3 System Tick Interrupt                   */
+
+/******  STM32 specific Interrupt Numbers *********************************************************/
+  WWDG_IRQn                   = 0,      /*!< Window WatchDog Interrupt                            */
+  PVD_IRQn                    = 1,      /*!< PVD through EXTI Line detection Interrupt            */
+  TAMPER_IRQn                 = 2,      /*!< Tamper Interrupt                                     */
+  RTC_IRQn                    = 3,      /*!< RTC global Interrupt                                 */
+  FLASH_IRQn                  = 4,      /*!< FLASH global Interrupt                               */
+  RCC_IRQn                    = 5,      /*!< RCC global Interrupt                                 */
+  EXTI0_IRQn                  = 6,      /*!< EXTI Line0 Interrupt                                 */
+  EXTI1_IRQn                  = 7,      /*!< EXTI Line1 Interrupt                                 */
+  EXTI2_IRQn                  = 8,      /*!< EXTI Line2 Interrupt                                 */
+  EXTI3_IRQn                  = 9,      /*!< EXTI Line3 Interrupt                                 */
+  EXTI4_IRQn                  = 10,     /*!< EXTI Line4 Interrupt                                 */
+  DMA1_Channel1_IRQn          = 11,     /*!< DMA1 Channel 1 global Interrupt                      */
+  DMA1_Channel2_IRQn          = 12,     /*!< DMA1 Channel 2 global Interrupt                      */
+  DMA1_Channel3_IRQn          = 13,     /*!< DMA1 Channel 3 global Interrupt                      */
+  DMA1_Channel4_IRQn          = 14,     /*!< DMA1 Channel 4 global Interrupt                      */
+  DMA1_Channel5_IRQn          = 15,     /*!< DMA1 Channel 5 global Interrupt                      */
+  DMA1_Channel6_IRQn          = 16,     /*!< DMA1 Channel 6 global Interrupt                      */
+  DMA1_Channel7_IRQn          = 17,     /*!< DMA1 Channel 7 global Interrupt                      */
+  ADC1_2_IRQn                 = 18,     /*!< ADC1 and ADC2 global Interrupt                       */
+
+#ifdef STM32F10X_LD
+  USB_HP_CAN1_TX_IRQn         = 19,     /*!< USB Device High Priority or CAN1 TX Interrupts       */
+  USB_LP_CAN1_RX0_IRQn        = 20,     /*!< USB Device Low Priority or CAN1 RX0 Interrupts       */
+  CAN1_RX1_IRQn               = 21,     /*!< CAN1 RX1 Interrupt                                   */
+  CAN1_SCE_IRQn               = 22,     /*!< CAN1 SCE Interrupt                                   */
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                        */
+  TIM1_BRK_IRQn               = 24,     /*!< TIM1 Break Interrupt                                 */
+  TIM1_UP_IRQn                = 25,     /*!< TIM1 Update Interrupt                                */
+  TIM1_TRG_COM_IRQn           = 26,     /*!< TIM1 Trigger and Commutation Interrupt               */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                       */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                 */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                 */
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                              */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                              */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                      */
+  RTCAlarm_IRQn               = 41,     /*!< RTC Alarm through EXTI Line Interrupt                */
+  USBWakeUp_IRQn              = 42,     /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */    
+#endif /* STM32F10X_LD */  
+
+#ifdef STM32F10X_MD
+  USB_HP_CAN1_TX_IRQn         = 19,     /*!< USB Device High Priority or CAN1 TX Interrupts       */
+  USB_LP_CAN1_RX0_IRQn        = 20,     /*!< USB Device Low Priority or CAN1 RX0 Interrupts       */
+  CAN1_RX1_IRQn               = 21,     /*!< CAN1 RX1 Interrupt                                   */
+  CAN1_SCE_IRQn               = 22,     /*!< CAN1 SCE Interrupt                                   */
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                        */
+  TIM1_BRK_IRQn               = 24,     /*!< TIM1 Break Interrupt                                 */
+  TIM1_UP_IRQn                = 25,     /*!< TIM1 Update Interrupt                                */
+  TIM1_TRG_COM_IRQn           = 26,     /*!< TIM1 Trigger and Commutation Interrupt               */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                       */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                */
+  TIM4_IRQn                   = 30,     /*!< TIM4 global Interrupt                                */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                 */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                 */
+  I2C2_EV_IRQn                = 33,     /*!< I2C2 Event Interrupt                                 */
+  I2C2_ER_IRQn                = 34,     /*!< I2C2 Error Interrupt                                 */
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                */
+  SPI2_IRQn                   = 36,     /*!< SPI2 global Interrupt                                */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                              */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                              */
+  USART3_IRQn                 = 39,     /*!< USART3 global Interrupt                              */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                      */
+  RTCAlarm_IRQn               = 41,     /*!< RTC Alarm through EXTI Line Interrupt                */
+  USBWakeUp_IRQn              = 42,     /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */  
+#endif /* STM32F10X_MD */  
+
+#ifdef STM32F10X_HD
+  USB_HP_CAN1_TX_IRQn         = 19,     /*!< USB Device High Priority or CAN1 TX Interrupts       */
+  USB_LP_CAN1_RX0_IRQn        = 20,     /*!< USB Device Low Priority or CAN1 RX0 Interrupts       */
+  CAN1_RX1_IRQn               = 21,     /*!< CAN1 RX1 Interrupt                                   */
+  CAN1_SCE_IRQn               = 22,     /*!< CAN1 SCE Interrupt                                   */
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                        */
+  TIM1_BRK_IRQn               = 24,     /*!< TIM1 Break Interrupt                                 */
+  TIM1_UP_IRQn                = 25,     /*!< TIM1 Update Interrupt                                */
+  TIM1_TRG_COM_IRQn           = 26,     /*!< TIM1 Trigger and Commutation Interrupt               */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                       */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                */
+  TIM4_IRQn                   = 30,     /*!< TIM4 global Interrupt                                */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                 */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                 */
+  I2C2_EV_IRQn                = 33,     /*!< I2C2 Event Interrupt                                 */
+  I2C2_ER_IRQn                = 34,     /*!< I2C2 Error Interrupt                                 */
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                */
+  SPI2_IRQn                   = 36,     /*!< SPI2 global Interrupt                                */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                              */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                              */
+  USART3_IRQn                 = 39,     /*!< USART3 global Interrupt                              */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                      */
+  RTCAlarm_IRQn               = 41,     /*!< RTC Alarm through EXTI Line Interrupt                */
+  USBWakeUp_IRQn              = 42,     /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */
+  TIM8_BRK_IRQn               = 43,     /*!< TIM8 Break Interrupt                                 */
+  TIM8_UP_IRQn                = 44,     /*!< TIM8 Update Interrupt                                */
+  TIM8_TRG_COM_IRQn           = 45,     /*!< TIM8 Trigger and Commutation Interrupt               */
+  TIM8_CC_IRQn                = 46,     /*!< TIM8 Capture Compare Interrupt                       */
+  ADC3_IRQn                   = 47,     /*!< ADC3 global Interrupt                                */
+  FSMC_IRQn                   = 48,     /*!< FSMC global Interrupt                                */
+  SDIO_IRQn                   = 49,     /*!< SDIO global Interrupt                                */
+  TIM5_IRQn                   = 50,     /*!< TIM5 global Interrupt                                */
+  SPI3_IRQn                   = 51,     /*!< SPI3 global Interrupt                                */
+  UART4_IRQn                  = 52,     /*!< UART4 global Interrupt                               */
+  UART5_IRQn                  = 53,     /*!< UART5 global Interrupt                               */
+  TIM6_IRQn                   = 54,     /*!< TIM6 global Interrupt                                */
+  TIM7_IRQn                   = 55,     /*!< TIM7 global Interrupt                                */
+  DMA2_Channel1_IRQn          = 56,     /*!< DMA2 Channel 1 global Interrupt                      */
+  DMA2_Channel2_IRQn          = 57,     /*!< DMA2 Channel 2 global Interrupt                      */
+  DMA2_Channel3_IRQn          = 58,     /*!< DMA2 Channel 3 global Interrupt                      */
+  DMA2_Channel4_5_IRQn        = 59      /*!< DMA2 Channel 4 and Channel 5 global Interrupt        */
+#endif /* STM32F10X_HD */  
+
+#ifdef STM32F10X_CL
+  CAN1_TX_IRQn                = 19,     /*!< USB Device High Priority or CAN1 TX Interrupts       */
+  CAN1_RX0_IRQn               = 20,     /*!< USB Device Low Priority or CAN1 RX0 Interrupts       */
+  CAN1_RX1_IRQn               = 21,     /*!< CAN1 RX1 Interrupt                                   */
+  CAN1_SCE_IRQn               = 22,     /*!< CAN1 SCE Interrupt                                   */
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                        */
+  TIM1_BRK_IRQn               = 24,     /*!< TIM1 Break Interrupt                                 */
+  TIM1_UP_IRQn                = 25,     /*!< TIM1 Update Interrupt                                */
+  TIM1_TRG_COM_IRQn           = 26,     /*!< TIM1 Trigger and Commutation Interrupt               */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                       */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                */
+  TIM4_IRQn                   = 30,     /*!< TIM4 global Interrupt                                */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                 */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                 */
+  I2C2_EV_IRQn                = 33,     /*!< I2C2 Event Interrupt                                 */
+  I2C2_ER_IRQn                = 34,     /*!< I2C2 Error Interrupt                                 */
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                */
+  SPI2_IRQn                   = 36,     /*!< SPI2 global Interrupt                                */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                              */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                              */
+  USART3_IRQn                 = 39,     /*!< USART3 global Interrupt                              */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                      */
+  RTCAlarm_IRQn               = 41,     /*!< RTC Alarm through EXTI Line Interrupt                */
+  OTG_FS_WKUP_IRQn            = 42,     /*!< USB OTG FS WakeUp from suspend through EXTI Line Interrupt */
+  TIM5_IRQn                   = 50,     /*!< TIM5 global Interrupt                                */
+  SPI3_IRQn                   = 51,     /*!< SPI3 global Interrupt                                */
+  UART4_IRQn                  = 52,     /*!< UART4 global Interrupt                               */
+  UART5_IRQn                  = 53,     /*!< UART5 global Interrupt                               */
+  TIM6_IRQn                   = 54,     /*!< TIM6 global Interrupt                                */
+  TIM7_IRQn                   = 55,     /*!< TIM7 global Interrupt                                */
+  DMA2_Channel1_IRQn          = 56,     /*!< DMA2 Channel 1 global Interrupt                      */
+  DMA2_Channel2_IRQn          = 57,     /*!< DMA2 Channel 2 global Interrupt                      */
+  DMA2_Channel3_IRQn          = 58,     /*!< DMA2 Channel 3 global Interrupt                      */
+  DMA2_Channel4_IRQn          = 59,     /*!< DMA2 Channel 4 global Interrupt                      */
+  DMA2_Channel5_IRQn          = 60,     /*!< DMA2 Channel 5 global Interrupt                      */
+  ETH_IRQn                    = 61,     /*!< Ethernet global Interrupt                            */
+  ETH_WKUP_IRQn               = 62,     /*!< Ethernet Wakeup through EXTI line Interrupt          */
+  CAN2_TX_IRQn                = 63,     /*!< CAN2 TX Interrupt                                    */
+  CAN2_RX0_IRQn               = 64,     /*!< CAN2 RX0 Interrupt                                   */
+  CAN2_RX1_IRQn               = 65,     /*!< CAN2 RX1 Interrupt                                   */
+  CAN2_SCE_IRQn               = 66,     /*!< CAN2 SCE Interrupt                                   */
+  OTG_FS_IRQn                 = 67      /*!< USB OTG FS global Interrupt                          */
+#endif /* STM32F10X_CL */     
+} IRQn_Type;
+
+/**
+  * @}
+  */
+
+#include "core_cm3.h"
+#include "system_stm32f10x.h"
+#include <stdint.h>
+
+/** @addtogroup Exported_types
+  * @{
+  */  
+
+/*!< STM32F10x Standard Peripheral Library old types (maintained for legacy purpose) */
+typedef int32_t  s32;
+typedef int16_t s16;
+typedef int8_t  s8;
+
+typedef const int32_t sc32;  /*!< Read Only */
+typedef const int16_t sc16;  /*!< Read Only */
+typedef const int8_t sc8;   /*!< Read Only */
+
+typedef __IO int32_t  vs32;
+typedef __IO int16_t  vs16;
+typedef __IO int8_t   vs8;
+
+typedef __I int32_t vsc32;  /*!< Read Only */
+typedef __I int16_t vsc16;  /*!< Read Only */
+typedef __I int8_t vsc8;   /*!< Read Only */
+
+typedef uint32_t  u32;
+typedef uint16_t u16;
+typedef uint8_t  u8;
+
+typedef const uint32_t uc32;  /*!< Read Only */
+typedef const uint16_t uc16;  /*!< Read Only */
+typedef const uint8_t uc8;   /*!< Read Only */
+
+typedef __IO uint32_t  vu32;
+typedef __IO uint16_t vu16;
+typedef __IO uint8_t  vu8;
+
+typedef __I uint32_t vuc32;  /*!< Read Only */
+typedef __I uint16_t vuc16;  /*!< Read Only */
+typedef __I uint8_t vuc8;   /*!< Read Only */
+
+#ifndef __cplusplus
+typedef enum {FALSE = 0, TRUE = !FALSE} bool;
+#endif
+
+typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;
+
+typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
+#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
+
+typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
+
+/**
+  * @}
+  */
+
+/** @addtogroup Peripheral_registers_structures
+  * @{
+  */   
+
+/** 
+  * @brief Analog to Digital Converter  
+  */
+
+typedef struct
+{
+  __IO uint32_t SR;
+  __IO uint32_t CR1;
+  __IO uint32_t CR2;
+  __IO uint32_t SMPR1;
+  __IO uint32_t SMPR2;
+  __IO uint32_t JOFR1;
+  __IO uint32_t JOFR2;
+  __IO uint32_t JOFR3;
+  __IO uint32_t JOFR4;
+  __IO uint32_t HTR;
+  __IO uint32_t LTR;
+  __IO uint32_t SQR1;
+  __IO uint32_t SQR2;
+  __IO uint32_t SQR3;
+  __IO uint32_t JSQR;
+  __IO uint32_t JDR1;
+  __IO uint32_t JDR2;
+  __IO uint32_t JDR3;
+  __IO uint32_t JDR4;
+  __IO uint32_t DR;
+} ADC_TypeDef;
+
+/** 
+  * @brief Backup Registers  
+  */
+
+typedef struct
+{
+  uint32_t  RESERVED0;
+  __IO uint16_t DR1;
+  uint16_t  RESERVED1;
+  __IO uint16_t DR2;
+  uint16_t  RESERVED2;
+  __IO uint16_t DR3;
+  uint16_t  RESERVED3;
+  __IO uint16_t DR4;
+  uint16_t  RESERVED4;
+  __IO uint16_t DR5;
+  uint16_t  RESERVED5;
+  __IO uint16_t DR6;
+  uint16_t  RESERVED6;
+  __IO uint16_t DR7;
+  uint16_t  RESERVED7;
+  __IO uint16_t DR8;
+  uint16_t  RESERVED8;
+  __IO uint16_t DR9;
+  uint16_t  RESERVED9;
+  __IO uint16_t DR10;
+  uint16_t  RESERVED10; 
+  __IO uint16_t RTCCR;
+  uint16_t  RESERVED11;
+  __IO uint16_t CR;
+  uint16_t  RESERVED12;
+  __IO uint16_t CSR;
+  uint16_t  RESERVED13[5];
+  __IO uint16_t DR11;
+  uint16_t  RESERVED14;
+  __IO uint16_t DR12;
+  uint16_t  RESERVED15;
+  __IO uint16_t DR13;
+  uint16_t  RESERVED16;
+  __IO uint16_t DR14;
+  uint16_t  RESERVED17;
+  __IO uint16_t DR15;
+  uint16_t  RESERVED18;
+  __IO uint16_t DR16;
+  uint16_t  RESERVED19;
+  __IO uint16_t DR17;
+  uint16_t  RESERVED20;
+  __IO uint16_t DR18;
+  uint16_t  RESERVED21;
+  __IO uint16_t DR19;
+  uint16_t  RESERVED22;
+  __IO uint16_t DR20;
+  uint16_t  RESERVED23;
+  __IO uint16_t DR21;
+  uint16_t  RESERVED24;
+  __IO uint16_t DR22;
+  uint16_t  RESERVED25;
+  __IO uint16_t DR23;
+  uint16_t  RESERVED26;
+  __IO uint16_t DR24;
+  uint16_t  RESERVED27;
+  __IO uint16_t DR25;
+  uint16_t  RESERVED28;
+  __IO uint16_t DR26;
+  uint16_t  RESERVED29;
+  __IO uint16_t DR27;
+  uint16_t  RESERVED30;
+  __IO uint16_t DR28;
+  uint16_t  RESERVED31;
+  __IO uint16_t DR29;
+  uint16_t  RESERVED32;
+  __IO uint16_t DR30;
+  uint16_t  RESERVED33; 
+  __IO uint16_t DR31;
+  uint16_t  RESERVED34;
+  __IO uint16_t DR32;
+  uint16_t  RESERVED35;
+  __IO uint16_t DR33;
+  uint16_t  RESERVED36;
+  __IO uint16_t DR34;
+  uint16_t  RESERVED37;
+  __IO uint16_t DR35;
+  uint16_t  RESERVED38;
+  __IO uint16_t DR36;
+  uint16_t  RESERVED39;
+  __IO uint16_t DR37;
+  uint16_t  RESERVED40;
+  __IO uint16_t DR38;
+  uint16_t  RESERVED41;
+  __IO uint16_t DR39;
+  uint16_t  RESERVED42;
+  __IO uint16_t DR40;
+  uint16_t  RESERVED43;
+  __IO uint16_t DR41;
+  uint16_t  RESERVED44;
+  __IO uint16_t DR42;
+  uint16_t  RESERVED45;    
+} BKP_TypeDef;
+
+/** 
+  * @brief Controller Area Network TxMailBox 
+  */
+
+typedef struct
+{
+  __IO uint32_t TIR;
+  __IO uint32_t TDTR;
+  __IO uint32_t TDLR;
+  __IO uint32_t TDHR;
+} CAN_TxMailBox_TypeDef;
+
+/** 
+  * @brief Controller Area Network FIFOMailBox 
+  */
+  
+typedef struct
+{
+  __IO uint32_t RIR;
+  __IO uint32_t RDTR;
+  __IO uint32_t RDLR;
+  __IO uint32_t RDHR;
+} CAN_FIFOMailBox_TypeDef;
+
+/** 
+  * @brief Controller Area Network FilterRegister 
+  */
+  
+typedef struct
+{
+  __IO uint32_t FR1;
+  __IO uint32_t FR2;
+} CAN_FilterRegister_TypeDef;
+
+/** 
+  * @brief Controller Area Network 
+  */
+  
+typedef struct
+{
+  __IO uint32_t MCR;
+  __IO uint32_t MSR;
+  __IO uint32_t TSR;
+  __IO uint32_t RF0R;
+  __IO uint32_t RF1R;
+  __IO uint32_t IER;
+  __IO uint32_t ESR;
+  __IO uint32_t BTR;
+  uint32_t  RESERVED0[88];
+  CAN_TxMailBox_TypeDef sTxMailBox[3];
+  CAN_FIFOMailBox_TypeDef sFIFOMailBox[2];
+  uint32_t  RESERVED1[12];
+  __IO uint32_t FMR;
+  __IO uint32_t FM1R;
+  uint32_t  RESERVED2;
+  __IO uint32_t FS1R;
+  uint32_t  RESERVED3;
+  __IO uint32_t FFA1R;
+  uint32_t  RESERVED4;
+  __IO uint32_t FA1R;
+  uint32_t  RESERVED5[8];
+#ifndef STM32F10X_CL
+  CAN_FilterRegister_TypeDef sFilterRegister[14];
+#else
+  CAN_FilterRegister_TypeDef sFilterRegister[28];
+#endif /* STM32F10X_CL */  
+} CAN_TypeDef;
+
+/** 
+  * @brief CRC calculation unit 
+  */
+
+typedef struct
+{
+  __IO uint32_t DR;
+  __IO uint8_t  IDR;
+  uint8_t   RESERVED0;
+  uint16_t  RESERVED1;
+  __IO uint32_t CR;
+} CRC_TypeDef;
+
+/** 
+  * @brief Digital to Analog Converter
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;
+  __IO uint32_t SWTRIGR;
+  __IO uint32_t DHR12R1;
+  __IO uint32_t DHR12L1;
+  __IO uint32_t DHR8R1;
+  __IO uint32_t DHR12R2;
+  __IO uint32_t DHR12L2;
+  __IO uint32_t DHR8R2;
+  __IO uint32_t DHR12RD;
+  __IO uint32_t DHR12LD;
+  __IO uint32_t DHR8RD;
+  __IO uint32_t DOR1;
+  __IO uint32_t DOR2;
+} DAC_TypeDef;
+
+/** 
+  * @brief Debug MCU
+  */
+
+typedef struct
+{
+  __IO uint32_t IDCODE;
+  __IO uint32_t CR;	
+}DBGMCU_TypeDef;
+
+/** 
+  * @brief DMA Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t CCR;
+  __IO uint32_t CNDTR;
+  __IO uint32_t CPAR;
+  __IO uint32_t CMAR;
+} DMA_Channel_TypeDef;
+
+typedef struct
+{
+  __IO uint32_t ISR;
+  __IO uint32_t IFCR;
+} DMA_TypeDef;
+
+/** 
+  * @brief Ethernet MAC
+  */
+
+typedef struct
+{
+  __IO uint32_t MACCR;
+  __IO uint32_t MACFFR;
+  __IO uint32_t MACHTHR;
+  __IO uint32_t MACHTLR;
+  __IO uint32_t MACMIIAR;
+  __IO uint32_t MACMIIDR;
+  __IO uint32_t MACFCR;
+  __IO uint32_t MACVLANTR;             /*    8 */
+       uint32_t RESERVED0[2];
+  __IO uint32_t MACRWUFFR;             /*   11 */
+  __IO uint32_t MACPMTCSR;
+       uint32_t RESERVED1[2];
+  __IO uint32_t MACSR;                 /*   15 */
+  __IO uint32_t MACIMR;
+  __IO uint32_t MACA0HR;
+  __IO uint32_t MACA0LR;
+  __IO uint32_t MACA1HR;
+  __IO uint32_t MACA1LR;
+  __IO uint32_t MACA2HR;
+  __IO uint32_t MACA2LR;
+  __IO uint32_t MACA3HR;
+  __IO uint32_t MACA3LR;               /*   24 */
+       uint32_t RESERVED2[40];
+  __IO uint32_t MMCCR;                 /*   65 */
+  __IO uint32_t MMCRIR;
+  __IO uint32_t MMCTIR;
+  __IO uint32_t MMCRIMR;
+  __IO uint32_t MMCTIMR;               /*   69 */
+       uint32_t RESERVED3[14];
+  __IO uint32_t MMCTGFSCCR;            /*   84 */
+  __IO uint32_t MMCTGFMSCCR;
+       uint32_t RESERVED4[5];
+  __IO uint32_t MMCTGFCR;
+       uint32_t RESERVED5[10];
+  __IO uint32_t MMCRFCECR;
+  __IO uint32_t MMCRFAECR;
+       uint32_t RESERVED6[10];
+  __IO uint32_t MMCRGUFCR;
+       uint32_t RESERVED7[334];
+  __IO uint32_t PTPTSCR;
+  __IO uint32_t PTPSSIR;
+  __IO uint32_t PTPTSHR;
+  __IO uint32_t PTPTSLR;
+  __IO uint32_t PTPTSHUR;
+  __IO uint32_t PTPTSLUR;
+  __IO uint32_t PTPTSAR;
+  __IO uint32_t PTPTTHR;
+  __IO uint32_t PTPTTLR;
+       uint32_t RESERVED8[567];
+  __IO uint32_t DMABMR;
+  __IO uint32_t DMATPDR;
+  __IO uint32_t DMARPDR;
+  __IO uint32_t DMARDLAR;
+  __IO uint32_t DMATDLAR;
+  __IO uint32_t DMASR;
+  __IO uint32_t DMAOMR;
+  __IO uint32_t DMAIER;
+  __IO uint32_t DMAMFBOCR;
+       uint32_t RESERVED9[9];
+  __IO uint32_t DMACHTDR;
+  __IO uint32_t DMACHRDR;
+  __IO uint32_t DMACHTBAR;
+  __IO uint32_t DMACHRBAR;
+} ETH_TypeDef;
+
+/** 
+  * @brief External Interrupt/Event Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t IMR;
+  __IO uint32_t EMR;
+  __IO uint32_t RTSR;
+  __IO uint32_t FTSR;
+  __IO uint32_t SWIER;
+  __IO uint32_t PR;
+} EXTI_TypeDef;
+
+/** 
+  * @brief FLASH Registers
+  */
+
+typedef struct
+{
+  __IO uint32_t ACR;
+  __IO uint32_t KEYR;
+  __IO uint32_t OPTKEYR;
+  __IO uint32_t SR;
+  __IO uint32_t CR;
+  __IO uint32_t AR;
+  __IO uint32_t RESERVED;
+  __IO uint32_t OBR;
+  __IO uint32_t WRPR;
+} FLASH_TypeDef;
+
+/** 
+  * @brief Option Bytes Registers
+  */
+  
+typedef struct
+{
+  __IO uint16_t RDP;
+  __IO uint16_t USER;
+  __IO uint16_t Data0;
+  __IO uint16_t Data1;
+  __IO uint16_t WRP0;
+  __IO uint16_t WRP1;
+  __IO uint16_t WRP2;
+  __IO uint16_t WRP3;
+} OB_TypeDef;
+
+/** 
+  * @brief Flexible Static Memory Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t BTCR[8];   
+} FSMC_Bank1_TypeDef; 
+
+/** 
+  * @brief Flexible Static Memory Controller Bank1E
+  */
+  
+typedef struct
+{
+  __IO uint32_t BWTR[7];
+} FSMC_Bank1E_TypeDef;
+
+/** 
+  * @brief Flexible Static Memory Controller Bank2
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR2;
+  __IO uint32_t SR2;
+  __IO uint32_t PMEM2;
+  __IO uint32_t PATT2;
+  uint32_t  RESERVED0;   
+  __IO uint32_t ECCR2; 
+} FSMC_Bank2_TypeDef;  
+
+/** 
+  * @brief Flexible Static Memory Controller Bank3
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR3;
+  __IO uint32_t SR3;
+  __IO uint32_t PMEM3;
+  __IO uint32_t PATT3;
+  uint32_t  RESERVED0;   
+  __IO uint32_t ECCR3; 
+} FSMC_Bank3_TypeDef; 
+
+/** 
+  * @brief Flexible Static Memory Controller Bank4
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR4;
+  __IO uint32_t SR4;
+  __IO uint32_t PMEM4;
+  __IO uint32_t PATT4;
+  __IO uint32_t PIO4; 
+} FSMC_Bank4_TypeDef; 
+
+/** 
+  * @brief General Purpose I/O
+  */
+
+typedef struct
+{
+  __IO uint32_t CRL;
+  __IO uint32_t CRH;
+  __IO uint32_t IDR;
+  __IO uint32_t ODR;
+  __IO uint32_t BSRR;
+  __IO uint32_t BRR;
+  __IO uint32_t LCKR;
+} GPIO_TypeDef;
+
+/** 
+  * @brief Alternate Function I/O
+  */
+
+typedef struct
+{
+  __IO uint32_t EVCR;
+  __IO uint32_t MAPR;
+  __IO uint32_t EXTICR[4];
+} AFIO_TypeDef;
+/** 
+  * @brief Inter-integrated Circuit Interface
+  */
+
+typedef struct
+{
+  __IO uint16_t CR1;
+  uint16_t  RESERVED0;
+  __IO uint16_t CR2;
+  uint16_t  RESERVED1;
+  __IO uint16_t OAR1;
+  uint16_t  RESERVED2;
+  __IO uint16_t OAR2;
+  uint16_t  RESERVED3;
+  __IO uint16_t DR;
+  uint16_t  RESERVED4;
+  __IO uint16_t SR1;
+  uint16_t  RESERVED5;
+  __IO uint16_t SR2;
+  uint16_t  RESERVED6;
+  __IO uint16_t CCR;
+  uint16_t  RESERVED7;
+  __IO uint16_t TRISE;
+  uint16_t  RESERVED8;
+} I2C_TypeDef;
+
+/** 
+  * @brief Independent WATCHDOG
+  */
+
+typedef struct
+{
+  __IO uint32_t KR;
+  __IO uint32_t PR;
+  __IO uint32_t RLR;
+  __IO uint32_t SR;
+} IWDG_TypeDef;
+
+/** 
+  * @brief Power Control
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;
+  __IO uint32_t CSR;
+} PWR_TypeDef;
+
+/** 
+  * @brief Reset and Clock Control
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;
+  __IO uint32_t CFGR;
+  __IO uint32_t CIR;
+  __IO uint32_t APB2RSTR;
+  __IO uint32_t APB1RSTR;
+  __IO uint32_t AHBENR;
+  __IO uint32_t APB2ENR;
+  __IO uint32_t APB1ENR;
+  __IO uint32_t BDCR;
+  __IO uint32_t CSR;
+#ifdef STM32F10X_CL  
+  __IO uint32_t AHBRSTR;
+  __IO uint32_t CFGR2;
+#endif /* STM32F10X_CL */ 
+} RCC_TypeDef;
+
+/** 
+  * @brief Real-Time Clock
+  */
+
+typedef struct
+{
+  __IO uint16_t CRH;
+  uint16_t  RESERVED0;
+  __IO uint16_t CRL;
+  uint16_t  RESERVED1;
+  __IO uint16_t PRLH;
+  uint16_t  RESERVED2;
+  __IO uint16_t PRLL;
+  uint16_t  RESERVED3;
+  __IO uint16_t DIVH;
+  uint16_t  RESERVED4;
+  __IO uint16_t DIVL;
+  uint16_t  RESERVED5;
+  __IO uint16_t CNTH;
+  uint16_t  RESERVED6;
+  __IO uint16_t CNTL;
+  uint16_t  RESERVED7;
+  __IO uint16_t ALRH;
+  uint16_t  RESERVED8;
+  __IO uint16_t ALRL;
+  uint16_t  RESERVED9;
+} RTC_TypeDef;
+
+/** 
+  * @brief SD host Interface
+  */
+
+typedef struct
+{
+  __IO uint32_t POWER;
+  __IO uint32_t CLKCR;
+  __IO uint32_t ARG;
+  __IO uint32_t CMD;
+  __I uint32_t RESPCMD;
+  __I uint32_t RESP1;
+  __I uint32_t RESP2;
+  __I uint32_t RESP3;
+  __I uint32_t RESP4;
+  __IO uint32_t DTIMER;
+  __IO uint32_t DLEN;
+  __IO uint32_t DCTRL;
+  __I uint32_t DCOUNT;
+  __I uint32_t STA;
+  __IO uint32_t ICR;
+  __IO uint32_t MASK;
+  uint32_t  RESERVED0[2];
+  __I uint32_t FIFOCNT;
+  uint32_t  RESERVED1[13];
+  __IO uint32_t FIFO;
+} SDIO_TypeDef;
+
+/** 
+  * @brief Serial Peripheral Interface
+  */
+
+typedef struct
+{
+  __IO uint16_t CR1;
+  uint16_t  RESERVED0;
+  __IO uint16_t CR2;
+  uint16_t  RESERVED1;
+  __IO uint16_t SR;
+  uint16_t  RESERVED2;
+  __IO uint16_t DR;
+  uint16_t  RESERVED3;
+  __IO uint16_t CRCPR;
+  uint16_t  RESERVED4;
+  __IO uint16_t RXCRCR;
+  uint16_t  RESERVED5;
+  __IO uint16_t TXCRCR;
+  uint16_t  RESERVED6;
+  __IO uint16_t I2SCFGR;
+  uint16_t  RESERVED7;
+  __IO uint16_t I2SPR;
+  uint16_t  RESERVED8;  
+} SPI_TypeDef;
+
+/** 
+  * @brief TIM
+  */
+
+typedef struct
+{
+  __IO uint16_t CR1;
+  uint16_t  RESERVED0;
+  __IO uint16_t CR2;
+  uint16_t  RESERVED1;
+  __IO uint16_t SMCR;
+  uint16_t  RESERVED2;
+  __IO uint16_t DIER;
+  uint16_t  RESERVED3;
+  __IO uint16_t SR;
+  uint16_t  RESERVED4;
+  __IO uint16_t EGR;
+  uint16_t  RESERVED5;
+  __IO uint16_t CCMR1;
+  uint16_t  RESERVED6;
+  __IO uint16_t CCMR2;
+  uint16_t  RESERVED7;
+  __IO uint16_t CCER;
+  uint16_t  RESERVED8;
+  __IO uint16_t CNT;
+  uint16_t  RESERVED9;
+  __IO uint16_t PSC;
+  uint16_t  RESERVED10;
+  __IO uint16_t ARR;
+  uint16_t  RESERVED11;
+  __IO uint16_t RCR;
+  uint16_t  RESERVED12;
+  __IO uint16_t CCR1;
+  uint16_t  RESERVED13;
+  __IO uint16_t CCR2;
+  uint16_t  RESERVED14;
+  __IO uint16_t CCR3;
+  uint16_t  RESERVED15;
+  __IO uint16_t CCR4;
+  uint16_t  RESERVED16;
+  __IO uint16_t BDTR;
+  uint16_t  RESERVED17;
+  __IO uint16_t DCR;
+  uint16_t  RESERVED18;
+  __IO uint16_t DMAR;
+  uint16_t  RESERVED19;
+} TIM_TypeDef;
+
+/** 
+  * @brief Universal Synchronous Asynchronous Receiver Transmitter
+  */
+ 
+typedef struct
+{
+  __IO uint16_t SR;
+  uint16_t  RESERVED0;
+  __IO uint16_t DR;
+  uint16_t  RESERVED1;
+  __IO uint16_t BRR;
+  uint16_t  RESERVED2;
+  __IO uint16_t CR1;
+  uint16_t  RESERVED3;
+  __IO uint16_t CR2;
+  uint16_t  RESERVED4;
+  __IO uint16_t CR3;
+  uint16_t  RESERVED5;
+  __IO uint16_t GTPR;
+  uint16_t  RESERVED6;
+} USART_TypeDef;
+
+/** 
+  * @brief Window WATCHDOG
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;
+  __IO uint32_t CFR;
+  __IO uint32_t SR;
+} WWDG_TypeDef;
+
+/**
+  * @}
+  */
+  
+/** @addtogroup Peripheral_memory_map
+  * @{
+  */
+
+#define PERIPH_BB_BASE        ((uint32_t)0x42000000) /*!< Peripheral base address in the alias region */
+#define SRAM_BB_BASE          ((uint32_t)0x22000000) /*!< SRAM base address in the alias region */
+
+#define SRAM_BASE             ((uint32_t)0x20000000) /*!< Peripheral base address in the bit-band region */
+#define PERIPH_BASE           ((uint32_t)0x40000000) /*!< SRAM base address in the bit-band region */
+
+#define FSMC_R_BASE           ((uint32_t)0xA0000000) /*!< FSMC registers base address */
+
+/*!< Peripheral memory map */
+#define APB1PERIPH_BASE       PERIPH_BASE
+#define APB2PERIPH_BASE       (PERIPH_BASE + 0x10000)
+#define AHBPERIPH_BASE        (PERIPH_BASE + 0x20000)
+
+#define TIM2_BASE             (APB1PERIPH_BASE + 0x0000)
+#define TIM3_BASE             (APB1PERIPH_BASE + 0x0400)
+#define TIM4_BASE             (APB1PERIPH_BASE + 0x0800)
+#define TIM5_BASE             (APB1PERIPH_BASE + 0x0C00)
+#define TIM6_BASE             (APB1PERIPH_BASE + 0x1000)
+#define TIM7_BASE             (APB1PERIPH_BASE + 0x1400)
+#define RTC_BASE              (APB1PERIPH_BASE + 0x2800)
+#define WWDG_BASE             (APB1PERIPH_BASE + 0x2C00)
+#define IWDG_BASE             (APB1PERIPH_BASE + 0x3000)
+#define SPI2_BASE             (APB1PERIPH_BASE + 0x3800)
+#define SPI3_BASE             (APB1PERIPH_BASE + 0x3C00)
+#define USART2_BASE           (APB1PERIPH_BASE + 0x4400)
+#define USART3_BASE           (APB1PERIPH_BASE + 0x4800)
+#define UART4_BASE            (APB1PERIPH_BASE + 0x4C00)
+#define UART5_BASE            (APB1PERIPH_BASE + 0x5000)
+#define I2C1_BASE             (APB1PERIPH_BASE + 0x5400)
+#define I2C2_BASE             (APB1PERIPH_BASE + 0x5800)
+#define CAN1_BASE             (APB1PERIPH_BASE + 0x6400)
+#define CAN2_BASE             (APB1PERIPH_BASE + 0x6800)
+#define BKP_BASE              (APB1PERIPH_BASE + 0x6C00)
+#define PWR_BASE              (APB1PERIPH_BASE + 0x7000)
+#define DAC_BASE              (APB1PERIPH_BASE + 0x7400)
+
+#define AFIO_BASE             (APB2PERIPH_BASE + 0x0000)
+#define EXTI_BASE             (APB2PERIPH_BASE + 0x0400)
+#define GPIOA_BASE            (APB2PERIPH_BASE + 0x0800)
+#define GPIOB_BASE            (APB2PERIPH_BASE + 0x0C00)
+#define GPIOC_BASE            (APB2PERIPH_BASE + 0x1000)
+#define GPIOD_BASE            (APB2PERIPH_BASE + 0x1400)
+#define GPIOE_BASE            (APB2PERIPH_BASE + 0x1800)
+#define GPIOF_BASE            (APB2PERIPH_BASE + 0x1C00)
+#define GPIOG_BASE            (APB2PERIPH_BASE + 0x2000)
+#define ADC1_BASE             (APB2PERIPH_BASE + 0x2400)
+#define ADC2_BASE             (APB2PERIPH_BASE + 0x2800)
+#define TIM1_BASE             (APB2PERIPH_BASE + 0x2C00)
+#define SPI1_BASE             (APB2PERIPH_BASE + 0x3000)
+#define TIM8_BASE             (APB2PERIPH_BASE + 0x3400)
+#define USART1_BASE           (APB2PERIPH_BASE + 0x3800)
+#define ADC3_BASE             (APB2PERIPH_BASE + 0x3C00)
+
+#define SDIO_BASE             (PERIPH_BASE + 0x18000)
+
+#define DMA1_BASE             (AHBPERIPH_BASE + 0x0000)
+#define DMA1_Channel1_BASE    (AHBPERIPH_BASE + 0x0008)
+#define DMA1_Channel2_BASE    (AHBPERIPH_BASE + 0x001C)
+#define DMA1_Channel3_BASE    (AHBPERIPH_BASE + 0x0030)
+#define DMA1_Channel4_BASE    (AHBPERIPH_BASE + 0x0044)
+#define DMA1_Channel5_BASE    (AHBPERIPH_BASE + 0x0058)
+#define DMA1_Channel6_BASE    (AHBPERIPH_BASE + 0x006C)
+#define DMA1_Channel7_BASE    (AHBPERIPH_BASE + 0x0080)
+#define DMA2_BASE             (AHBPERIPH_BASE + 0x0400)
+#define DMA2_Channel1_BASE    (AHBPERIPH_BASE + 0x0408)
+#define DMA2_Channel2_BASE    (AHBPERIPH_BASE + 0x041C)
+#define DMA2_Channel3_BASE    (AHBPERIPH_BASE + 0x0430)
+#define DMA2_Channel4_BASE    (AHBPERIPH_BASE + 0x0444)
+#define DMA2_Channel5_BASE    (AHBPERIPH_BASE + 0x0458)
+#define RCC_BASE              (AHBPERIPH_BASE + 0x1000)
+#define CRC_BASE              (AHBPERIPH_BASE + 0x3000)
+
+#define FLASH_R_BASE          (AHBPERIPH_BASE + 0x2000) /*!< Flash registers base address */
+#define OB_BASE               ((uint32_t)0x1FFFF800)    /*!< Flash Option Bytes base address */
+
+#define ETH_BASE              (AHBPERIPH_BASE + 0x8000)
+#define ETH_MAC_BASE          (ETH_BASE)
+#define ETH_MMC_BASE          (ETH_BASE + 0x0100)
+#define ETH_PTP_BASE          (ETH_BASE + 0x0700)
+#define ETH_DMA_BASE          (ETH_BASE + 0x1000)
+
+#define FSMC_Bank1_R_BASE     (FSMC_R_BASE + 0x0000) /*!< FSMC Bank1 registers base address */
+#define FSMC_Bank1E_R_BASE    (FSMC_R_BASE + 0x0104) /*!< FSMC Bank1E registers base address */
+#define FSMC_Bank2_R_BASE     (FSMC_R_BASE + 0x0060) /*!< FSMC Bank2 registers base address */
+#define FSMC_Bank3_R_BASE     (FSMC_R_BASE + 0x0080) /*!< FSMC Bank3 registers base address */
+#define FSMC_Bank4_R_BASE     (FSMC_R_BASE + 0x00A0) /*!< FSMC Bank4 registers base address */
+
+#define DBGMCU_BASE          ((uint32_t)0xE0042000) /*!< Debug MCU registers base address */
+
+/**
+  * @}
+  */
+  
+/** @addtogroup Peripheral_declaration
+  * @{
+  */  
+
+#define TIM2                ((TIM_TypeDef *) TIM2_BASE)
+#define TIM3                ((TIM_TypeDef *) TIM3_BASE)
+#define TIM4                ((TIM_TypeDef *) TIM4_BASE)
+#define TIM5                ((TIM_TypeDef *) TIM5_BASE)
+#define TIM6                ((TIM_TypeDef *) TIM6_BASE)
+#define TIM7                ((TIM_TypeDef *) TIM7_BASE)
+#define RTC                 ((RTC_TypeDef *) RTC_BASE)
+#define WWDG                ((WWDG_TypeDef *) WWDG_BASE)
+#define IWDG                ((IWDG_TypeDef *) IWDG_BASE)
+#define SPI2                ((SPI_TypeDef *) SPI2_BASE)
+#define SPI3                ((SPI_TypeDef *) SPI3_BASE)
+#define USART2              ((USART_TypeDef *) USART2_BASE)
+#define USART3              ((USART_TypeDef *) USART3_BASE)
+#define UART4               ((USART_TypeDef *) UART4_BASE)
+#define UART5               ((USART_TypeDef *) UART5_BASE)
+#define I2C1                ((I2C_TypeDef *) I2C1_BASE)
+#define I2C2                ((I2C_TypeDef *) I2C2_BASE)
+#define CAN1                ((CAN_TypeDef *) CAN1_BASE)
+#define CAN2                ((CAN_TypeDef *) CAN2_BASE)
+#define BKP                 ((BKP_TypeDef *) BKP_BASE)
+#define PWR                 ((PWR_TypeDef *) PWR_BASE)
+#define DAC                 ((DAC_TypeDef *) DAC_BASE)
+#define AFIO                ((AFIO_TypeDef *) AFIO_BASE)
+#define EXTI                ((EXTI_TypeDef *) EXTI_BASE)
+#define GPIOA               ((GPIO_TypeDef *) GPIOA_BASE)
+#define GPIOB               ((GPIO_TypeDef *) GPIOB_BASE)
+#define GPIOC               ((GPIO_TypeDef *) GPIOC_BASE)
+#define GPIOD               ((GPIO_TypeDef *) GPIOD_BASE)
+#define GPIOE               ((GPIO_TypeDef *) GPIOE_BASE)
+#define GPIOF               ((GPIO_TypeDef *) GPIOF_BASE)
+#define GPIOG               ((GPIO_TypeDef *) GPIOG_BASE)
+#define ADC1                ((ADC_TypeDef *) ADC1_BASE)
+#define ADC2                ((ADC_TypeDef *) ADC2_BASE)
+#define TIM1                ((TIM_TypeDef *) TIM1_BASE)
+#define SPI1                ((SPI_TypeDef *) SPI1_BASE)
+#define TIM8                ((TIM_TypeDef *) TIM8_BASE)
+#define USART1              ((USART_TypeDef *) USART1_BASE)
+#define ADC3                ((ADC_TypeDef *) ADC3_BASE)
+#define SDIO                ((SDIO_TypeDef *) SDIO_BASE)
+#define DMA1                ((DMA_TypeDef *) DMA1_BASE)
+#define DMA2                ((DMA_TypeDef *) DMA2_BASE)
+#define DMA1_Channel1       ((DMA_Channel_TypeDef *) DMA1_Channel1_BASE)
+#define DMA1_Channel2       ((DMA_Channel_TypeDef *) DMA1_Channel2_BASE)
+#define DMA1_Channel3       ((DMA_Channel_TypeDef *) DMA1_Channel3_BASE)
+#define DMA1_Channel4       ((DMA_Channel_TypeDef *) DMA1_Channel4_BASE)
+#define DMA1_Channel5       ((DMA_Channel_TypeDef *) DMA1_Channel5_BASE)
+#define DMA1_Channel6       ((DMA_Channel_TypeDef *) DMA1_Channel6_BASE)
+#define DMA1_Channel7       ((DMA_Channel_TypeDef *) DMA1_Channel7_BASE)
+#define DMA2_Channel1       ((DMA_Channel_TypeDef *) DMA2_Channel1_BASE)
+#define DMA2_Channel2       ((DMA_Channel_TypeDef *) DMA2_Channel2_BASE)
+#define DMA2_Channel3       ((DMA_Channel_TypeDef *) DMA2_Channel3_BASE)
+#define DMA2_Channel4       ((DMA_Channel_TypeDef *) DMA2_Channel4_BASE)
+#define DMA2_Channel5       ((DMA_Channel_TypeDef *) DMA2_Channel5_BASE)
+#define RCC                 ((RCC_TypeDef *) RCC_BASE)
+#define CRC                 ((CRC_TypeDef *) CRC_BASE)
+#define FLASH               ((FLASH_TypeDef *) FLASH_R_BASE)
+#define OB                  ((OB_TypeDef *) OB_BASE) 
+#define ETH                 ((ETH_TypeDef *) ETH_BASE)
+#define FSMC_Bank1          ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE)
+#define FSMC_Bank1E         ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE)
+#define FSMC_Bank2          ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE)
+#define FSMC_Bank3          ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE)
+#define FSMC_Bank4          ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE)
+#define DBGMCU              ((DBGMCU_TypeDef *) DBGMCU_BASE)
+
+/**
+  * @}
+  */
+
+/** @addtogroup Exported_constants
+  * @{
+  */
+  
+  /** @addtogroup Peripheral_Registers_Bits_Definition
+  * @{
+  */
+    
+/******************************************************************************/
+/*                         Peripheral Registers_Bits_Definition               */
+/******************************************************************************/
+
+/******************************************************************************/
+/*                                                                            */
+/*                          CRC calculation unit                              */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for CRC_DR register  *********************/
+#define  CRC_DR_DR                           ((uint32_t)0xFFFFFFFF) /*!< Data register bits */
+
+
+/*******************  Bit definition for CRC_IDR register  ********************/
+#define  CRC_IDR_IDR                         ((uint8_t)0xFF)        /*!< General-purpose 8-bit data register bits */
+
+
+/********************  Bit definition for CRC_CR register  ********************/
+#define  CRC_CR_RESET                        ((uint8_t)0x01)        /*!< RESET bit */
+
+/******************************************************************************/
+/*                                                                            */
+/*                             Power Control                                  */
+/*                                                                            */
+/******************************************************************************/
+
+/********************  Bit definition for PWR_CR register  ********************/
+#define  PWR_CR_LPDS                         ((uint16_t)0x0001)     /*!< Low-Power Deepsleep */
+#define  PWR_CR_PDDS                         ((uint16_t)0x0002)     /*!< Power Down Deepsleep */
+#define  PWR_CR_CWUF                         ((uint16_t)0x0004)     /*!< Clear Wakeup Flag */
+#define  PWR_CR_CSBF                         ((uint16_t)0x0008)     /*!< Clear Standby Flag */
+#define  PWR_CR_PVDE                         ((uint16_t)0x0010)     /*!< Power Voltage Detector Enable */
+
+#define  PWR_CR_PLS                          ((uint16_t)0x00E0)     /*!< PLS[2:0] bits (PVD Level Selection) */
+#define  PWR_CR_PLS_0                        ((uint16_t)0x0020)     /*!< Bit 0 */
+#define  PWR_CR_PLS_1                        ((uint16_t)0x0040)     /*!< Bit 1 */
+#define  PWR_CR_PLS_2                        ((uint16_t)0x0080)     /*!< Bit 2 */
+
+/*!< PVD level configuration */
+#define  PWR_CR_PLS_2V2                      ((uint16_t)0x0000)     /*!< PVD level 2.2V */
+#define  PWR_CR_PLS_2V3                      ((uint16_t)0x0020)     /*!< PVD level 2.3V */
+#define  PWR_CR_PLS_2V4                      ((uint16_t)0x0040)     /*!< PVD level 2.4V */
+#define  PWR_CR_PLS_2V5                      ((uint16_t)0x0060)     /*!< PVD level 2.5V */
+#define  PWR_CR_PLS_2V6                      ((uint16_t)0x0080)     /*!< PVD level 2.6V */
+#define  PWR_CR_PLS_2V7                      ((uint16_t)0x00A0)     /*!< PVD level 2.7V */
+#define  PWR_CR_PLS_2V8                      ((uint16_t)0x00C0)     /*!< PVD level 2.8V */
+#define  PWR_CR_PLS_2V9                      ((uint16_t)0x00E0)     /*!< PVD level 2.9V */
+
+#define  PWR_CR_DBP                          ((uint16_t)0x0100)     /*!< Disable Backup Domain write protection */
+
+
+/*******************  Bit definition for PWR_CSR register  ********************/
+#define  PWR_CSR_WUF                         ((uint16_t)0x0001)     /*!< Wakeup Flag */
+#define  PWR_CSR_SBF                         ((uint16_t)0x0002)     /*!< Standby Flag */
+#define  PWR_CSR_PVDO                        ((uint16_t)0x0004)     /*!< PVD Output */
+#define  PWR_CSR_EWUP                        ((uint16_t)0x0100)     /*!< Enable WKUP pin */
+
+/******************************************************************************/
+/*                                                                            */
+/*                            Backup registers                                */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for BKP_DR1 register  ********************/
+#define  BKP_DR1_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR2 register  ********************/
+#define  BKP_DR2_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR3 register  ********************/
+#define  BKP_DR3_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR4 register  ********************/
+#define  BKP_DR4_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR5 register  ********************/
+#define  BKP_DR5_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR6 register  ********************/
+#define  BKP_DR6_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR7 register  ********************/
+#define  BKP_DR7_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR8 register  ********************/
+#define  BKP_DR8_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR9 register  ********************/
+#define  BKP_DR9_D                           ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR10 register  *******************/
+#define  BKP_DR10_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR11 register  *******************/
+#define  BKP_DR11_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR12 register  *******************/
+#define  BKP_DR12_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR13 register  *******************/
+#define  BKP_DR13_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR14 register  *******************/
+#define  BKP_DR14_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR15 register  *******************/
+#define  BKP_DR15_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR16 register  *******************/
+#define  BKP_DR16_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR17 register  *******************/
+#define  BKP_DR17_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/******************  Bit definition for BKP_DR18 register  ********************/
+#define  BKP_DR18_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR19 register  *******************/
+#define  BKP_DR19_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR20 register  *******************/
+#define  BKP_DR20_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR21 register  *******************/
+#define  BKP_DR21_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR22 register  *******************/
+#define  BKP_DR22_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR23 register  *******************/
+#define  BKP_DR23_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR24 register  *******************/
+#define  BKP_DR24_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR25 register  *******************/
+#define  BKP_DR25_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR26 register  *******************/
+#define  BKP_DR26_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR27 register  *******************/
+#define  BKP_DR27_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR28 register  *******************/
+#define  BKP_DR28_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR29 register  *******************/
+#define  BKP_DR29_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR30 register  *******************/
+#define  BKP_DR30_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR31 register  *******************/
+#define  BKP_DR31_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR32 register  *******************/
+#define  BKP_DR32_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR33 register  *******************/
+#define  BKP_DR33_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR34 register  *******************/
+#define  BKP_DR34_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR35 register  *******************/
+#define  BKP_DR35_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR36 register  *******************/
+#define  BKP_DR36_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR37 register  *******************/
+#define  BKP_DR37_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR38 register  *******************/
+#define  BKP_DR38_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR39 register  *******************/
+#define  BKP_DR39_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR40 register  *******************/
+#define  BKP_DR40_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR41 register  *******************/
+#define  BKP_DR41_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/*******************  Bit definition for BKP_DR42 register  *******************/
+#define  BKP_DR42_D                          ((uint16_t)0xFFFF)     /*!< Backup data */
+
+/******************  Bit definition for BKP_RTCCR register  *******************/
+#define  BKP_RTCCR_CAL                       ((uint16_t)0x007F)     /*!< Calibration value */
+#define  BKP_RTCCR_CCO                       ((uint16_t)0x0080)     /*!< Calibration Clock Output */
+#define  BKP_RTCCR_ASOE                      ((uint16_t)0x0100)     /*!< Alarm or Second Output Enable */
+#define  BKP_RTCCR_ASOS                      ((uint16_t)0x0200)     /*!< Alarm or Second Output Selection */
+
+/********************  Bit definition for BKP_CR register  ********************/
+#define  BKP_CR_TPE                          ((uint8_t)0x01)        /*!< TAMPER pin enable */
+#define  BKP_CR_TPAL                         ((uint8_t)0x02)        /*!< TAMPER pin active level */
+
+/*******************  Bit definition for BKP_CSR register  ********************/
+#define  BKP_CSR_CTE                         ((uint16_t)0x0001)     /*!< Clear Tamper event */
+#define  BKP_CSR_CTI                         ((uint16_t)0x0002)     /*!< Clear Tamper Interrupt */
+#define  BKP_CSR_TPIE                        ((uint16_t)0x0004)     /*!< TAMPER Pin interrupt enable */
+#define  BKP_CSR_TEF                         ((uint16_t)0x0100)     /*!< Tamper Event Flag */
+#define  BKP_CSR_TIF                         ((uint16_t)0x0200)     /*!< Tamper Interrupt Flag */
+
+/******************************************************************************/
+/*                                                                            */
+/*                         Reset and Clock Control                            */
+/*                                                                            */
+/******************************************************************************/
+
+/********************  Bit definition for RCC_CR register  ********************/
+#define  RCC_CR_HSION                        ((uint32_t)0x00000001)        /*!< Internal High Speed clock enable */
+#define  RCC_CR_HSIRDY                       ((uint32_t)0x00000002)        /*!< Internal High Speed clock ready flag */
+#define  RCC_CR_HSITRIM                      ((uint32_t)0x000000F8)        /*!< Internal High Speed clock trimming */
+#define  RCC_CR_HSICAL                       ((uint32_t)0x0000FF00)        /*!< Internal High Speed clock Calibration */
+#define  RCC_CR_HSEON                        ((uint32_t)0x00010000)        /*!< External High Speed clock enable */
+#define  RCC_CR_HSERDY                       ((uint32_t)0x00020000)        /*!< External High Speed clock ready flag */
+#define  RCC_CR_HSEBYP                       ((uint32_t)0x00040000)        /*!< External High Speed clock Bypass */
+#define  RCC_CR_CSSON                        ((uint32_t)0x00080000)        /*!< Clock Security System enable */
+#define  RCC_CR_PLLON                        ((uint32_t)0x01000000)        /*!< PLL enable */
+#define  RCC_CR_PLLRDY                       ((uint32_t)0x02000000)        /*!< PLL clock ready flag */
+
+#ifdef STM32F10X_CL
+ #define  RCC_CR_PLL2ON                       ((uint32_t)0x04000000)        /*!< PLL2 enable */
+ #define  RCC_CR_PLL2RDY                      ((uint32_t)0x08000000)        /*!< PLL2 clock ready flag */
+ #define  RCC_CR_PLL3ON                       ((uint32_t)0x10000000)        /*!< PLL3 enable */
+ #define  RCC_CR_PLL3RDY                      ((uint32_t)0x20000000)        /*!< PLL3 clock ready flag */
+#endif /* STM32F10X_CL */
+
+/*******************  Bit definition for RCC_CFGR register  *******************/
+/*!< SW configuration */
+#define  RCC_CFGR_SW                         ((uint32_t)0x00000003)        /*!< SW[1:0] bits (System clock Switch) */
+#define  RCC_CFGR_SW_0                       ((uint32_t)0x00000001)        /*!< Bit 0 */
+#define  RCC_CFGR_SW_1                       ((uint32_t)0x00000002)        /*!< Bit 1 */
+
+#define  RCC_CFGR_SW_HSI                     ((uint32_t)0x00000000)        /*!< HSI selected as system clock */
+#define  RCC_CFGR_SW_HSE                     ((uint32_t)0x00000001)        /*!< HSE selected as system clock */
+#define  RCC_CFGR_SW_PLL                     ((uint32_t)0x00000002)        /*!< PLL selected as system clock */
+
+/*!< SWS configuration */
+#define  RCC_CFGR_SWS                        ((uint32_t)0x0000000C)        /*!< SWS[1:0] bits (System Clock Switch Status) */
+#define  RCC_CFGR_SWS_0                      ((uint32_t)0x00000004)        /*!< Bit 0 */
+#define  RCC_CFGR_SWS_1                      ((uint32_t)0x00000008)        /*!< Bit 1 */
+
+#define  RCC_CFGR_SWS_HSI                    ((uint32_t)0x00000000)        /*!< HSI oscillator used as system clock */
+#define  RCC_CFGR_SWS_HSE                    ((uint32_t)0x00000004)        /*!< HSE oscillator used as system clock */
+#define  RCC_CFGR_SWS_PLL                    ((uint32_t)0x00000008)        /*!< PLL used as system clock */
+
+/*!< HPRE configuration */
+#define  RCC_CFGR_HPRE                       ((uint32_t)0x000000F0)        /*!< HPRE[3:0] bits (AHB prescaler) */
+#define  RCC_CFGR_HPRE_0                     ((uint32_t)0x00000010)        /*!< Bit 0 */
+#define  RCC_CFGR_HPRE_1                     ((uint32_t)0x00000020)        /*!< Bit 1 */
+#define  RCC_CFGR_HPRE_2                     ((uint32_t)0x00000040)        /*!< Bit 2 */
+#define  RCC_CFGR_HPRE_3                     ((uint32_t)0x00000080)        /*!< Bit 3 */
+
+#define  RCC_CFGR_HPRE_DIV1                  ((uint32_t)0x00000000)        /*!< SYSCLK not divided */
+#define  RCC_CFGR_HPRE_DIV2                  ((uint32_t)0x00000080)        /*!< SYSCLK divided by 2 */
+#define  RCC_CFGR_HPRE_DIV4                  ((uint32_t)0x00000090)        /*!< SYSCLK divided by 4 */
+#define  RCC_CFGR_HPRE_DIV8                  ((uint32_t)0x000000A0)        /*!< SYSCLK divided by 8 */
+#define  RCC_CFGR_HPRE_DIV16                 ((uint32_t)0x000000B0)        /*!< SYSCLK divided by 16 */
+#define  RCC_CFGR_HPRE_DIV64                 ((uint32_t)0x000000C0)        /*!< SYSCLK divided by 64 */
+#define  RCC_CFGR_HPRE_DIV128                ((uint32_t)0x000000D0)        /*!< SYSCLK divided by 128 */
+#define  RCC_CFGR_HPRE_DIV256                ((uint32_t)0x000000E0)        /*!< SYSCLK divided by 256 */
+#define  RCC_CFGR_HPRE_DIV512                ((uint32_t)0x000000F0)        /*!< SYSCLK divided by 512 */
+
+/*!< PPRE1 configuration */
+#define  RCC_CFGR_PPRE1                      ((uint32_t)0x00000700)        /*!< PRE1[2:0] bits (APB1 prescaler) */
+#define  RCC_CFGR_PPRE1_0                    ((uint32_t)0x00000100)        /*!< Bit 0 */
+#define  RCC_CFGR_PPRE1_1                    ((uint32_t)0x00000200)        /*!< Bit 1 */
+#define  RCC_CFGR_PPRE1_2                    ((uint32_t)0x00000400)        /*!< Bit 2 */
+
+#define  RCC_CFGR_PPRE1_DIV1                 ((uint32_t)0x00000000)        /*!< HCLK not divided */
+#define  RCC_CFGR_PPRE1_DIV2                 ((uint32_t)0x00000400)        /*!< HCLK divided by 2 */
+#define  RCC_CFGR_PPRE1_DIV4                 ((uint32_t)0x00000500)        /*!< HCLK divided by 4 */
+#define  RCC_CFGR_PPRE1_DIV8                 ((uint32_t)0x00000600)        /*!< HCLK divided by 8 */
+#define  RCC_CFGR_PPRE1_DIV16                ((uint32_t)0x00000700)        /*!< HCLK divided by 16 */
+
+/*!< PPRE2 configuration */
+#define  RCC_CFGR_PPRE2                      ((uint32_t)0x00003800)        /*!< PRE2[2:0] bits (APB2 prescaler) */
+#define  RCC_CFGR_PPRE2_0                    ((uint32_t)0x00000800)        /*!< Bit 0 */
+#define  RCC_CFGR_PPRE2_1                    ((uint32_t)0x00001000)        /*!< Bit 1 */
+#define  RCC_CFGR_PPRE2_2                    ((uint32_t)0x00002000)        /*!< Bit 2 */
+
+#define  RCC_CFGR_PPRE2_DIV1                 ((uint32_t)0x00000000)        /*!< HCLK not divided */
+#define  RCC_CFGR_PPRE2_DIV2                 ((uint32_t)0x00002000)        /*!< HCLK divided by 2 */
+#define  RCC_CFGR_PPRE2_DIV4                 ((uint32_t)0x00002800)        /*!< HCLK divided by 4 */
+#define  RCC_CFGR_PPRE2_DIV8                 ((uint32_t)0x00003000)        /*!< HCLK divided by 8 */
+#define  RCC_CFGR_PPRE2_DIV16                ((uint32_t)0x00003800)        /*!< HCLK divided by 16 */
+
+/*!< ADCPPRE configuration */
+#define  RCC_CFGR_ADCPRE                     ((uint32_t)0x0000C000)        /*!< ADCPRE[1:0] bits (ADC prescaler) */
+#define  RCC_CFGR_ADCPRE_0                   ((uint32_t)0x00004000)        /*!< Bit 0 */
+#define  RCC_CFGR_ADCPRE_1                   ((uint32_t)0x00008000)        /*!< Bit 1 */
+
+#define  RCC_CFGR_ADCPRE_DIV2                ((uint32_t)0x00000000)        /*!< PCLK2 divided by 2 */
+#define  RCC_CFGR_ADCPRE_DIV4                ((uint32_t)0x00004000)        /*!< PCLK2 divided by 4 */
+#define  RCC_CFGR_ADCPRE_DIV6                ((uint32_t)0x00008000)        /*!< PCLK2 divided by 6 */
+#define  RCC_CFGR_ADCPRE_DIV8                ((uint32_t)0x0000C000)        /*!< PCLK2 divided by 8 */
+
+#define  RCC_CFGR_PLLSRC                     ((uint32_t)0x00010000)        /*!< PLL entry clock source */
+
+#define  RCC_CFGR_PLLXTPRE                   ((uint32_t)0x00020000)        /*!< HSE divider for PLL entry */
+
+/*!< PLLMUL configuration */
+#define  RCC_CFGR_PLLMULL                    ((uint32_t)0x003C0000)        /*!< PLLMUL[3:0] bits (PLL multiplication factor) */
+#define  RCC_CFGR_PLLMULL_0                  ((uint32_t)0x00040000)        /*!< Bit 0 */
+#define  RCC_CFGR_PLLMULL_1                  ((uint32_t)0x00080000)        /*!< Bit 1 */
+#define  RCC_CFGR_PLLMULL_2                  ((uint32_t)0x00100000)        /*!< Bit 2 */
+#define  RCC_CFGR_PLLMULL_3                  ((uint32_t)0x00200000)        /*!< Bit 3 */
+
+#ifdef STM32F10X_CL
+ #define  RCC_CFGR_PLLSRC_HSI_Div2           ((uint32_t)0x00000000)        /*!< HSI clock divided by 2 selected as PLL entry clock source */
+ #define  RCC_CFGR_PLLSRC_PREDIV1            ((uint32_t)0x00010000)        /*!< PREDIV1 clock selected as PLL entry clock source */
+
+ #define  RCC_CFGR_PLLXTPRE_PREDIV1          ((uint32_t)0x00000000)        /*!< PREDIV1 clock not divided for PLL entry */
+ #define  RCC_CFGR_PLLXTPRE_PREDIV1_Div2     ((uint32_t)0x00020000)        /*!< PREDIV1 clock divided by 2 for PLL entry */
+
+ #define  RCC_CFGR_PLLMULL4                  ((uint32_t)0x00080000)        /*!< PLL input clock * 4 */
+ #define  RCC_CFGR_PLLMULL5                  ((uint32_t)0x000C0000)        /*!< PLL input clock * 5 */
+ #define  RCC_CFGR_PLLMULL6                  ((uint32_t)0x00100000)        /*!< PLL input clock * 6 */
+ #define  RCC_CFGR_PLLMULL7                  ((uint32_t)0x00140000)        /*!< PLL input clock * 7 */
+ #define  RCC_CFGR_PLLMULL8                  ((uint32_t)0x00180000)        /*!< PLL input clock * 8 */
+ #define  RCC_CFGR_PLLMULL9                  ((uint32_t)0x001C0000)        /*!< PLL input clock * 9 */
+ #define  RCC_CFGR_PLLMULL6_5                ((uint32_t)0x00340000)        /*!< PLL input clock * 6.5 */
+ 
+ #define  RCC_CFGR_OTGFSPRE                  ((uint32_t)0x00400000)        /*!< USB OTG FS prescaler */
+ 
+/*!< MCO configuration */
+ #define  RCC_CFGR_MCO                       ((uint32_t)0x0F000000)        /*!< MCO[3:0] bits (Microcontroller Clock Output) */
+ #define  RCC_CFGR_MCO_0                     ((uint32_t)0x01000000)        /*!< Bit 0 */
+ #define  RCC_CFGR_MCO_1                     ((uint32_t)0x02000000)        /*!< Bit 1 */
+ #define  RCC_CFGR_MCO_2                     ((uint32_t)0x04000000)        /*!< Bit 2 */
+ #define  RCC_CFGR_MCO_3                     ((uint32_t)0x08000000)        /*!< Bit 3 */
+
+ #define  RCC_CFGR_MCO_NOCLOCK               ((uint32_t)0x00000000)        /*!< No clock */
+ #define  RCC_CFGR_MCO_SYSCLK                ((uint32_t)0x04000000)        /*!< System clock selected as MCO source */
+ #define  RCC_CFGR_MCO_HSI                   ((uint32_t)0x05000000)        /*!< HSI clock selected as MCO source */
+ #define  RCC_CFGR_MCO_HSE                   ((uint32_t)0x06000000)        /*!< HSE clock selected as MCO source */
+ #define  RCC_CFGR_MCO_PLLCLK_Div2           ((uint32_t)0x07000000)        /*!< PLL clock divided by 2 selected as MCO source */
+ #define  RCC_CFGR_MCO_PLL2CLK               ((uint32_t)0x08000000)        /*!< PLL2 clock selected as MCO source*/
+ #define  RCC_CFGR_MCO_PLL3CLK_Div2          ((uint32_t)0x09000000)        /*!< PLL3 clock divided by 2 selected as MCO source*/
+ #define  RCC_CFGR_MCO_Ext_HSE               ((uint32_t)0x0A000000)        /*!< XT1 external 3-25 MHz oscillator clock selected as MCO source */
+ #define  RCC_CFGR_MCO_PLL3CLK               ((uint32_t)0x0B000000)        /*!< PLL3 clock selected as MCO source */
+#else
+ #define  RCC_CFGR_PLLSRC_HSI_Div2           ((uint32_t)0x00000000)        /*!< HSI clock divided by 2 selected as PLL entry clock source */
+ #define  RCC_CFGR_PLLSRC_HSE                ((uint32_t)0x00010000)        /*!< HSE clock selected as PLL entry clock source */
+
+ #define  RCC_CFGR_PLLXTPRE_HSE              ((uint32_t)0x00000000)        /*!< HSE clock not divided for PLL entry */
+ #define  RCC_CFGR_PLLXTPRE_HSE_Div2         ((uint32_t)0x00020000)        /*!< HSE clock divided by 2 for PLL entry */
+
+ #define  RCC_CFGR_PLLMULL2                  ((uint32_t)0x00000000)        /*!< PLL input clock*2 */
+ #define  RCC_CFGR_PLLMULL3                  ((uint32_t)0x00040000)        /*!< PLL input clock*3 */
+ #define  RCC_CFGR_PLLMULL4                  ((uint32_t)0x00080000)        /*!< PLL input clock*4 */
+ #define  RCC_CFGR_PLLMULL5                  ((uint32_t)0x000C0000)        /*!< PLL input clock*5 */
+ #define  RCC_CFGR_PLLMULL6                  ((uint32_t)0x00100000)        /*!< PLL input clock*6 */
+ #define  RCC_CFGR_PLLMULL7                  ((uint32_t)0x00140000)        /*!< PLL input clock*7 */
+ #define  RCC_CFGR_PLLMULL8                  ((uint32_t)0x00180000)        /*!< PLL input clock*8 */
+ #define  RCC_CFGR_PLLMULL9                  ((uint32_t)0x001C0000)        /*!< PLL input clock*9 */
+ #define  RCC_CFGR_PLLMULL10                 ((uint32_t)0x00200000)        /*!< PLL input clock10 */
+ #define  RCC_CFGR_PLLMULL11                 ((uint32_t)0x00240000)        /*!< PLL input clock*11 */
+ #define  RCC_CFGR_PLLMULL12                 ((uint32_t)0x00280000)        /*!< PLL input clock*12 */
+ #define  RCC_CFGR_PLLMULL13                 ((uint32_t)0x002C0000)        /*!< PLL input clock*13 */
+ #define  RCC_CFGR_PLLMULL14                 ((uint32_t)0x00300000)        /*!< PLL input clock*14 */
+ #define  RCC_CFGR_PLLMULL15                 ((uint32_t)0x00340000)        /*!< PLL input clock*15 */
+ #define  RCC_CFGR_PLLMULL16                 ((uint32_t)0x00380000)        /*!< PLL input clock*16 */
+ #define  RCC_CFGR_USBPRE                    ((uint32_t)0x00400000)        /*!< USB Device prescaler */
+
+/*!< MCO configuration */
+ #define  RCC_CFGR_MCO                       ((uint32_t)0x07000000)        /*!< MCO[2:0] bits (Microcontroller Clock Output) */
+ #define  RCC_CFGR_MCO_0                     ((uint32_t)0x01000000)        /*!< Bit 0 */
+ #define  RCC_CFGR_MCO_1                     ((uint32_t)0x02000000)        /*!< Bit 1 */
+ #define  RCC_CFGR_MCO_2                     ((uint32_t)0x04000000)        /*!< Bit 2 */
+
+ #define  RCC_CFGR_MCO_NOCLOCK               ((uint32_t)0x00000000)        /*!< No clock */
+ #define  RCC_CFGR_MCO_SYSCLK                ((uint32_t)0x04000000)        /*!< System clock selected as MCO source */
+ #define  RCC_CFGR_MCO_HSI                   ((uint32_t)0x05000000)        /*!< HSI clock selected as MCO source */
+ #define  RCC_CFGR_MCO_HSE                   ((uint32_t)0x06000000)        /*!< HSE clock selected as MCO source  */
+ #define  RCC_CFGR_MCO_PLL                   ((uint32_t)0x07000000)        /*!< PLL clock divided by 2 selected as MCO source */
+#endif /* STM32F10X_CL */
+
+/*!<******************  Bit definition for RCC_CIR register  ********************/
+#define  RCC_CIR_LSIRDYF                     ((uint32_t)0x00000001)        /*!< LSI Ready Interrupt flag */
+#define  RCC_CIR_LSERDYF                     ((uint32_t)0x00000002)        /*!< LSE Ready Interrupt flag */
+#define  RCC_CIR_HSIRDYF                     ((uint32_t)0x00000004)        /*!< HSI Ready Interrupt flag */
+#define  RCC_CIR_HSERDYF                     ((uint32_t)0x00000008)        /*!< HSE Ready Interrupt flag */
+#define  RCC_CIR_PLLRDYF                     ((uint32_t)0x00000010)        /*!< PLL Ready Interrupt flag */
+#define  RCC_CIR_CSSF                        ((uint32_t)0x00000080)        /*!< Clock Security System Interrupt flag */
+#define  RCC_CIR_LSIRDYIE                    ((uint32_t)0x00000100)        /*!< LSI Ready Interrupt Enable */
+#define  RCC_CIR_LSERDYIE                    ((uint32_t)0x00000200)        /*!< LSE Ready Interrupt Enable */
+#define  RCC_CIR_HSIRDYIE                    ((uint32_t)0x00000400)        /*!< HSI Ready Interrupt Enable */
+#define  RCC_CIR_HSERDYIE                    ((uint32_t)0x00000800)        /*!< HSE Ready Interrupt Enable */
+#define  RCC_CIR_PLLRDYIE                    ((uint32_t)0x00001000)        /*!< PLL Ready Interrupt Enable */
+#define  RCC_CIR_LSIRDYC                     ((uint32_t)0x00010000)        /*!< LSI Ready Interrupt Clear */
+#define  RCC_CIR_LSERDYC                     ((uint32_t)0x00020000)        /*!< LSE Ready Interrupt Clear */
+#define  RCC_CIR_HSIRDYC                     ((uint32_t)0x00040000)        /*!< HSI Ready Interrupt Clear */
+#define  RCC_CIR_HSERDYC                     ((uint32_t)0x00080000)        /*!< HSE Ready Interrupt Clear */
+#define  RCC_CIR_PLLRDYC                     ((uint32_t)0x00100000)        /*!< PLL Ready Interrupt Clear */
+#define  RCC_CIR_CSSC                        ((uint32_t)0x00800000)        /*!< Clock Security System Interrupt Clear */
+
+#ifdef STM32F10X_CL
+ #define  RCC_CIR_PLL2RDYF                    ((uint32_t)0x00000020)        /*!< PLL2 Ready Interrupt flag */
+ #define  RCC_CIR_PLL3RDYF                    ((uint32_t)0x00000040)        /*!< PLL3 Ready Interrupt flag */
+ #define  RCC_CIR_PLL2RDYIE                   ((uint32_t)0x00002000)        /*!< PLL2 Ready Interrupt Enable */
+ #define  RCC_CIR_PLL3RDYIE                   ((uint32_t)0x00004000)        /*!< PLL3 Ready Interrupt Enable */
+ #define  RCC_CIR_PLL2RDYC                    ((uint32_t)0x00200000)        /*!< PLL2 Ready Interrupt Clear */
+ #define  RCC_CIR_PLL3RDYC                    ((uint32_t)0x00400000)        /*!< PLL3 Ready Interrupt Clear */
+#endif /* STM32F10X_CL */
+
+/*****************  Bit definition for RCC_APB2RSTR register  *****************/
+#define  RCC_APB2RSTR_AFIORST                ((uint16_t)0x0001)            /*!< Alternate Function I/O reset */
+#define  RCC_APB2RSTR_IOPARST                ((uint16_t)0x0004)            /*!< I/O port A reset */
+#define  RCC_APB2RSTR_IOPBRST                ((uint16_t)0x0008)            /*!< I/O port B reset */
+#define  RCC_APB2RSTR_IOPCRST                ((uint16_t)0x0010)            /*!< I/O port C reset */
+#define  RCC_APB2RSTR_IOPDRST                ((uint16_t)0x0020)            /*!< I/O port D reset */
+#define  RCC_APB2RSTR_ADC1RST                ((uint16_t)0x0200)            /*!< ADC 1 interface reset */
+#define  RCC_APB2RSTR_ADC2RST                ((uint16_t)0x0400)            /*!< ADC 2 interface reset */
+#define  RCC_APB2RSTR_TIM1RST                ((uint16_t)0x0800)            /*!< TIM1 Timer reset */
+#define  RCC_APB2RSTR_SPI1RST                ((uint16_t)0x1000)            /*!< SPI 1 reset */
+#define  RCC_APB2RSTR_USART1RST              ((uint16_t)0x4000)            /*!< USART1 reset */
+
+#ifndef STM32F10X_LD
+ #define  RCC_APB2RSTR_IOPERST               ((uint16_t)0x0040)            /*!< I/O port E reset */
+#endif /* STM32F10X_HD */
+
+#ifdef STM32F10X_HD
+ #define  RCC_APB2RSTR_IOPFRST               ((uint16_t)0x0080)            /*!< I/O port F reset */
+ #define  RCC_APB2RSTR_IOPGRST               ((uint16_t)0x0100)            /*!< I/O port G reset */
+ #define  RCC_APB2RSTR_TIM8RST               ((uint16_t)0x2000)            /*!< TIM8 Timer reset */
+ #define  RCC_APB2RSTR_ADC3RST               ((uint16_t)0x8000)            /*!< ADC3 interface reset */
+#endif /* STM32F10X_HD */
+
+/*****************  Bit definition for RCC_APB1RSTR register  *****************/
+#define  RCC_APB1RSTR_TIM2RST                ((uint32_t)0x00000001)        /*!< Timer 2 reset */
+#define  RCC_APB1RSTR_TIM3RST                ((uint32_t)0x00000002)        /*!< Timer 3 reset */
+#define  RCC_APB1RSTR_WWDGRST                ((uint32_t)0x00000800)        /*!< Window Watchdog reset */
+#define  RCC_APB1RSTR_USART2RST              ((uint32_t)0x00020000)        /*!< USART 2 reset */
+#define  RCC_APB1RSTR_I2C1RST                ((uint32_t)0x00200000)        /*!< I2C 1 reset */
+#define  RCC_APB1RSTR_CAN1RST                ((uint32_t)0x02000000)        /*!< CAN1 reset */
+#define  RCC_APB1RSTR_BKPRST                 ((uint32_t)0x08000000)        /*!< Backup interface reset */
+#define  RCC_APB1RSTR_PWRRST                 ((uint32_t)0x10000000)        /*!< Power interface reset */
+
+#ifndef STM32F10X_LD
+ #define  RCC_APB1RSTR_TIM4RST               ((uint32_t)0x00000004)        /*!< Timer 4 reset */
+ #define  RCC_APB1RSTR_SPI2RST               ((uint32_t)0x00004000)        /*!< SPI 2 reset */
+ #define  RCC_APB1RSTR_USART3RST             ((uint32_t)0x00040000)        /*!< RUSART 3 reset */
+ #define  RCC_APB1RSTR_I2C2RST               ((uint32_t)0x00400000)        /*!< I2C 2 reset */
+#endif /* STM32F10X_HD */
+
+#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD)
+ #define  RCC_APB1RSTR_USBRST                ((uint32_t)0x00800000)        /*!< USB Device reset */
+#endif
+
+#if defined (STM32F10X_HD) || defined  (STM32F10X_CL)
+ #define  RCC_APB1RSTR_TIM5RST                ((uint32_t)0x00000008)        /*!< Timer 5 reset */
+ #define  RCC_APB1RSTR_TIM6RST                ((uint32_t)0x00000010)        /*!< Timer 6 reset */
+ #define  RCC_APB1RSTR_TIM7RST                ((uint32_t)0x00000020)        /*!< Timer 7 reset */
+ #define  RCC_APB1RSTR_SPI3RST                ((uint32_t)0x00008000)        /*!< SPI 3 reset */
+ #define  RCC_APB1RSTR_UART4RST               ((uint32_t)0x00080000)        /*!< UART 4 reset */
+ #define  RCC_APB1RSTR_UART5RST               ((uint32_t)0x00100000)        /*!< UART 5 reset */
+ #define  RCC_APB1RSTR_DACRST                 ((uint32_t)0x20000000)        /*!< DAC interface reset */
+#endif
+
+#ifdef STM32F10X_CL
+ #define  RCC_APB1RSTR_CAN2RST                ((uint32_t)0x08000000)        /*!< CAN2 reset */
+#endif /* STM32F10X_CL */
+
+/******************  Bit definition for RCC_AHBENR register  ******************/
+#define  RCC_AHBENR_DMA1EN                   ((uint16_t)0x0001)            /*!< DMA1 clock enable */
+#define  RCC_AHBENR_SRAMEN                   ((uint16_t)0x0004)            /*!< SRAM interface clock enable */
+#define  RCC_AHBENR_FLITFEN                  ((uint16_t)0x0010)            /*!< FLITF clock enable */
+#define  RCC_AHBENR_CRCEN                    ((uint16_t)0x0040)            /*!< CRC clock enable */
+
+#if defined (STM32F10X_HD) || defined  (STM32F10X_CL)
+ #define  RCC_AHBENR_DMA2EN                  ((uint16_t)0x0002)            /*!< DMA2 clock enable */
+#endif
+
+#ifdef STM32F10X_HD
+ #define  RCC_AHBENR_FSMCEN                  ((uint16_t)0x0100)            /*!< FSMC clock enable */
+ #define  RCC_AHBENR_SDIOEN                  ((uint16_t)0x0400)            /*!< SDIO clock enable */
+#endif /* STM32F10X_HD */
+
+#ifdef STM32F10X_CL
+ #define  RCC_AHBENR_OTGFSEN                 ((uint32_t)0x00001000)         /*!< USB OTG FS clock enable */
+ #define  RCC_AHBENR_ETHMACEN                ((uint32_t)0x00004000)         /*!< ETHERNET MAC clock enable */
+ #define  RCC_AHBENR_ETHMACTXEN              ((uint32_t)0x00008000)         /*!< ETHERNET MAC Tx clock enable */
+ #define  RCC_AHBENR_ETHMACRXEN              ((uint32_t)0x00010000)         /*!< ETHERNET MAC Rx clock enable */
+#endif /* STM32F10X_CL */
+
+/******************  Bit definition for RCC_APB2ENR register  *****************/
+#define  RCC_APB2ENR_AFIOEN                  ((uint16_t)0x0001)            /*!< Alternate Function I/O clock enable */
+#define  RCC_APB2ENR_IOPAEN                  ((uint16_t)0x0004)            /*!< I/O port A clock enable */
+#define  RCC_APB2ENR_IOPBEN                  ((uint16_t)0x0008)            /*!< I/O port B clock enable */
+#define  RCC_APB2ENR_IOPCEN                  ((uint16_t)0x0010)            /*!< I/O port C clock enable */
+#define  RCC_APB2ENR_IOPDEN                  ((uint16_t)0x0020)            /*!< I/O port D clock enable */
+#define  RCC_APB2ENR_ADC1EN                  ((uint16_t)0x0200)            /*!< ADC 1 interface clock enable */
+#define  RCC_APB2ENR_ADC2EN                  ((uint16_t)0x0400)            /*!< ADC 2 interface clock enable */
+#define  RCC_APB2ENR_TIM1EN                  ((uint16_t)0x0800)            /*!< TIM1 Timer clock enable */
+#define  RCC_APB2ENR_SPI1EN                  ((uint16_t)0x1000)            /*!< SPI 1 clock enable */
+#define  RCC_APB2ENR_USART1EN                ((uint16_t)0x4000)            /*!< USART1 clock enable */
+
+#ifndef STM32F10X_LD
+ #define  RCC_APB2ENR_IOPEEN                 ((uint16_t)0x0040)            /*!< I/O port E clock enable */
+#endif /* STM32F10X_HD */
+
+#ifdef STM32F10X_HD
+ #define  RCC_APB2ENR_IOPFEN                 ((uint16_t)0x0080)            /*!< I/O port F clock enable */
+ #define  RCC_APB2ENR_IOPGEN                 ((uint16_t)0x0100)            /*!< I/O port G clock enable */
+ #define  RCC_APB2ENR_TIM8EN                 ((uint16_t)0x2000)            /*!< TIM8 Timer clock enable */
+ #define  RCC_APB2ENR_ADC3EN                 ((uint16_t)0x8000)            /*!< DMA1 clock enable */
+#endif /* STM32F10X_HD */
+
+/*****************  Bit definition for RCC_APB1ENR register  ******************/
+#define  RCC_APB1ENR_TIM2EN                  ((uint32_t)0x00000001)        /*!< Timer 2 clock enabled*/
+#define  RCC_APB1ENR_TIM3EN                  ((uint32_t)0x00000002)        /*!< Timer 3 clock enable */
+#define  RCC_APB1ENR_WWDGEN                  ((uint32_t)0x00000800)        /*!< Window Watchdog clock enable */
+#define  RCC_APB1ENR_USART2EN                ((uint32_t)0x00020000)        /*!< USART 2 clock enable */
+#define  RCC_APB1ENR_I2C1EN                  ((uint32_t)0x00200000)        /*!< I2C 1 clock enable */
+#define  RCC_APB1ENR_CAN1EN                  ((uint32_t)0x02000000)        /*!< CAN1 clock enable */
+#define  RCC_APB1ENR_BKPEN                   ((uint32_t)0x08000000)        /*!< Backup interface clock enable */
+#define  RCC_APB1ENR_PWREN                   ((uint32_t)0x10000000)        /*!< Power interface clock enable */
+
+#ifndef STM32F10X_LD
+ #define  RCC_APB1ENR_TIM4EN                 ((uint32_t)0x00000004)        /*!< Timer 4 clock enable */
+ #define  RCC_APB1ENR_SPI2EN                 ((uint32_t)0x00004000)        /*!< SPI 2 clock enable */
+ #define  RCC_APB1ENR_USART3EN               ((uint32_t)0x00040000)        /*!< USART 3 clock enable */
+ #define  RCC_APB1ENR_I2C2EN                 ((uint32_t)0x00400000)        /*!< I2C 2 clock enable */
+#endif /* STM32F10X_HD */
+
+#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined  (STM32F10X_LD)
+ #define  RCC_APB1ENR_USBEN                  ((uint32_t)0x00800000)        /*!< USB Device clock enable */
+#endif
+
+#if defined (STM32F10X_HD) || defined  (STM32F10X_CL)
+ #define  RCC_APB1ENR_TIM5EN                 ((uint32_t)0x00000008)        /*!< Timer 5 clock enable */
+ #define  RCC_APB1ENR_TIM6EN                 ((uint32_t)0x00000010)        /*!< Timer 6 clock enable */
+ #define  RCC_APB1ENR_TIM7EN                 ((uint32_t)0x00000020)        /*!< Timer 7 clock enable */
+ #define  RCC_APB1ENR_SPI3EN                 ((uint32_t)0x00008000)        /*!< SPI 3 clock enable */
+ #define  RCC_APB1ENR_UART4EN                ((uint32_t)0x00080000)        /*!< UART 4 clock enable */
+ #define  RCC_APB1ENR_UART5EN                ((uint32_t)0x00100000)        /*!< UART 5 clock enable */
+ #define  RCC_APB1ENR_DACEN                  ((uint32_t)0x20000000)        /*!< DAC interface clock enable */
+#endif
+
+#ifdef STM32F10X_CL
+ #define  RCC_APB1ENR_CAN2EN                  ((uint32_t)0x08000000)        /*!< CAN2 clock enable */
+#endif /* STM32F10X_CL */
+
+/*******************  Bit definition for RCC_BDCR register  *******************/
+#define  RCC_BDCR_LSEON                      ((uint32_t)0x00000001)        /*!< External Low Speed oscillator enable */
+#define  RCC_BDCR_LSERDY                     ((uint32_t)0x00000002)        /*!< External Low Speed oscillator Ready */
+#define  RCC_BDCR_LSEBYP                     ((uint32_t)0x00000004)        /*!< External Low Speed oscillator Bypass */
+
+#define  RCC_BDCR_RTCSEL                     ((uint32_t)0x00000300)        /*!< RTCSEL[1:0] bits (RTC clock source selection) */
+#define  RCC_BDCR_RTCSEL_0                   ((uint32_t)0x00000100)        /*!< Bit 0 */
+#define  RCC_BDCR_RTCSEL_1                   ((uint32_t)0x00000200)        /*!< Bit 1 */
+
+/*!< RTC congiguration */
+#define  RCC_BDCR_RTCSEL_NOCLOCK             ((uint32_t)0x00000000)        /*!< No clock */
+#define  RCC_BDCR_RTCSEL_LSE                 ((uint32_t)0x00000100)        /*!< LSE oscillator clock used as RTC clock */
+#define  RCC_BDCR_RTCSEL_LSI                 ((uint32_t)0x00000200)        /*!< LSI oscillator clock used as RTC clock */
+#define  RCC_BDCR_RTCSEL_HSE                 ((uint32_t)0x00000300)        /*!< HSE oscillator clock divided by 128 used as RTC clock */
+
+#define  RCC_BDCR_RTCEN                      ((uint32_t)0x00008000)        /*!< RTC clock enable */
+#define  RCC_BDCR_BDRST                      ((uint32_t)0x00010000)        /*!< Backup domain software reset  */
+
+/*******************  Bit definition for RCC_CSR register  ********************/  
+#define  RCC_CSR_LSION                       ((uint32_t)0x00000001)        /*!< Internal Low Speed oscillator enable */
+#define  RCC_CSR_LSIRDY                      ((uint32_t)0x00000002)        /*!< Internal Low Speed oscillator Ready */
+#define  RCC_CSR_RMVF                        ((uint32_t)0x01000000)        /*!< Remove reset flag */
+#define  RCC_CSR_PINRSTF                     ((uint32_t)0x04000000)        /*!< PIN reset flag */
+#define  RCC_CSR_PORRSTF                     ((uint32_t)0x08000000)        /*!< POR/PDR reset flag */
+#define  RCC_CSR_SFTRSTF                     ((uint32_t)0x10000000)        /*!< Software Reset flag */
+#define  RCC_CSR_IWDGRSTF                    ((uint32_t)0x20000000)        /*!< Independent Watchdog reset flag */
+#define  RCC_CSR_WWDGRSTF                    ((uint32_t)0x40000000)        /*!< Window watchdog reset flag */
+#define  RCC_CSR_LPWRRSTF                    ((uint32_t)0x80000000)        /*!< Low-Power reset flag */
+
+#ifdef STM32F10X_CL
+/*******************  Bit definition for RCC_AHBRSTR register  ****************/
+ #define  RCC_AHBRSTR_OTGFSRST               ((uint32_t)0x00001000)         /*!< USB OTG FS reset */
+ #define  RCC_AHBRSTR_ETHMACRST              ((uint32_t)0x00004000)         /*!< ETHERNET MAC reset */
+
+/*******************  Bit definition for RCC_CFGR2 register  ******************/
+/*!< PREDIV1 configuration */
+ #define  RCC_CFGR2_PREDIV1                  ((uint32_t)0x0000000F)        /*!< PREDIV1[3:0] bits */
+ #define  RCC_CFGR2_PREDIV1_0                ((uint32_t)0x00000001)        /*!< Bit 0 */
+ #define  RCC_CFGR2_PREDIV1_1                ((uint32_t)0x00000002)        /*!< Bit 1 */
+ #define  RCC_CFGR2_PREDIV1_2                ((uint32_t)0x00000004)        /*!< Bit 2 */
+ #define  RCC_CFGR2_PREDIV1_3                ((uint32_t)0x00000008)        /*!< Bit 3 */
+
+ #define  RCC_CFGR2_PREDIV1_DIV1             ((uint32_t)0x00000000)        /*!< PREDIV1 input clock not divided */
+ #define  RCC_CFGR2_PREDIV1_DIV2             ((uint32_t)0x00000001)        /*!< PREDIV1 input clock divided by 2 */
+ #define  RCC_CFGR2_PREDIV1_DIV3             ((uint32_t)0x00000002)        /*!< PREDIV1 input clock divided by 3 */
+ #define  RCC_CFGR2_PREDIV1_DIV4             ((uint32_t)0x00000003)        /*!< PREDIV1 input clock divided by 4 */
+ #define  RCC_CFGR2_PREDIV1_DIV5             ((uint32_t)0x00000004)        /*!< PREDIV1 input clock divided by 5 */
+ #define  RCC_CFGR2_PREDIV1_DIV6             ((uint32_t)0x00000005)        /*!< PREDIV1 input clock divided by 6 */
+ #define  RCC_CFGR2_PREDIV1_DIV7             ((uint32_t)0x00000006)        /*!< PREDIV1 input clock divided by 7 */
+ #define  RCC_CFGR2_PREDIV1_DIV8             ((uint32_t)0x00000007)        /*!< PREDIV1 input clock divided by 8 */
+ #define  RCC_CFGR2_PREDIV1_DIV9             ((uint32_t)0x00000008)        /*!< PREDIV1 input clock divided by 9 */
+ #define  RCC_CFGR2_PREDIV1_DIV10            ((uint32_t)0x00000009)        /*!< PREDIV1 input clock divided by 10 */
+ #define  RCC_CFGR2_PREDIV1_DIV11            ((uint32_t)0x0000000A)        /*!< PREDIV1 input clock divided by 11 */
+ #define  RCC_CFGR2_PREDIV1_DIV12            ((uint32_t)0x0000000B)        /*!< PREDIV1 input clock divided by 12 */
+ #define  RCC_CFGR2_PREDIV1_DIV13            ((uint32_t)0x0000000C)        /*!< PREDIV1 input clock divided by 13 */
+ #define  RCC_CFGR2_PREDIV1_DIV14            ((uint32_t)0x0000000D)        /*!< PREDIV1 input clock divided by 14 */
+ #define  RCC_CFGR2_PREDIV1_DIV15            ((uint32_t)0x0000000E)        /*!< PREDIV1 input clock divided by 15 */
+ #define  RCC_CFGR2_PREDIV1_DIV16            ((uint32_t)0x0000000F)        /*!< PREDIV1 input clock divided by 16 */
+
+/*!< PREDIV2 configuration */
+ #define  RCC_CFGR2_PREDIV2                  ((uint32_t)0x000000F0)        /*!< PREDIV2[3:0] bits */
+ #define  RCC_CFGR2_PREDIV2_0                ((uint32_t)0x00000010)        /*!< Bit 0 */
+ #define  RCC_CFGR2_PREDIV2_1                ((uint32_t)0x00000020)        /*!< Bit 1 */
+ #define  RCC_CFGR2_PREDIV2_2                ((uint32_t)0x00000040)        /*!< Bit 2 */
+ #define  RCC_CFGR2_PREDIV2_3                ((uint32_t)0x00000080)        /*!< Bit 3 */
+
+ #define  RCC_CFGR2_PREDIV2_DIV1             ((uint32_t)0x00000000)        /*!< PREDIV2 input clock not divided */
+ #define  RCC_CFGR2_PREDIV2_DIV2             ((uint32_t)0x00000010)        /*!< PREDIV2 input clock divided by 2 */
+ #define  RCC_CFGR2_PREDIV2_DIV3             ((uint32_t)0x00000020)        /*!< PREDIV2 input clock divided by 3 */
+ #define  RCC_CFGR2_PREDIV2_DIV4             ((uint32_t)0x00000030)        /*!< PREDIV2 input clock divided by 4 */
+ #define  RCC_CFGR2_PREDIV2_DIV5             ((uint32_t)0x00000040)        /*!< PREDIV2 input clock divided by 5 */
+ #define  RCC_CFGR2_PREDIV2_DIV6             ((uint32_t)0x00000050)        /*!< PREDIV2 input clock divided by 6 */
+ #define  RCC_CFGR2_PREDIV2_DIV7             ((uint32_t)0x00000060)        /*!< PREDIV2 input clock divided by 7 */
+ #define  RCC_CFGR2_PREDIV2_DIV8             ((uint32_t)0x00000070)        /*!< PREDIV2 input clock divided by 8 */
+ #define  RCC_CFGR2_PREDIV2_DIV9             ((uint32_t)0x00000080)        /*!< PREDIV2 input clock divided by 9 */
+ #define  RCC_CFGR2_PREDIV2_DIV10            ((uint32_t)0x00000090)        /*!< PREDIV2 input clock divided by 10 */
+ #define  RCC_CFGR2_PREDIV2_DIV11            ((uint32_t)0x000000A0)        /*!< PREDIV2 input clock divided by 11 */
+ #define  RCC_CFGR2_PREDIV2_DIV12            ((uint32_t)0x000000B0)        /*!< PREDIV2 input clock divided by 12 */
+ #define  RCC_CFGR2_PREDIV2_DIV13            ((uint32_t)0x000000C0)        /*!< PREDIV2 input clock divided by 13 */
+ #define  RCC_CFGR2_PREDIV2_DIV14            ((uint32_t)0x000000D0)        /*!< PREDIV2 input clock divided by 14 */
+ #define  RCC_CFGR2_PREDIV2_DIV15            ((uint32_t)0x000000E0)        /*!< PREDIV2 input clock divided by 15 */
+ #define  RCC_CFGR2_PREDIV2_DIV16            ((uint32_t)0x000000F0)        /*!< PREDIV2 input clock divided by 16 */
+
+/*!< PLL2MUL configuration */
+ #define  RCC_CFGR2_PLL2MUL                  ((uint32_t)0x00000F00)        /*!< PLL2MUL[3:0] bits */
+ #define  RCC_CFGR2_PLL2MUL_0                ((uint32_t)0x00000100)        /*!< Bit 0 */
+ #define  RCC_CFGR2_PLL2MUL_1                ((uint32_t)0x00000200)        /*!< Bit 1 */
+ #define  RCC_CFGR2_PLL2MUL_2                ((uint32_t)0x00000400)        /*!< Bit 2 */
+ #define  RCC_CFGR2_PLL2MUL_3                ((uint32_t)0x00000800)        /*!< Bit 3 */
+
+ #define  RCC_CFGR2_PLL2MUL8                 ((uint32_t)0x00000600)        /*!< PLL2 input clock * 8 */
+ #define  RCC_CFGR2_PLL2MUL9                 ((uint32_t)0x00000700)        /*!< PLL2 input clock * 9 */
+ #define  RCC_CFGR2_PLL2MUL10                ((uint32_t)0x00000800)        /*!< PLL2 input clock * 10 */
+ #define  RCC_CFGR2_PLL2MUL11                ((uint32_t)0x00000900)        /*!< PLL2 input clock * 11 */
+ #define  RCC_CFGR2_PLL2MUL12                ((uint32_t)0x00000A00)        /*!< PLL2 input clock * 12 */
+ #define  RCC_CFGR2_PLL2MUL13                ((uint32_t)0x00000B00)        /*!< PLL2 input clock * 13 */
+ #define  RCC_CFGR2_PLL2MUL14                ((uint32_t)0x00000C00)        /*!< PLL2 input clock * 14 */
+ #define  RCC_CFGR2_PLL2MUL16                ((uint32_t)0x00000E00)        /*!< PLL2 input clock * 16 */
+ #define  RCC_CFGR2_PLL2MUL20                ((uint32_t)0x00000F00)        /*!< PLL2 input clock * 20 */
+
+/*!< PLL3MUL configuration */
+ #define  RCC_CFGR2_PLL3MUL                  ((uint32_t)0x0000F000)        /*!< PLL3MUL[3:0] bits */
+ #define  RCC_CFGR2_PLL3MUL_0                ((uint32_t)0x00001000)        /*!< Bit 0 */
+ #define  RCC_CFGR2_PLL3MUL_1                ((uint32_t)0x00002000)        /*!< Bit 1 */
+ #define  RCC_CFGR2_PLL3MUL_2                ((uint32_t)0x00004000)        /*!< Bit 2 */
+ #define  RCC_CFGR2_PLL3MUL_3                ((uint32_t)0x00008000)        /*!< Bit 3 */
+
+ #define  RCC_CFGR2_PLL3MUL8                 ((uint32_t)0x00006000)        /*!< PLL3 input clock * 8 */
+ #define  RCC_CFGR2_PLL3MUL9                 ((uint32_t)0x00007000)        /*!< PLL3 input clock * 9 */
+ #define  RCC_CFGR2_PLL3MUL10                ((uint32_t)0x00008000)        /*!< PLL3 input clock * 10 */
+ #define  RCC_CFGR2_PLL3MUL11                ((uint32_t)0x00009000)        /*!< PLL3 input clock * 11 */
+ #define  RCC_CFGR2_PLL3MUL12                ((uint32_t)0x0000A000)        /*!< PLL3 input clock * 12 */
+ #define  RCC_CFGR2_PLL3MUL13                ((uint32_t)0x0000B000)        /*!< PLL3 input clock * 13 */
+ #define  RCC_CFGR2_PLL3MUL14                ((uint32_t)0x0000C000)        /*!< PLL3 input clock * 14 */
+ #define  RCC_CFGR2_PLL3MUL16                ((uint32_t)0x0000E000)        /*!< PLL3 input clock * 16 */
+ #define  RCC_CFGR2_PLL3MUL20                ((uint32_t)0x0000F000)        /*!< PLL3 input clock * 20 */
+
+ #define  RCC_CFGR2_PREDIV1SRC               ((uint32_t)0x00010000)        /*!< PREDIV1 entry clock source */
+ #define  RCC_CFGR2_PREDIV1SRC_PLL2          ((uint32_t)0x00010000)        /*!< PLL2 selected as PREDIV1 entry clock source */
+ #define  RCC_CFGR2_PREDIV1SRC_HSE           ((uint32_t)0x00000000)        /*!< HSE selected as PREDIV1 entry clock source */
+ #define  RCC_CFGR2_I2S2SRC                  ((uint32_t)0x00020000)        /*!< I2S2 entry clock source */
+ #define  RCC_CFGR2_I2S3SRC                  ((uint32_t)0x00040000)        /*!< I2S3 clock source */
+#endif /* STM32F10X_CL */
+
+/******************************************************************************/
+/*                                                                            */
+/*                General Purpose and Alternate Function I/O                  */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for GPIO_CRL register  *******************/
+#define  GPIO_CRL_MODE                       ((uint32_t)0x33333333)        /*!< Port x mode bits */
+
+#define  GPIO_CRL_MODE0                      ((uint32_t)0x00000003)        /*!< MODE0[1:0] bits (Port x mode bits, pin 0) */
+#define  GPIO_CRL_MODE0_0                    ((uint32_t)0x00000001)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE0_1                    ((uint32_t)0x00000002)        /*!< Bit 1 */
+
+#define  GPIO_CRL_MODE1                      ((uint32_t)0x00000030)        /*!< MODE1[1:0] bits (Port x mode bits, pin 1) */
+#define  GPIO_CRL_MODE1_0                    ((uint32_t)0x00000010)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE1_1                    ((uint32_t)0x00000020)        /*!< Bit 1 */
+
+#define  GPIO_CRL_MODE2                      ((uint32_t)0x00000300)        /*!< MODE2[1:0] bits (Port x mode bits, pin 2) */
+#define  GPIO_CRL_MODE2_0                    ((uint32_t)0x00000100)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE2_1                    ((uint32_t)0x00000200)        /*!< Bit 1 */
+
+#define  GPIO_CRL_MODE3                      ((uint32_t)0x00003000)        /*!< MODE3[1:0] bits (Port x mode bits, pin 3) */
+#define  GPIO_CRL_MODE3_0                    ((uint32_t)0x00001000)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE3_1                    ((uint32_t)0x00002000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_MODE4                      ((uint32_t)0x00030000)        /*!< MODE4[1:0] bits (Port x mode bits, pin 4) */
+#define  GPIO_CRL_MODE4_0                    ((uint32_t)0x00010000)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE4_1                    ((uint32_t)0x00020000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_MODE5                      ((uint32_t)0x00300000)        /*!< MODE5[1:0] bits (Port x mode bits, pin 5) */
+#define  GPIO_CRL_MODE5_0                    ((uint32_t)0x00100000)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE5_1                    ((uint32_t)0x00200000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_MODE6                      ((uint32_t)0x03000000)        /*!< MODE6[1:0] bits (Port x mode bits, pin 6) */
+#define  GPIO_CRL_MODE6_0                    ((uint32_t)0x01000000)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE6_1                    ((uint32_t)0x02000000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_MODE7                      ((uint32_t)0x30000000)        /*!< MODE7[1:0] bits (Port x mode bits, pin 7) */
+#define  GPIO_CRL_MODE7_0                    ((uint32_t)0x10000000)        /*!< Bit 0 */
+#define  GPIO_CRL_MODE7_1                    ((uint32_t)0x20000000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF                        ((uint32_t)0xCCCCCCCC)        /*!< Port x configuration bits */
+
+#define  GPIO_CRL_CNF0                       ((uint32_t)0x0000000C)        /*!< CNF0[1:0] bits (Port x configuration bits, pin 0) */
+#define  GPIO_CRL_CNF0_0                     ((uint32_t)0x00000004)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF0_1                     ((uint32_t)0x00000008)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF1                       ((uint32_t)0x000000C0)        /*!< CNF1[1:0] bits (Port x configuration bits, pin 1) */
+#define  GPIO_CRL_CNF1_0                     ((uint32_t)0x00000040)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF1_1                     ((uint32_t)0x00000080)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF2                       ((uint32_t)0x00000C00)        /*!< CNF2[1:0] bits (Port x configuration bits, pin 2) */
+#define  GPIO_CRL_CNF2_0                     ((uint32_t)0x00000400)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF2_1                     ((uint32_t)0x00000800)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF3                       ((uint32_t)0x0000C000)        /*!< CNF3[1:0] bits (Port x configuration bits, pin 3) */
+#define  GPIO_CRL_CNF3_0                     ((uint32_t)0x00004000)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF3_1                     ((uint32_t)0x00008000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF4                       ((uint32_t)0x000C0000)        /*!< CNF4[1:0] bits (Port x configuration bits, pin 4) */
+#define  GPIO_CRL_CNF4_0                     ((uint32_t)0x00040000)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF4_1                     ((uint32_t)0x00080000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF5                       ((uint32_t)0x00C00000)        /*!< CNF5[1:0] bits (Port x configuration bits, pin 5) */
+#define  GPIO_CRL_CNF5_0                     ((uint32_t)0x00400000)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF5_1                     ((uint32_t)0x00800000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF6                       ((uint32_t)0x0C000000)        /*!< CNF6[1:0] bits (Port x configuration bits, pin 6) */
+#define  GPIO_CRL_CNF6_0                     ((uint32_t)0x04000000)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF6_1                     ((uint32_t)0x08000000)        /*!< Bit 1 */
+
+#define  GPIO_CRL_CNF7                       ((uint32_t)0xC0000000)        /*!< CNF7[1:0] bits (Port x configuration bits, pin 7) */
+#define  GPIO_CRL_CNF7_0                     ((uint32_t)0x40000000)        /*!< Bit 0 */
+#define  GPIO_CRL_CNF7_1                     ((uint32_t)0x80000000)        /*!< Bit 1 */
+
+/*******************  Bit definition for GPIO_CRH register  *******************/
+#define  GPIO_CRH_MODE                       ((uint32_t)0x33333333)        /*!< Port x mode bits */
+
+#define  GPIO_CRH_MODE8                      ((uint32_t)0x00000003)        /*!< MODE8[1:0] bits (Port x mode bits, pin 8) */
+#define  GPIO_CRH_MODE8_0                    ((uint32_t)0x00000001)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE8_1                    ((uint32_t)0x00000002)        /*!< Bit 1 */
+
+#define  GPIO_CRH_MODE9                      ((uint32_t)0x00000030)        /*!< MODE9[1:0] bits (Port x mode bits, pin 9) */
+#define  GPIO_CRH_MODE9_0                    ((uint32_t)0x00000010)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE9_1                    ((uint32_t)0x00000020)        /*!< Bit 1 */
+
+#define  GPIO_CRH_MODE10                     ((uint32_t)0x00000300)        /*!< MODE10[1:0] bits (Port x mode bits, pin 10) */
+#define  GPIO_CRH_MODE10_0                   ((uint32_t)0x00000100)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE10_1                   ((uint32_t)0x00000200)        /*!< Bit 1 */
+
+#define  GPIO_CRH_MODE11                     ((uint32_t)0x00003000)        /*!< MODE11[1:0] bits (Port x mode bits, pin 11) */
+#define  GPIO_CRH_MODE11_0                   ((uint32_t)0x00001000)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE11_1                   ((uint32_t)0x00002000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_MODE12                     ((uint32_t)0x00030000)        /*!< MODE12[1:0] bits (Port x mode bits, pin 12) */
+#define  GPIO_CRH_MODE12_0                   ((uint32_t)0x00010000)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE12_1                   ((uint32_t)0x00020000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_MODE13                     ((uint32_t)0x00300000)        /*!< MODE13[1:0] bits (Port x mode bits, pin 13) */
+#define  GPIO_CRH_MODE13_0                   ((uint32_t)0x00100000)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE13_1                   ((uint32_t)0x00200000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_MODE14                     ((uint32_t)0x03000000)        /*!< MODE14[1:0] bits (Port x mode bits, pin 14) */
+#define  GPIO_CRH_MODE14_0                   ((uint32_t)0x01000000)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE14_1                   ((uint32_t)0x02000000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_MODE15                     ((uint32_t)0x30000000)        /*!< MODE15[1:0] bits (Port x mode bits, pin 15) */
+#define  GPIO_CRH_MODE15_0                   ((uint32_t)0x10000000)        /*!< Bit 0 */
+#define  GPIO_CRH_MODE15_1                   ((uint32_t)0x20000000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF                        ((uint32_t)0xCCCCCCCC)        /*!< Port x configuration bits */
+
+#define  GPIO_CRH_CNF8                       ((uint32_t)0x0000000C)        /*!< CNF8[1:0] bits (Port x configuration bits, pin 8) */
+#define  GPIO_CRH_CNF8_0                     ((uint32_t)0x00000004)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF8_1                     ((uint32_t)0x00000008)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF9                       ((uint32_t)0x000000C0)        /*!< CNF9[1:0] bits (Port x configuration bits, pin 9) */
+#define  GPIO_CRH_CNF9_0                     ((uint32_t)0x00000040)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF9_1                     ((uint32_t)0x00000080)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF10                      ((uint32_t)0x00000C00)        /*!< CNF10[1:0] bits (Port x configuration bits, pin 10) */
+#define  GPIO_CRH_CNF10_0                    ((uint32_t)0x00000400)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF10_1                    ((uint32_t)0x00000800)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF11                      ((uint32_t)0x0000C000)        /*!< CNF11[1:0] bits (Port x configuration bits, pin 11) */
+#define  GPIO_CRH_CNF11_0                    ((uint32_t)0x00004000)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF11_1                    ((uint32_t)0x00008000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF12                      ((uint32_t)0x000C0000)        /*!< CNF12[1:0] bits (Port x configuration bits, pin 12) */
+#define  GPIO_CRH_CNF12_0                    ((uint32_t)0x00040000)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF12_1                    ((uint32_t)0x00080000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF13                      ((uint32_t)0x00C00000)        /*!< CNF13[1:0] bits (Port x configuration bits, pin 13) */
+#define  GPIO_CRH_CNF13_0                    ((uint32_t)0x00400000)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF13_1                    ((uint32_t)0x00800000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF14                      ((uint32_t)0x0C000000)        /*!< CNF14[1:0] bits (Port x configuration bits, pin 14) */
+#define  GPIO_CRH_CNF14_0                    ((uint32_t)0x04000000)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF14_1                    ((uint32_t)0x08000000)        /*!< Bit 1 */
+
+#define  GPIO_CRH_CNF15                      ((uint32_t)0xC0000000)        /*!< CNF15[1:0] bits (Port x configuration bits, pin 15) */
+#define  GPIO_CRH_CNF15_0                    ((uint32_t)0x40000000)        /*!< Bit 0 */
+#define  GPIO_CRH_CNF15_1                    ((uint32_t)0x80000000)        /*!< Bit 1 */
+
+/*!<******************  Bit definition for GPIO_IDR register  *******************/
+#define GPIO_IDR_IDR0                        ((uint16_t)0x0001)            /*!< Port input data, bit 0 */
+#define GPIO_IDR_IDR1                        ((uint16_t)0x0002)            /*!< Port input data, bit 1 */
+#define GPIO_IDR_IDR2                        ((uint16_t)0x0004)            /*!< Port input data, bit 2 */
+#define GPIO_IDR_IDR3                        ((uint16_t)0x0008)            /*!< Port input data, bit 3 */
+#define GPIO_IDR_IDR4                        ((uint16_t)0x0010)            /*!< Port input data, bit 4 */
+#define GPIO_IDR_IDR5                        ((uint16_t)0x0020)            /*!< Port input data, bit 5 */
+#define GPIO_IDR_IDR6                        ((uint16_t)0x0040)            /*!< Port input data, bit 6 */
+#define GPIO_IDR_IDR7                        ((uint16_t)0x0080)            /*!< Port input data, bit 7 */
+#define GPIO_IDR_IDR8                        ((uint16_t)0x0100)            /*!< Port input data, bit 8 */
+#define GPIO_IDR_IDR9                        ((uint16_t)0x0200)            /*!< Port input data, bit 9 */
+#define GPIO_IDR_IDR10                       ((uint16_t)0x0400)            /*!< Port input data, bit 10 */
+#define GPIO_IDR_IDR11                       ((uint16_t)0x0800)            /*!< Port input data, bit 11 */
+#define GPIO_IDR_IDR12                       ((uint16_t)0x1000)            /*!< Port input data, bit 12 */
+#define GPIO_IDR_IDR13                       ((uint16_t)0x2000)            /*!< Port input data, bit 13 */
+#define GPIO_IDR_IDR14                       ((uint16_t)0x4000)            /*!< Port input data, bit 14 */
+#define GPIO_IDR_IDR15                       ((uint16_t)0x8000)            /*!< Port input data, bit 15 */
+
+/*******************  Bit definition for GPIO_ODR register  *******************/
+#define GPIO_ODR_ODR0                        ((uint16_t)0x0001)            /*!< Port output data, bit 0 */
+#define GPIO_ODR_ODR1                        ((uint16_t)0x0002)            /*!< Port output data, bit 1 */
+#define GPIO_ODR_ODR2                        ((uint16_t)0x0004)            /*!< Port output data, bit 2 */
+#define GPIO_ODR_ODR3                        ((uint16_t)0x0008)            /*!< Port output data, bit 3 */
+#define GPIO_ODR_ODR4                        ((uint16_t)0x0010)            /*!< Port output data, bit 4 */
+#define GPIO_ODR_ODR5                        ((uint16_t)0x0020)            /*!< Port output data, bit 5 */
+#define GPIO_ODR_ODR6                        ((uint16_t)0x0040)            /*!< Port output data, bit 6 */
+#define GPIO_ODR_ODR7                        ((uint16_t)0x0080)            /*!< Port output data, bit 7 */
+#define GPIO_ODR_ODR8                        ((uint16_t)0x0100)            /*!< Port output data, bit 8 */
+#define GPIO_ODR_ODR9                        ((uint16_t)0x0200)            /*!< Port output data, bit 9 */
+#define GPIO_ODR_ODR10                       ((uint16_t)0x0400)            /*!< Port output data, bit 10 */
+#define GPIO_ODR_ODR11                       ((uint16_t)0x0800)            /*!< Port output data, bit 11 */
+#define GPIO_ODR_ODR12                       ((uint16_t)0x1000)            /*!< Port output data, bit 12 */
+#define GPIO_ODR_ODR13                       ((uint16_t)0x2000)            /*!< Port output data, bit 13 */
+#define GPIO_ODR_ODR14                       ((uint16_t)0x4000)            /*!< Port output data, bit 14 */
+#define GPIO_ODR_ODR15                       ((uint16_t)0x8000)            /*!< Port output data, bit 15 */
+
+/******************  Bit definition for GPIO_BSRR register  *******************/
+#define GPIO_BSRR_BS0                        ((uint32_t)0x00000001)        /*!< Port x Set bit 0 */
+#define GPIO_BSRR_BS1                        ((uint32_t)0x00000002)        /*!< Port x Set bit 1 */
+#define GPIO_BSRR_BS2                        ((uint32_t)0x00000004)        /*!< Port x Set bit 2 */
+#define GPIO_BSRR_BS3                        ((uint32_t)0x00000008)        /*!< Port x Set bit 3 */
+#define GPIO_BSRR_BS4                        ((uint32_t)0x00000010)        /*!< Port x Set bit 4 */
+#define GPIO_BSRR_BS5                        ((uint32_t)0x00000020)        /*!< Port x Set bit 5 */
+#define GPIO_BSRR_BS6                        ((uint32_t)0x00000040)        /*!< Port x Set bit 6 */
+#define GPIO_BSRR_BS7                        ((uint32_t)0x00000080)        /*!< Port x Set bit 7 */
+#define GPIO_BSRR_BS8                        ((uint32_t)0x00000100)        /*!< Port x Set bit 8 */
+#define GPIO_BSRR_BS9                        ((uint32_t)0x00000200)        /*!< Port x Set bit 9 */
+#define GPIO_BSRR_BS10                       ((uint32_t)0x00000400)        /*!< Port x Set bit 10 */
+#define GPIO_BSRR_BS11                       ((uint32_t)0x00000800)        /*!< Port x Set bit 11 */
+#define GPIO_BSRR_BS12                       ((uint32_t)0x00001000)        /*!< Port x Set bit 12 */
+#define GPIO_BSRR_BS13                       ((uint32_t)0x00002000)        /*!< Port x Set bit 13 */
+#define GPIO_BSRR_BS14                       ((uint32_t)0x00004000)        /*!< Port x Set bit 14 */
+#define GPIO_BSRR_BS15                       ((uint32_t)0x00008000)        /*!< Port x Set bit 15 */
+
+#define GPIO_BSRR_BR0                        ((uint32_t)0x00010000)        /*!< Port x Reset bit 0 */
+#define GPIO_BSRR_BR1                        ((uint32_t)0x00020000)        /*!< Port x Reset bit 1 */
+#define GPIO_BSRR_BR2                        ((uint32_t)0x00040000)        /*!< Port x Reset bit 2 */
+#define GPIO_BSRR_BR3                        ((uint32_t)0x00080000)        /*!< Port x Reset bit 3 */
+#define GPIO_BSRR_BR4                        ((uint32_t)0x00100000)        /*!< Port x Reset bit 4 */
+#define GPIO_BSRR_BR5                        ((uint32_t)0x00200000)        /*!< Port x Reset bit 5 */
+#define GPIO_BSRR_BR6                        ((uint32_t)0x00400000)        /*!< Port x Reset bit 6 */
+#define GPIO_BSRR_BR7                        ((uint32_t)0x00800000)        /*!< Port x Reset bit 7 */
+#define GPIO_BSRR_BR8                        ((uint32_t)0x01000000)        /*!< Port x Reset bit 8 */
+#define GPIO_BSRR_BR9                        ((uint32_t)0x02000000)        /*!< Port x Reset bit 9 */
+#define GPIO_BSRR_BR10                       ((uint32_t)0x04000000)        /*!< Port x Reset bit 10 */
+#define GPIO_BSRR_BR11                       ((uint32_t)0x08000000)        /*!< Port x Reset bit 11 */
+#define GPIO_BSRR_BR12                       ((uint32_t)0x10000000)        /*!< Port x Reset bit 12 */
+#define GPIO_BSRR_BR13                       ((uint32_t)0x20000000)        /*!< Port x Reset bit 13 */
+#define GPIO_BSRR_BR14                       ((uint32_t)0x40000000)        /*!< Port x Reset bit 14 */
+#define GPIO_BSRR_BR15                       ((uint32_t)0x80000000)        /*!< Port x Reset bit 15 */
+
+/*******************  Bit definition for GPIO_BRR register  *******************/
+#define GPIO_BRR_BR0                         ((uint16_t)0x0001)            /*!< Port x Reset bit 0 */
+#define GPIO_BRR_BR1                         ((uint16_t)0x0002)            /*!< Port x Reset bit 1 */
+#define GPIO_BRR_BR2                         ((uint16_t)0x0004)            /*!< Port x Reset bit 2 */
+#define GPIO_BRR_BR3                         ((uint16_t)0x0008)            /*!< Port x Reset bit 3 */
+#define GPIO_BRR_BR4                         ((uint16_t)0x0010)            /*!< Port x Reset bit 4 */
+#define GPIO_BRR_BR5                         ((uint16_t)0x0020)            /*!< Port x Reset bit 5 */
+#define GPIO_BRR_BR6                         ((uint16_t)0x0040)            /*!< Port x Reset bit 6 */
+#define GPIO_BRR_BR7                         ((uint16_t)0x0080)            /*!< Port x Reset bit 7 */
+#define GPIO_BRR_BR8                         ((uint16_t)0x0100)            /*!< Port x Reset bit 8 */
+#define GPIO_BRR_BR9                         ((uint16_t)0x0200)            /*!< Port x Reset bit 9 */
+#define GPIO_BRR_BR10                        ((uint16_t)0x0400)            /*!< Port x Reset bit 10 */
+#define GPIO_BRR_BR11                        ((uint16_t)0x0800)            /*!< Port x Reset bit 11 */
+#define GPIO_BRR_BR12                        ((uint16_t)0x1000)            /*!< Port x Reset bit 12 */
+#define GPIO_BRR_BR13                        ((uint16_t)0x2000)            /*!< Port x Reset bit 13 */
+#define GPIO_BRR_BR14                        ((uint16_t)0x4000)            /*!< Port x Reset bit 14 */
+#define GPIO_BRR_BR15                        ((uint16_t)0x8000)            /*!< Port x Reset bit 15 */
+
+/******************  Bit definition for GPIO_LCKR register  *******************/
+#define GPIO_LCKR_LCK0                       ((uint32_t)0x00000001)        /*!< Port x Lock bit 0 */
+#define GPIO_LCKR_LCK1                       ((uint32_t)0x00000002)        /*!< Port x Lock bit 1 */
+#define GPIO_LCKR_LCK2                       ((uint32_t)0x00000004)        /*!< Port x Lock bit 2 */
+#define GPIO_LCKR_LCK3                       ((uint32_t)0x00000008)        /*!< Port x Lock bit 3 */
+#define GPIO_LCKR_LCK4                       ((uint32_t)0x00000010)        /*!< Port x Lock bit 4 */
+#define GPIO_LCKR_LCK5                       ((uint32_t)0x00000020)        /*!< Port x Lock bit 5 */
+#define GPIO_LCKR_LCK6                       ((uint32_t)0x00000040)        /*!< Port x Lock bit 6 */
+#define GPIO_LCKR_LCK7                       ((uint32_t)0x00000080)        /*!< Port x Lock bit 7 */
+#define GPIO_LCKR_LCK8                       ((uint32_t)0x00000100)        /*!< Port x Lock bit 8 */
+#define GPIO_LCKR_LCK9                       ((uint32_t)0x00000200)        /*!< Port x Lock bit 9 */
+#define GPIO_LCKR_LCK10                      ((uint32_t)0x00000400)        /*!< Port x Lock bit 10 */
+#define GPIO_LCKR_LCK11                      ((uint32_t)0x00000800)        /*!< Port x Lock bit 11 */
+#define GPIO_LCKR_LCK12                      ((uint32_t)0x00001000)        /*!< Port x Lock bit 12 */
+#define GPIO_LCKR_LCK13                      ((uint32_t)0x00002000)        /*!< Port x Lock bit 13 */
+#define GPIO_LCKR_LCK14                      ((uint32_t)0x00004000)        /*!< Port x Lock bit 14 */
+#define GPIO_LCKR_LCK15                      ((uint32_t)0x00008000)        /*!< Port x Lock bit 15 */
+#define GPIO_LCKR_LCKK                       ((uint32_t)0x00010000)        /*!< Lock key */
+
+/*----------------------------------------------------------------------------*/
+
+/******************  Bit definition for AFIO_EVCR register  *******************/
+#define AFIO_EVCR_PIN                        ((uint8_t)0x0F)               /*!< PIN[3:0] bits (Pin selection) */
+#define AFIO_EVCR_PIN_0                      ((uint8_t)0x01)               /*!< Bit 0 */
+#define AFIO_EVCR_PIN_1                      ((uint8_t)0x02)               /*!< Bit 1 */
+#define AFIO_EVCR_PIN_2                      ((uint8_t)0x04)               /*!< Bit 2 */
+#define AFIO_EVCR_PIN_3                      ((uint8_t)0x08)               /*!< Bit 3 */
+
+/*!< PIN configuration */
+#define AFIO_EVCR_PIN_PX0                    ((uint8_t)0x00)               /*!< Pin 0 selected */
+#define AFIO_EVCR_PIN_PX1                    ((uint8_t)0x01)               /*!< Pin 1 selected */
+#define AFIO_EVCR_PIN_PX2                    ((uint8_t)0x02)               /*!< Pin 2 selected */
+#define AFIO_EVCR_PIN_PX3                    ((uint8_t)0x03)               /*!< Pin 3 selected */
+#define AFIO_EVCR_PIN_PX4                    ((uint8_t)0x04)               /*!< Pin 4 selected */
+#define AFIO_EVCR_PIN_PX5                    ((uint8_t)0x05)               /*!< Pin 5 selected */
+#define AFIO_EVCR_PIN_PX6                    ((uint8_t)0x06)               /*!< Pin 6 selected */
+#define AFIO_EVCR_PIN_PX7                    ((uint8_t)0x07)               /*!< Pin 7 selected */
+#define AFIO_EVCR_PIN_PX8                    ((uint8_t)0x08)               /*!< Pin 8 selected */
+#define AFIO_EVCR_PIN_PX9                    ((uint8_t)0x09)               /*!< Pin 9 selected */
+#define AFIO_EVCR_PIN_PX10                   ((uint8_t)0x0A)               /*!< Pin 10 selected */
+#define AFIO_EVCR_PIN_PX11                   ((uint8_t)0x0B)               /*!< Pin 11 selected */
+#define AFIO_EVCR_PIN_PX12                   ((uint8_t)0x0C)               /*!< Pin 12 selected */
+#define AFIO_EVCR_PIN_PX13                   ((uint8_t)0x0D)               /*!< Pin 13 selected */
+#define AFIO_EVCR_PIN_PX14                   ((uint8_t)0x0E)               /*!< Pin 14 selected */
+#define AFIO_EVCR_PIN_PX15                   ((uint8_t)0x0F)               /*!< Pin 15 selected */
+
+#define AFIO_EVCR_PORT                       ((uint8_t)0x70)               /*!< PORT[2:0] bits (Port selection) */
+#define AFIO_EVCR_PORT_0                     ((uint8_t)0x10)               /*!< Bit 0 */
+#define AFIO_EVCR_PORT_1                     ((uint8_t)0x20)               /*!< Bit 1 */
+#define AFIO_EVCR_PORT_2                     ((uint8_t)0x40)               /*!< Bit 2 */
+
+/*!< PORT configuration */
+#define AFIO_EVCR_PORT_PA                    ((uint8_t)0x00)               /*!< Port A selected */
+#define AFIO_EVCR_PORT_PB                    ((uint8_t)0x10)               /*!< Port B selected */
+#define AFIO_EVCR_PORT_PC                    ((uint8_t)0x20)               /*!< Port C selected */
+#define AFIO_EVCR_PORT_PD                    ((uint8_t)0x30)               /*!< Port D selected */
+#define AFIO_EVCR_PORT_PE                    ((uint8_t)0x40)               /*!< Port E selected */
+
+#define AFIO_EVCR_EVOE                       ((uint8_t)0x80)               /*!< Event Output Enable */
+
+/******************  Bit definition for AFIO_MAPR register  *******************/
+#define AFIO_MAPR_SPI1_REMAP                 ((uint32_t)0x00000001)        /*!< SPI1 remapping */
+#define AFIO_MAPR_I2C1_REMAP                 ((uint32_t)0x00000002)        /*!< I2C1 remapping */
+#define AFIO_MAPR_USART1_REMAP               ((uint32_t)0x00000004)        /*!< USART1 remapping */
+#define AFIO_MAPR_USART2_REMAP               ((uint32_t)0x00000008)        /*!< USART2 remapping */
+
+#define AFIO_MAPR_USART3_REMAP               ((uint32_t)0x00000030)        /*!< USART3_REMAP[1:0] bits (USART3 remapping) */
+#define AFIO_MAPR_USART3_REMAP_0             ((uint32_t)0x00000010)        /*!< Bit 0 */
+#define AFIO_MAPR_USART3_REMAP_1             ((uint32_t)0x00000020)        /*!< Bit 1 */
+
+/* USART3_REMAP configuration */
+#define AFIO_MAPR_USART3_REMAP_NOREMAP       ((uint32_t)0x00000000)        /*!< No remap (TX/PB10, RX/PB11, CK/PB12, CTS/PB13, RTS/PB14) */
+#define AFIO_MAPR_USART3_REMAP_PARTIALREMAP  ((uint32_t)0x00000010)        /*!< Partial remap (TX/PC10, RX/PC11, CK/PC12, CTS/PB13, RTS/PB14) */
+#define AFIO_MAPR_USART3_REMAP_FULLREMAP     ((uint32_t)0x00000030)        /*!< Full remap (TX/PD8, RX/PD9, CK/PD10, CTS/PD11, RTS/PD12) */
+
+#define AFIO_MAPR_TIM1_REMAP                 ((uint32_t)0x000000C0)        /*!< TIM1_REMAP[1:0] bits (TIM1 remapping) */
+#define AFIO_MAPR_TIM1_REMAP_0               ((uint32_t)0x00000040)        /*!< Bit 0 */
+#define AFIO_MAPR_TIM1_REMAP_1               ((uint32_t)0x00000080)        /*!< Bit 1 */
+
+/*!< TIM1_REMAP configuration */
+#define AFIO_MAPR_TIM1_REMAP_NOREMAP         ((uint32_t)0x00000000)        /*!< No remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PB12, CH1N/PB13, CH2N/PB14, CH3N/PB15) */
+#define AFIO_MAPR_TIM1_REMAP_PARTIALREMAP    ((uint32_t)0x00000040)        /*!< Partial remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PA6, CH1N/PA7, CH2N/PB0, CH3N/PB1) */
+#define AFIO_MAPR_TIM1_REMAP_FULLREMAP       ((uint32_t)0x000000C0)        /*!< Full remap (ETR/PE7, CH1/PE9, CH2/PE11, CH3/PE13, CH4/PE14, BKIN/PE15, CH1N/PE8, CH2N/PE10, CH3N/PE12) */
+
+#define AFIO_MAPR_TIM2_REMAP                 ((uint32_t)0x00000300)        /*!< TIM2_REMAP[1:0] bits (TIM2 remapping) */
+#define AFIO_MAPR_TIM2_REMAP_0               ((uint32_t)0x00000100)        /*!< Bit 0 */
+#define AFIO_MAPR_TIM2_REMAP_1               ((uint32_t)0x00000200)        /*!< Bit 1 */
+
+/*!< TIM2_REMAP configuration */
+#define AFIO_MAPR_TIM2_REMAP_NOREMAP         ((uint32_t)0x00000000)        /*!< No remap (CH1/ETR/PA0, CH2/PA1, CH3/PA2, CH4/PA3) */
+#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP1   ((uint32_t)0x00000100)        /*!< Partial remap (CH1/ETR/PA15, CH2/PB3, CH3/PA2, CH4/PA3) */
+#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP2   ((uint32_t)0x00000200)        /*!< Partial remap (CH1/ETR/PA0, CH2/PA1, CH3/PB10, CH4/PB11) */
+#define AFIO_MAPR_TIM2_REMAP_FULLREMAP       ((uint32_t)0x00000300)        /*!< Full remap (CH1/ETR/PA15, CH2/PB3, CH3/PB10, CH4/PB11) */
+
+#define AFIO_MAPR_TIM3_REMAP                 ((uint32_t)0x00000C00)        /*!< TIM3_REMAP[1:0] bits (TIM3 remapping) */
+#define AFIO_MAPR_TIM3_REMAP_0               ((uint32_t)0x00000400)        /*!< Bit 0 */
+#define AFIO_MAPR_TIM3_REMAP_1               ((uint32_t)0x00000800)        /*!< Bit 1 */
+
+/*!< TIM3_REMAP configuration */
+#define AFIO_MAPR_TIM3_REMAP_NOREMAP         ((uint32_t)0x00000000)        /*!< No remap (CH1/PA6, CH2/PA7, CH3/PB0, CH4/PB1) */
+#define AFIO_MAPR_TIM3_REMAP_PARTIALREMAP    ((uint32_t)0x00000800)        /*!< Partial remap (CH1/PB4, CH2/PB5, CH3/PB0, CH4/PB1) */
+#define AFIO_MAPR_TIM3_REMAP_FULLREMAP       ((uint32_t)0x00000C00)        /*!< Full remap (CH1/PC6, CH2/PC7, CH3/PC8, CH4/PC9) */
+
+#define AFIO_MAPR_TIM4_REMAP                 ((uint32_t)0x00001000)        /*!< TIM4_REMAP bit (TIM4 remapping) */
+
+#define AFIO_MAPR_CAN_REMAP                  ((uint32_t)0x00006000)        /*!< CAN_REMAP[1:0] bits (CAN Alternate function remapping) */
+#define AFIO_MAPR_CAN_REMAP_0                ((uint32_t)0x00002000)        /*!< Bit 0 */
+#define AFIO_MAPR_CAN_REMAP_1                ((uint32_t)0x00004000)        /*!< Bit 1 */
+
+/*!< CAN_REMAP configuration */
+#define AFIO_MAPR_CAN_REMAP_REMAP1           ((uint32_t)0x00000000)        /*!< CANRX mapped to PA11, CANTX mapped to PA12 */
+#define AFIO_MAPR_CAN_REMAP_REMAP2           ((uint32_t)0x00004000)        /*!< CANRX mapped to PB8, CANTX mapped to PB9 */
+#define AFIO_MAPR_CAN_REMAP_REMAP3           ((uint32_t)0x00006000)        /*!< CANRX mapped to PD0, CANTX mapped to PD1 */
+
+#define AFIO_MAPR_PD01_REMAP                 ((uint32_t)0x00008000)        /*!< Port D0/Port D1 mapping on OSC_IN/OSC_OUT */
+#define AFIO_MAPR_TIM5CH4_IREMAP             ((uint32_t)0x00010000)        /*!< TIM5 Channel4 Internal Remap */
+#define AFIO_MAPR_ADC1_ETRGINJ_REMAP         ((uint32_t)0x00020000)        /*!< ADC 1 External Trigger Injected Conversion remapping */
+#define AFIO_MAPR_ADC1_ETRGREG_REMAP         ((uint32_t)0x00040000)        /*!< ADC 1 External Trigger Regular Conversion remapping */
+#define AFIO_MAPR_ADC2_ETRGINJ_REMAP         ((uint32_t)0x00080000)        /*!< ADC 2 External Trigger Injected Conversion remapping */
+#define AFIO_MAPR_ADC2_ETRGREG_REMAP         ((uint32_t)0x00100000)        /*!< ADC 2 External Trigger Regular Conversion remapping */
+
+/*!< SWJ_CFG configuration */
+#define AFIO_MAPR_SWJ_CFG                    ((uint32_t)0x07000000)        /*!< SWJ_CFG[2:0] bits (Serial Wire JTAG configuration) */
+#define AFIO_MAPR_SWJ_CFG_0                  ((uint32_t)0x01000000)        /*!< Bit 0 */
+#define AFIO_MAPR_SWJ_CFG_1                  ((uint32_t)0x02000000)        /*!< Bit 1 */
+#define AFIO_MAPR_SWJ_CFG_2                  ((uint32_t)0x04000000)        /*!< Bit 2 */
+
+#define AFIO_MAPR_SWJ_CFG_RESET              ((uint32_t)0x00000000)        /*!< Full SWJ (JTAG-DP + SW-DP) : Reset State */
+#define AFIO_MAPR_SWJ_CFG_NOJNTRST           ((uint32_t)0x01000000)        /*!< Full SWJ (JTAG-DP + SW-DP) but without JNTRST */
+#define AFIO_MAPR_SWJ_CFG_JTAGDISABLE        ((uint32_t)0x02000000)        /*!< JTAG-DP Disabled and SW-DP Enabled */
+#define AFIO_MAPR_SWJ_CFG_DISABLE            ((uint32_t)0x04000000)        /*!< JTAG-DP Disabled and SW-DP Disabled */
+
+#ifdef STM32F10X_CL
+/*!< ETH_REMAP configuration */
+ #define AFIO_MAPR_ETH_REMAP                  ((uint32_t)0x00200000)        /*!< SPI3_REMAP bit (Ethernet MAC I/O remapping) */
+
+/*!< CAN2_REMAP configuration */
+ #define AFIO_MAPR_CAN2_REMAP                 ((uint32_t)0x00400000)        /*!< CAN2_REMAP bit (CAN2 I/O remapping) */
+
+/*!< MII_RMII_SEL configuration */
+ #define AFIO_MAPR_MII_RMII_SEL               ((uint32_t)0x00800000)        /*!< MII_RMII_SEL bit (Ethernet MII or RMII selection) */
+
+/*!< SPI3_REMAP configuration */
+ #define AFIO_MAPR_SPI3_REMAP                 ((uint32_t)0x10000000)        /*!< SPI3_REMAP bit (SPI3 remapping) */
+
+/*!< TIM2ITR1_IREMAP configuration */
+ #define AFIO_MAPR_TIM2ITR1_IREMAP            ((uint32_t)0x20000000)        /*!< TIM2ITR1_IREMAP bit (TIM2 internal trigger 1 remapping) */
+
+/*!< PTP_PPS_REMAP configuration */
+ #define AFIO_MAPR_PTP_PPS_REMAP              ((uint32_t)0x20000000)        /*!< PTP_PPS_REMAP bit (Ethernet PTP PPS remapping) */
+#endif
+
+/*****************  Bit definition for AFIO_EXTICR1 register  *****************/
+#define AFIO_EXTICR1_EXTI0                   ((uint16_t)0x000F)            /*!< EXTI 0 configuration */
+#define AFIO_EXTICR1_EXTI1                   ((uint16_t)0x00F0)            /*!< EXTI 1 configuration */
+#define AFIO_EXTICR1_EXTI2                   ((uint16_t)0x0F00)            /*!< EXTI 2 configuration */
+#define AFIO_EXTICR1_EXTI3                   ((uint16_t)0xF000)            /*!< EXTI 3 configuration */
+
+/*!< EXTI0 configuration */
+#define AFIO_EXTICR1_EXTI0_PA                ((uint16_t)0x0000)            /*!< PA[0] pin */
+#define AFIO_EXTICR1_EXTI0_PB                ((uint16_t)0x0001)            /*!< PB[0] pin */
+#define AFIO_EXTICR1_EXTI0_PC                ((uint16_t)0x0002)            /*!< PC[0] pin */
+#define AFIO_EXTICR1_EXTI0_PD                ((uint16_t)0x0003)            /*!< PD[0] pin */
+#define AFIO_EXTICR1_EXTI0_PE                ((uint16_t)0x0004)            /*!< PE[0] pin */
+#define AFIO_EXTICR1_EXTI0_PF                ((uint16_t)0x0005)            /*!< PF[0] pin */
+#define AFIO_EXTICR1_EXTI0_PG                ((uint16_t)0x0006)            /*!< PG[0] pin */
+
+/*!< EXTI1 configuration */
+#define AFIO_EXTICR1_EXTI1_PA                ((uint16_t)0x0000)            /*!< PA[1] pin */
+#define AFIO_EXTICR1_EXTI1_PB                ((uint16_t)0x0010)            /*!< PB[1] pin */
+#define AFIO_EXTICR1_EXTI1_PC                ((uint16_t)0x0020)            /*!< PC[1] pin */
+#define AFIO_EXTICR1_EXTI1_PD                ((uint16_t)0x0030)            /*!< PD[1] pin */
+#define AFIO_EXTICR1_EXTI1_PE                ((uint16_t)0x0040)            /*!< PE[1] pin */
+#define AFIO_EXTICR1_EXTI1_PF                ((uint16_t)0x0050)            /*!< PF[1] pin */
+#define AFIO_EXTICR1_EXTI1_PG                ((uint16_t)0x0060)            /*!< PG[1] pin */
+
+/*!< EXTI2 configuration */  
+#define AFIO_EXTICR1_EXTI2_PA                ((uint16_t)0x0000)            /*!< PA[2] pin */
+#define AFIO_EXTICR1_EXTI2_PB                ((uint16_t)0x0100)            /*!< PB[2] pin */
+#define AFIO_EXTICR1_EXTI2_PC                ((uint16_t)0x0200)            /*!< PC[2] pin */
+#define AFIO_EXTICR1_EXTI2_PD                ((uint16_t)0x0300)            /*!< PD[2] pin */
+#define AFIO_EXTICR1_EXTI2_PE                ((uint16_t)0x0400)            /*!< PE[2] pin */
+#define AFIO_EXTICR1_EXTI2_PF                ((uint16_t)0x0500)            /*!< PF[2] pin */
+#define AFIO_EXTICR1_EXTI2_PG                ((uint16_t)0x0600)            /*!< PG[2] pin */
+
+/*!< EXTI3 configuration */
+#define AFIO_EXTICR1_EXTI3_PA                ((uint16_t)0x0000)            /*!< PA[3] pin */
+#define AFIO_EXTICR1_EXTI3_PB                ((uint16_t)0x1000)            /*!< PB[3] pin */
+#define AFIO_EXTICR1_EXTI3_PC                ((uint16_t)0x2000)            /*!< PC[3] pin */
+#define AFIO_EXTICR1_EXTI3_PD                ((uint16_t)0x3000)            /*!< PD[3] pin */
+#define AFIO_EXTICR1_EXTI3_PE                ((uint16_t)0x4000)            /*!< PE[3] pin */
+#define AFIO_EXTICR1_EXTI3_PF                ((uint16_t)0x5000)            /*!< PF[3] pin */
+#define AFIO_EXTICR1_EXTI3_PG                ((uint16_t)0x6000)            /*!< PG[3] pin */
+
+/*****************  Bit definition for AFIO_EXTICR2 register  *****************/
+#define AFIO_EXTICR2_EXTI4                   ((uint16_t)0x000F)            /*!< EXTI 4 configuration */
+#define AFIO_EXTICR2_EXTI5                   ((uint16_t)0x00F0)            /*!< EXTI 5 configuration */
+#define AFIO_EXTICR2_EXTI6                   ((uint16_t)0x0F00)            /*!< EXTI 6 configuration */
+#define AFIO_EXTICR2_EXTI7                   ((uint16_t)0xF000)            /*!< EXTI 7 configuration */
+
+/*!< EXTI4 configuration */
+#define AFIO_EXTICR2_EXTI4_PA                ((uint16_t)0x0000)            /*!< PA[4] pin */
+#define AFIO_EXTICR2_EXTI4_PB                ((uint16_t)0x0001)            /*!< PB[4] pin */
+#define AFIO_EXTICR2_EXTI4_PC                ((uint16_t)0x0002)            /*!< PC[4] pin */
+#define AFIO_EXTICR2_EXTI4_PD                ((uint16_t)0x0003)            /*!< PD[4] pin */
+#define AFIO_EXTICR2_EXTI4_PE                ((uint16_t)0x0004)            /*!< PE[4] pin */
+#define AFIO_EXTICR2_EXTI4_PF                ((uint16_t)0x0005)            /*!< PF[4] pin */
+#define AFIO_EXTICR2_EXTI4_PG                ((uint16_t)0x0006)            /*!< PG[4] pin */
+
+/* EXTI5 configuration */
+#define AFIO_EXTICR2_EXTI5_PA                ((uint16_t)0x0000)            /*!< PA[5] pin */
+#define AFIO_EXTICR2_EXTI5_PB                ((uint16_t)0x0010)            /*!< PB[5] pin */
+#define AFIO_EXTICR2_EXTI5_PC                ((uint16_t)0x0020)            /*!< PC[5] pin */
+#define AFIO_EXTICR2_EXTI5_PD                ((uint16_t)0x0030)            /*!< PD[5] pin */
+#define AFIO_EXTICR2_EXTI5_PE                ((uint16_t)0x0040)            /*!< PE[5] pin */
+#define AFIO_EXTICR2_EXTI5_PF                ((uint16_t)0x0050)            /*!< PF[5] pin */
+#define AFIO_EXTICR2_EXTI5_PG                ((uint16_t)0x0060)            /*!< PG[5] pin */
+
+/*!< EXTI6 configuration */  
+#define AFIO_EXTICR2_EXTI6_PA                ((uint16_t)0x0000)            /*!< PA[6] pin */
+#define AFIO_EXTICR2_EXTI6_PB                ((uint16_t)0x0100)            /*!< PB[6] pin */
+#define AFIO_EXTICR2_EXTI6_PC                ((uint16_t)0x0200)            /*!< PC[6] pin */
+#define AFIO_EXTICR2_EXTI6_PD                ((uint16_t)0x0300)            /*!< PD[6] pin */
+#define AFIO_EXTICR2_EXTI6_PE                ((uint16_t)0x0400)            /*!< PE[6] pin */
+#define AFIO_EXTICR2_EXTI6_PF                ((uint16_t)0x0500)            /*!< PF[6] pin */
+#define AFIO_EXTICR2_EXTI6_PG                ((uint16_t)0x0600)            /*!< PG[6] pin */
+
+/*!< EXTI7 configuration */
+#define AFIO_EXTICR2_EXTI7_PA                ((uint16_t)0x0000)            /*!< PA[7] pin */
+#define AFIO_EXTICR2_EXTI7_PB                ((uint16_t)0x1000)            /*!< PB[7] pin */
+#define AFIO_EXTICR2_EXTI7_PC                ((uint16_t)0x2000)            /*!< PC[7] pin */
+#define AFIO_EXTICR2_EXTI7_PD                ((uint16_t)0x3000)            /*!< PD[7] pin */
+#define AFIO_EXTICR2_EXTI7_PE                ((uint16_t)0x4000)            /*!< PE[7] pin */
+#define AFIO_EXTICR2_EXTI7_PF                ((uint16_t)0x5000)            /*!< PF[7] pin */
+#define AFIO_EXTICR2_EXTI7_PG                ((uint16_t)0x6000)            /*!< PG[7] pin */
+
+/*****************  Bit definition for AFIO_EXTICR3 register  *****************/
+#define AFIO_EXTICR3_EXTI8                   ((uint16_t)0x000F)            /*!< EXTI 8 configuration */
+#define AFIO_EXTICR3_EXTI9                   ((uint16_t)0x00F0)            /*!< EXTI 9 configuration */
+#define AFIO_EXTICR3_EXTI10                  ((uint16_t)0x0F00)            /*!< EXTI 10 configuration */
+#define AFIO_EXTICR3_EXTI11                  ((uint16_t)0xF000)            /*!< EXTI 11 configuration */
+
+/*!< EXTI8 configuration */
+#define AFIO_EXTICR3_EXTI8_PA                ((uint16_t)0x0000)            /*!< PA[8] pin */
+#define AFIO_EXTICR3_EXTI8_PB                ((uint16_t)0x0001)            /*!< PB[8] pin */
+#define AFIO_EXTICR3_EXTI8_PC                ((uint16_t)0x0002)            /*!< PC[8] pin */
+#define AFIO_EXTICR3_EXTI8_PD                ((uint16_t)0x0003)            /*!< PD[8] pin */
+#define AFIO_EXTICR3_EXTI8_PE                ((uint16_t)0x0004)            /*!< PE[8] pin */
+#define AFIO_EXTICR3_EXTI8_PF                ((uint16_t)0x0005)            /*!< PF[8] pin */
+#define AFIO_EXTICR3_EXTI8_PG                ((uint16_t)0x0006)            /*!< PG[8] pin */
+
+/*!< EXTI9 configuration */
+#define AFIO_EXTICR3_EXTI9_PA                ((uint16_t)0x0000)            /*!< PA[9] pin */
+#define AFIO_EXTICR3_EXTI9_PB                ((uint16_t)0x0010)            /*!< PB[9] pin */
+#define AFIO_EXTICR3_EXTI9_PC                ((uint16_t)0x0020)            /*!< PC[9] pin */
+#define AFIO_EXTICR3_EXTI9_PD                ((uint16_t)0x0030)            /*!< PD[9] pin */
+#define AFIO_EXTICR3_EXTI9_PE                ((uint16_t)0x0040)            /*!< PE[9] pin */
+#define AFIO_EXTICR3_EXTI9_PF                ((uint16_t)0x0050)            /*!< PF[9] pin */
+#define AFIO_EXTICR3_EXTI9_PG                ((uint16_t)0x0060)            /*!< PG[9] pin */
+
+/*!< EXTI10 configuration */  
+#define AFIO_EXTICR3_EXTI10_PA               ((uint16_t)0x0000)            /*!< PA[10] pin */
+#define AFIO_EXTICR3_EXTI10_PB               ((uint16_t)0x0100)            /*!< PB[10] pin */
+#define AFIO_EXTICR3_EXTI10_PC               ((uint16_t)0x0200)            /*!< PC[10] pin */
+#define AFIO_EXTICR3_EXTI10_PD               ((uint16_t)0x0300)            /*!< PD[10] pin */
+#define AFIO_EXTICR3_EXTI10_PE               ((uint16_t)0x0400)            /*!< PE[10] pin */
+#define AFIO_EXTICR3_EXTI10_PF               ((uint16_t)0x0500)            /*!< PF[10] pin */
+#define AFIO_EXTICR3_EXTI10_PG               ((uint16_t)0x0600)            /*!< PG[10] pin */
+
+/*!< EXTI11 configuration */
+#define AFIO_EXTICR3_EXTI11_PA               ((uint16_t)0x0000)            /*!< PA[11] pin */
+#define AFIO_EXTICR3_EXTI11_PB               ((uint16_t)0x1000)            /*!< PB[11] pin */
+#define AFIO_EXTICR3_EXTI11_PC               ((uint16_t)0x2000)            /*!< PC[11] pin */
+#define AFIO_EXTICR3_EXTI11_PD               ((uint16_t)0x3000)            /*!< PD[11] pin */
+#define AFIO_EXTICR3_EXTI11_PE               ((uint16_t)0x4000)            /*!< PE[11] pin */
+#define AFIO_EXTICR3_EXTI11_PF               ((uint16_t)0x5000)            /*!< PF[11] pin */
+#define AFIO_EXTICR3_EXTI11_PG               ((uint16_t)0x6000)            /*!< PG[11] pin */
+
+/*****************  Bit definition for AFIO_EXTICR4 register  *****************/
+#define AFIO_EXTICR4_EXTI12                  ((uint16_t)0x000F)            /*!< EXTI 12 configuration */
+#define AFIO_EXTICR4_EXTI13                  ((uint16_t)0x00F0)            /*!< EXTI 13 configuration */
+#define AFIO_EXTICR4_EXTI14                  ((uint16_t)0x0F00)            /*!< EXTI 14 configuration */
+#define AFIO_EXTICR4_EXTI15                  ((uint16_t)0xF000)            /*!< EXTI 15 configuration */
+
+/* EXTI12 configuration */
+#define AFIO_EXTICR4_EXTI12_PA               ((uint16_t)0x0000)            /*!< PA[12] pin */
+#define AFIO_EXTICR4_EXTI12_PB               ((uint16_t)0x0001)            /*!< PB[12] pin */
+#define AFIO_EXTICR4_EXTI12_PC               ((uint16_t)0x0002)            /*!< PC[12] pin */
+#define AFIO_EXTICR4_EXTI12_PD               ((uint16_t)0x0003)            /*!< PD[12] pin */
+#define AFIO_EXTICR4_EXTI12_PE               ((uint16_t)0x0004)            /*!< PE[12] pin */
+#define AFIO_EXTICR4_EXTI12_PF               ((uint16_t)0x0005)            /*!< PF[12] pin */
+#define AFIO_EXTICR4_EXTI12_PG               ((uint16_t)0x0006)            /*!< PG[12] pin */
+
+/* EXTI13 configuration */
+#define AFIO_EXTICR4_EXTI13_PA               ((uint16_t)0x0000)            /*!< PA[13] pin */
+#define AFIO_EXTICR4_EXTI13_PB               ((uint16_t)0x0010)            /*!< PB[13] pin */
+#define AFIO_EXTICR4_EXTI13_PC               ((uint16_t)0x0020)            /*!< PC[13] pin */
+#define AFIO_EXTICR4_EXTI13_PD               ((uint16_t)0x0030)            /*!< PD[13] pin */
+#define AFIO_EXTICR4_EXTI13_PE               ((uint16_t)0x0040)            /*!< PE[13] pin */
+#define AFIO_EXTICR4_EXTI13_PF               ((uint16_t)0x0050)            /*!< PF[13] pin */
+#define AFIO_EXTICR4_EXTI13_PG               ((uint16_t)0x0060)            /*!< PG[13] pin */
+
+/*!< EXTI14 configuration */  
+#define AFIO_EXTICR4_EXTI14_PA               ((uint16_t)0x0000)            /*!< PA[14] pin */
+#define AFIO_EXTICR4_EXTI14_PB               ((uint16_t)0x0100)            /*!< PB[14] pin */
+#define AFIO_EXTICR4_EXTI14_PC               ((uint16_t)0x0200)            /*!< PC[14] pin */
+#define AFIO_EXTICR4_EXTI14_PD               ((uint16_t)0x0300)            /*!< PD[14] pin */
+#define AFIO_EXTICR4_EXTI14_PE               ((uint16_t)0x0400)            /*!< PE[14] pin */
+#define AFIO_EXTICR4_EXTI14_PF               ((uint16_t)0x0500)            /*!< PF[14] pin */
+#define AFIO_EXTICR4_EXTI14_PG               ((uint16_t)0x0600)            /*!< PG[14] pin */
+
+/*!< EXTI15 configuration */
+#define AFIO_EXTICR4_EXTI15_PA               ((uint16_t)0x0000)            /*!< PA[15] pin */
+#define AFIO_EXTICR4_EXTI15_PB               ((uint16_t)0x1000)            /*!< PB[15] pin */
+#define AFIO_EXTICR4_EXTI15_PC               ((uint16_t)0x2000)            /*!< PC[15] pin */
+#define AFIO_EXTICR4_EXTI15_PD               ((uint16_t)0x3000)            /*!< PD[15] pin */
+#define AFIO_EXTICR4_EXTI15_PE               ((uint16_t)0x4000)            /*!< PE[15] pin */
+#define AFIO_EXTICR4_EXTI15_PF               ((uint16_t)0x5000)            /*!< PF[15] pin */
+#define AFIO_EXTICR4_EXTI15_PG               ((uint16_t)0x6000)            /*!< PG[15] pin */
+
+/******************************************************************************/
+/*                                                                            */
+/*                               SystemTick                                   */
+/*                                                                            */
+/******************************************************************************/
+
+/*****************  Bit definition for SysTick_CTRL register  *****************/
+#define  SysTick_CTRL_ENABLE                 ((uint32_t)0x00000001)        /*!< Counter enable */
+#define  SysTick_CTRL_TICKINT                ((uint32_t)0x00000002)        /*!< Counting down to 0 pends the SysTick handler */
+#define  SysTick_CTRL_CLKSOURCE              ((uint32_t)0x00000004)        /*!< Clock source */
+#define  SysTick_CTRL_COUNTFLAG              ((uint32_t)0x00010000)        /*!< Count Flag */
+
+/*****************  Bit definition for SysTick_LOAD register  *****************/
+#define  SysTick_LOAD_RELOAD                 ((uint32_t)0x00FFFFFF)        /*!< Value to load into the SysTick Current Value Register when the counter reaches 0 */
+
+/*****************  Bit definition for SysTick_VAL register  ******************/
+#define  SysTick_VAL_CURRENT                 ((uint32_t)0x00FFFFFF)        /*!< Current value at the time the register is accessed */
+
+/*****************  Bit definition for SysTick_CALIB register  ****************/
+#define  SysTick_CALIB_TENMS                 ((uint32_t)0x00FFFFFF)        /*!< Reload value to use for 10ms timing */
+#define  SysTick_CALIB_SKEW                  ((uint32_t)0x40000000)        /*!< Calibration value is not exactly 10 ms */
+#define  SysTick_CALIB_NOREF                 ((uint32_t)0x80000000)        /*!< The reference clock is not provided */
+
+/******************************************************************************/
+/*                                                                            */
+/*                  Nested Vectored Interrupt Controller                      */
+/*                                                                            */
+/******************************************************************************/
+
+/******************  Bit definition for NVIC_ISER register  *******************/
+#define  NVIC_ISER_SETENA                    ((uint32_t)0xFFFFFFFF)        /*!< Interrupt set enable bits */
+#define  NVIC_ISER_SETENA_0                  ((uint32_t)0x00000001)        /*!< bit 0 */
+#define  NVIC_ISER_SETENA_1                  ((uint32_t)0x00000002)        /*!< bit 1 */
+#define  NVIC_ISER_SETENA_2                  ((uint32_t)0x00000004)        /*!< bit 2 */
+#define  NVIC_ISER_SETENA_3                  ((uint32_t)0x00000008)        /*!< bit 3 */
+#define  NVIC_ISER_SETENA_4                  ((uint32_t)0x00000010)        /*!< bit 4 */
+#define  NVIC_ISER_SETENA_5                  ((uint32_t)0x00000020)        /*!< bit 5 */
+#define  NVIC_ISER_SETENA_6                  ((uint32_t)0x00000040)        /*!< bit 6 */
+#define  NVIC_ISER_SETENA_7                  ((uint32_t)0x00000080)        /*!< bit 7 */
+#define  NVIC_ISER_SETENA_8                  ((uint32_t)0x00000100)        /*!< bit 8 */
+#define  NVIC_ISER_SETENA_9                  ((uint32_t)0x00000200)        /*!< bit 9 */
+#define  NVIC_ISER_SETENA_10                 ((uint32_t)0x00000400)        /*!< bit 10 */
+#define  NVIC_ISER_SETENA_11                 ((uint32_t)0x00000800)        /*!< bit 11 */
+#define  NVIC_ISER_SETENA_12                 ((uint32_t)0x00001000)        /*!< bit 12 */
+#define  NVIC_ISER_SETENA_13                 ((uint32_t)0x00002000)        /*!< bit 13 */
+#define  NVIC_ISER_SETENA_14                 ((uint32_t)0x00004000)        /*!< bit 14 */
+#define  NVIC_ISER_SETENA_15                 ((uint32_t)0x00008000)        /*!< bit 15 */
+#define  NVIC_ISER_SETENA_16                 ((uint32_t)0x00010000)        /*!< bit 16 */
+#define  NVIC_ISER_SETENA_17                 ((uint32_t)0x00020000)        /*!< bit 17 */
+#define  NVIC_ISER_SETENA_18                 ((uint32_t)0x00040000)        /*!< bit 18 */
+#define  NVIC_ISER_SETENA_19                 ((uint32_t)0x00080000)        /*!< bit 19 */
+#define  NVIC_ISER_SETENA_20                 ((uint32_t)0x00100000)        /*!< bit 20 */
+#define  NVIC_ISER_SETENA_21                 ((uint32_t)0x00200000)        /*!< bit 21 */
+#define  NVIC_ISER_SETENA_22                 ((uint32_t)0x00400000)        /*!< bit 22 */
+#define  NVIC_ISER_SETENA_23                 ((uint32_t)0x00800000)        /*!< bit 23 */
+#define  NVIC_ISER_SETENA_24                 ((uint32_t)0x01000000)        /*!< bit 24 */
+#define  NVIC_ISER_SETENA_25                 ((uint32_t)0x02000000)        /*!< bit 25 */
+#define  NVIC_ISER_SETENA_26                 ((uint32_t)0x04000000)        /*!< bit 26 */
+#define  NVIC_ISER_SETENA_27                 ((uint32_t)0x08000000)        /*!< bit 27 */
+#define  NVIC_ISER_SETENA_28                 ((uint32_t)0x10000000)        /*!< bit 28 */
+#define  NVIC_ISER_SETENA_29                 ((uint32_t)0x20000000)        /*!< bit 29 */
+#define  NVIC_ISER_SETENA_30                 ((uint32_t)0x40000000)        /*!< bit 30 */
+#define  NVIC_ISER_SETENA_31                 ((uint32_t)0x80000000)        /*!< bit 31 */
+
+/******************  Bit definition for NVIC_ICER register  *******************/
+#define  NVIC_ICER_CLRENA                   ((uint32_t)0xFFFFFFFF)        /*!< Interrupt clear-enable bits */
+#define  NVIC_ICER_CLRENA_0                  ((uint32_t)0x00000001)        /*!< bit 0 */
+#define  NVIC_ICER_CLRENA_1                  ((uint32_t)0x00000002)        /*!< bit 1 */
+#define  NVIC_ICER_CLRENA_2                  ((uint32_t)0x00000004)        /*!< bit 2 */
+#define  NVIC_ICER_CLRENA_3                  ((uint32_t)0x00000008)        /*!< bit 3 */
+#define  NVIC_ICER_CLRENA_4                  ((uint32_t)0x00000010)        /*!< bit 4 */
+#define  NVIC_ICER_CLRENA_5                  ((uint32_t)0x00000020)        /*!< bit 5 */
+#define  NVIC_ICER_CLRENA_6                  ((uint32_t)0x00000040)        /*!< bit 6 */
+#define  NVIC_ICER_CLRENA_7                  ((uint32_t)0x00000080)        /*!< bit 7 */
+#define  NVIC_ICER_CLRENA_8                  ((uint32_t)0x00000100)        /*!< bit 8 */
+#define  NVIC_ICER_CLRENA_9                  ((uint32_t)0x00000200)        /*!< bit 9 */
+#define  NVIC_ICER_CLRENA_10                 ((uint32_t)0x00000400)        /*!< bit 10 */
+#define  NVIC_ICER_CLRENA_11                 ((uint32_t)0x00000800)        /*!< bit 11 */
+#define  NVIC_ICER_CLRENA_12                 ((uint32_t)0x00001000)        /*!< bit 12 */
+#define  NVIC_ICER_CLRENA_13                 ((uint32_t)0x00002000)        /*!< bit 13 */
+#define  NVIC_ICER_CLRENA_14                 ((uint32_t)0x00004000)        /*!< bit 14 */
+#define  NVIC_ICER_CLRENA_15                 ((uint32_t)0x00008000)        /*!< bit 15 */
+#define  NVIC_ICER_CLRENA_16                 ((uint32_t)0x00010000)        /*!< bit 16 */
+#define  NVIC_ICER_CLRENA_17                 ((uint32_t)0x00020000)        /*!< bit 17 */
+#define  NVIC_ICER_CLRENA_18                 ((uint32_t)0x00040000)        /*!< bit 18 */
+#define  NVIC_ICER_CLRENA_19                 ((uint32_t)0x00080000)        /*!< bit 19 */
+#define  NVIC_ICER_CLRENA_20                 ((uint32_t)0x00100000)        /*!< bit 20 */
+#define  NVIC_ICER_CLRENA_21                 ((uint32_t)0x00200000)        /*!< bit 21 */
+#define  NVIC_ICER_CLRENA_22                 ((uint32_t)0x00400000)        /*!< bit 22 */
+#define  NVIC_ICER_CLRENA_23                 ((uint32_t)0x00800000)        /*!< bit 23 */
+#define  NVIC_ICER_CLRENA_24                 ((uint32_t)0x01000000)        /*!< bit 24 */
+#define  NVIC_ICER_CLRENA_25                 ((uint32_t)0x02000000)        /*!< bit 25 */
+#define  NVIC_ICER_CLRENA_26                 ((uint32_t)0x04000000)        /*!< bit 26 */
+#define  NVIC_ICER_CLRENA_27                 ((uint32_t)0x08000000)        /*!< bit 27 */
+#define  NVIC_ICER_CLRENA_28                 ((uint32_t)0x10000000)        /*!< bit 28 */
+#define  NVIC_ICER_CLRENA_29                 ((uint32_t)0x20000000)        /*!< bit 29 */
+#define  NVIC_ICER_CLRENA_30                 ((uint32_t)0x40000000)        /*!< bit 30 */
+#define  NVIC_ICER_CLRENA_31                 ((uint32_t)0x80000000)        /*!< bit 31 */
+
+/******************  Bit definition for NVIC_ISPR register  *******************/
+#define  NVIC_ISPR_SETPEND                   ((uint32_t)0xFFFFFFFF)        /*!< Interrupt set-pending bits */
+#define  NVIC_ISPR_SETPEND_0                 ((uint32_t)0x00000001)        /*!< bit 0 */
+#define  NVIC_ISPR_SETPEND_1                 ((uint32_t)0x00000002)        /*!< bit 1 */
+#define  NVIC_ISPR_SETPEND_2                 ((uint32_t)0x00000004)        /*!< bit 2 */
+#define  NVIC_ISPR_SETPEND_3                 ((uint32_t)0x00000008)        /*!< bit 3 */
+#define  NVIC_ISPR_SETPEND_4                 ((uint32_t)0x00000010)        /*!< bit 4 */
+#define  NVIC_ISPR_SETPEND_5                 ((uint32_t)0x00000020)        /*!< bit 5 */
+#define  NVIC_ISPR_SETPEND_6                 ((uint32_t)0x00000040)        /*!< bit 6 */
+#define  NVIC_ISPR_SETPEND_7                 ((uint32_t)0x00000080)        /*!< bit 7 */
+#define  NVIC_ISPR_SETPEND_8                 ((uint32_t)0x00000100)        /*!< bit 8 */
+#define  NVIC_ISPR_SETPEND_9                 ((uint32_t)0x00000200)        /*!< bit 9 */
+#define  NVIC_ISPR_SETPEND_10                ((uint32_t)0x00000400)        /*!< bit 10 */
+#define  NVIC_ISPR_SETPEND_11                ((uint32_t)0x00000800)        /*!< bit 11 */
+#define  NVIC_ISPR_SETPEND_12                ((uint32_t)0x00001000)        /*!< bit 12 */
+#define  NVIC_ISPR_SETPEND_13                ((uint32_t)0x00002000)        /*!< bit 13 */
+#define  NVIC_ISPR_SETPEND_14                ((uint32_t)0x00004000)        /*!< bit 14 */
+#define  NVIC_ISPR_SETPEND_15                ((uint32_t)0x00008000)        /*!< bit 15 */
+#define  NVIC_ISPR_SETPEND_16                ((uint32_t)0x00010000)        /*!< bit 16 */
+#define  NVIC_ISPR_SETPEND_17                ((uint32_t)0x00020000)        /*!< bit 17 */
+#define  NVIC_ISPR_SETPEND_18                ((uint32_t)0x00040000)        /*!< bit 18 */
+#define  NVIC_ISPR_SETPEND_19                ((uint32_t)0x00080000)        /*!< bit 19 */
+#define  NVIC_ISPR_SETPEND_20                ((uint32_t)0x00100000)        /*!< bit 20 */
+#define  NVIC_ISPR_SETPEND_21                ((uint32_t)0x00200000)        /*!< bit 21 */
+#define  NVIC_ISPR_SETPEND_22                ((uint32_t)0x00400000)        /*!< bit 22 */
+#define  NVIC_ISPR_SETPEND_23                ((uint32_t)0x00800000)        /*!< bit 23 */
+#define  NVIC_ISPR_SETPEND_24                ((uint32_t)0x01000000)        /*!< bit 24 */
+#define  NVIC_ISPR_SETPEND_25                ((uint32_t)0x02000000)        /*!< bit 25 */
+#define  NVIC_ISPR_SETPEND_26                ((uint32_t)0x04000000)        /*!< bit 26 */
+#define  NVIC_ISPR_SETPEND_27                ((uint32_t)0x08000000)        /*!< bit 27 */
+#define  NVIC_ISPR_SETPEND_28                ((uint32_t)0x10000000)        /*!< bit 28 */
+#define  NVIC_ISPR_SETPEND_29                ((uint32_t)0x20000000)        /*!< bit 29 */
+#define  NVIC_ISPR_SETPEND_30                ((uint32_t)0x40000000)        /*!< bit 30 */
+#define  NVIC_ISPR_SETPEND_31                ((uint32_t)0x80000000)        /*!< bit 31 */
+
+/******************  Bit definition for NVIC_ICPR register  *******************/
+#define  NVIC_ICPR_CLRPEND                   ((uint32_t)0xFFFFFFFF)        /*!< Interrupt clear-pending bits */
+#define  NVIC_ICPR_CLRPEND_0                 ((uint32_t)0x00000001)        /*!< bit 0 */
+#define  NVIC_ICPR_CLRPEND_1                 ((uint32_t)0x00000002)        /*!< bit 1 */
+#define  NVIC_ICPR_CLRPEND_2                 ((uint32_t)0x00000004)        /*!< bit 2 */
+#define  NVIC_ICPR_CLRPEND_3                 ((uint32_t)0x00000008)        /*!< bit 3 */
+#define  NVIC_ICPR_CLRPEND_4                 ((uint32_t)0x00000010)        /*!< bit 4 */
+#define  NVIC_ICPR_CLRPEND_5                 ((uint32_t)0x00000020)        /*!< bit 5 */
+#define  NVIC_ICPR_CLRPEND_6                 ((uint32_t)0x00000040)        /*!< bit 6 */
+#define  NVIC_ICPR_CLRPEND_7                 ((uint32_t)0x00000080)        /*!< bit 7 */
+#define  NVIC_ICPR_CLRPEND_8                 ((uint32_t)0x00000100)        /*!< bit 8 */
+#define  NVIC_ICPR_CLRPEND_9                 ((uint32_t)0x00000200)        /*!< bit 9 */
+#define  NVIC_ICPR_CLRPEND_10                ((uint32_t)0x00000400)        /*!< bit 10 */
+#define  NVIC_ICPR_CLRPEND_11                ((uint32_t)0x00000800)        /*!< bit 11 */
+#define  NVIC_ICPR_CLRPEND_12                ((uint32_t)0x00001000)        /*!< bit 12 */
+#define  NVIC_ICPR_CLRPEND_13                ((uint32_t)0x00002000)        /*!< bit 13 */
+#define  NVIC_ICPR_CLRPEND_14                ((uint32_t)0x00004000)        /*!< bit 14 */
+#define  NVIC_ICPR_CLRPEND_15                ((uint32_t)0x00008000)        /*!< bit 15 */
+#define  NVIC_ICPR_CLRPEND_16                ((uint32_t)0x00010000)        /*!< bit 16 */
+#define  NVIC_ICPR_CLRPEND_17                ((uint32_t)0x00020000)        /*!< bit 17 */
+#define  NVIC_ICPR_CLRPEND_18                ((uint32_t)0x00040000)        /*!< bit 18 */
+#define  NVIC_ICPR_CLRPEND_19                ((uint32_t)0x00080000)        /*!< bit 19 */
+#define  NVIC_ICPR_CLRPEND_20                ((uint32_t)0x00100000)        /*!< bit 20 */
+#define  NVIC_ICPR_CLRPEND_21                ((uint32_t)0x00200000)        /*!< bit 21 */
+#define  NVIC_ICPR_CLRPEND_22                ((uint32_t)0x00400000)        /*!< bit 22 */
+#define  NVIC_ICPR_CLRPEND_23                ((uint32_t)0x00800000)        /*!< bit 23 */
+#define  NVIC_ICPR_CLRPEND_24                ((uint32_t)0x01000000)        /*!< bit 24 */
+#define  NVIC_ICPR_CLRPEND_25                ((uint32_t)0x02000000)        /*!< bit 25 */
+#define  NVIC_ICPR_CLRPEND_26                ((uint32_t)0x04000000)        /*!< bit 26 */
+#define  NVIC_ICPR_CLRPEND_27                ((uint32_t)0x08000000)        /*!< bit 27 */
+#define  NVIC_ICPR_CLRPEND_28                ((uint32_t)0x10000000)        /*!< bit 28 */
+#define  NVIC_ICPR_CLRPEND_29                ((uint32_t)0x20000000)        /*!< bit 29 */
+#define  NVIC_ICPR_CLRPEND_30                ((uint32_t)0x40000000)        /*!< bit 30 */
+#define  NVIC_ICPR_CLRPEND_31                ((uint32_t)0x80000000)        /*!< bit 31 */
+
+/******************  Bit definition for NVIC_IABR register  *******************/
+#define  NVIC_IABR_ACTIVE                    ((uint32_t)0xFFFFFFFF)        /*!< Interrupt active flags */
+#define  NVIC_IABR_ACTIVE_0                  ((uint32_t)0x00000001)        /*!< bit 0 */
+#define  NVIC_IABR_ACTIVE_1                  ((uint32_t)0x00000002)        /*!< bit 1 */
+#define  NVIC_IABR_ACTIVE_2                  ((uint32_t)0x00000004)        /*!< bit 2 */
+#define  NVIC_IABR_ACTIVE_3                  ((uint32_t)0x00000008)        /*!< bit 3 */
+#define  NVIC_IABR_ACTIVE_4                  ((uint32_t)0x00000010)        /*!< bit 4 */
+#define  NVIC_IABR_ACTIVE_5                  ((uint32_t)0x00000020)        /*!< bit 5 */
+#define  NVIC_IABR_ACTIVE_6                  ((uint32_t)0x00000040)        /*!< bit 6 */
+#define  NVIC_IABR_ACTIVE_7                  ((uint32_t)0x00000080)        /*!< bit 7 */
+#define  NVIC_IABR_ACTIVE_8                  ((uint32_t)0x00000100)        /*!< bit 8 */
+#define  NVIC_IABR_ACTIVE_9                  ((uint32_t)0x00000200)        /*!< bit 9 */
+#define  NVIC_IABR_ACTIVE_10                 ((uint32_t)0x00000400)        /*!< bit 10 */
+#define  NVIC_IABR_ACTIVE_11                 ((uint32_t)0x00000800)        /*!< bit 11 */
+#define  NVIC_IABR_ACTIVE_12                 ((uint32_t)0x00001000)        /*!< bit 12 */
+#define  NVIC_IABR_ACTIVE_13                 ((uint32_t)0x00002000)        /*!< bit 13 */
+#define  NVIC_IABR_ACTIVE_14                 ((uint32_t)0x00004000)        /*!< bit 14 */
+#define  NVIC_IABR_ACTIVE_15                 ((uint32_t)0x00008000)        /*!< bit 15 */
+#define  NVIC_IABR_ACTIVE_16                 ((uint32_t)0x00010000)        /*!< bit 16 */
+#define  NVIC_IABR_ACTIVE_17                 ((uint32_t)0x00020000)        /*!< bit 17 */
+#define  NVIC_IABR_ACTIVE_18                 ((uint32_t)0x00040000)        /*!< bit 18 */
+#define  NVIC_IABR_ACTIVE_19                 ((uint32_t)0x00080000)        /*!< bit 19 */
+#define  NVIC_IABR_ACTIVE_20                 ((uint32_t)0x00100000)        /*!< bit 20 */
+#define  NVIC_IABR_ACTIVE_21                 ((uint32_t)0x00200000)        /*!< bit 21 */
+#define  NVIC_IABR_ACTIVE_22                 ((uint32_t)0x00400000)        /*!< bit 22 */
+#define  NVIC_IABR_ACTIVE_23                 ((uint32_t)0x00800000)        /*!< bit 23 */
+#define  NVIC_IABR_ACTIVE_24                 ((uint32_t)0x01000000)        /*!< bit 24 */
+#define  NVIC_IABR_ACTIVE_25                 ((uint32_t)0x02000000)        /*!< bit 25 */
+#define  NVIC_IABR_ACTIVE_26                 ((uint32_t)0x04000000)        /*!< bit 26 */
+#define  NVIC_IABR_ACTIVE_27                 ((uint32_t)0x08000000)        /*!< bit 27 */
+#define  NVIC_IABR_ACTIVE_28                 ((uint32_t)0x10000000)        /*!< bit 28 */
+#define  NVIC_IABR_ACTIVE_29                 ((uint32_t)0x20000000)        /*!< bit 29 */
+#define  NVIC_IABR_ACTIVE_30                 ((uint32_t)0x40000000)        /*!< bit 30 */
+#define  NVIC_IABR_ACTIVE_31                 ((uint32_t)0x80000000)        /*!< bit 31 */
+
+/******************  Bit definition for NVIC_PRI0 register  *******************/
+#define  NVIC_IPR0_PRI_0                     ((uint32_t)0x000000FF)        /*!< Priority of interrupt 0 */
+#define  NVIC_IPR0_PRI_1                     ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 1 */
+#define  NVIC_IPR0_PRI_2                     ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 2 */
+#define  NVIC_IPR0_PRI_3                     ((uint32_t)0xFF000000)        /*!< Priority of interrupt 3 */
+
+/******************  Bit definition for NVIC_PRI1 register  *******************/
+#define  NVIC_IPR1_PRI_4                     ((uint32_t)0x000000FF)        /*!< Priority of interrupt 4 */
+#define  NVIC_IPR1_PRI_5                     ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 5 */
+#define  NVIC_IPR1_PRI_6                     ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 6 */
+#define  NVIC_IPR1_PRI_7                     ((uint32_t)0xFF000000)        /*!< Priority of interrupt 7 */
+
+/******************  Bit definition for NVIC_PRI2 register  *******************/
+#define  NVIC_IPR2_PRI_8                     ((uint32_t)0x000000FF)        /*!< Priority of interrupt 8 */
+#define  NVIC_IPR2_PRI_9                     ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 9 */
+#define  NVIC_IPR2_PRI_10                    ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 10 */
+#define  NVIC_IPR2_PRI_11                    ((uint32_t)0xFF000000)        /*!< Priority of interrupt 11 */
+
+/******************  Bit definition for NVIC_PRI3 register  *******************/
+#define  NVIC_IPR3_PRI_12                    ((uint32_t)0x000000FF)        /*!< Priority of interrupt 12 */
+#define  NVIC_IPR3_PRI_13                    ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 13 */
+#define  NVIC_IPR3_PRI_14                    ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 14 */
+#define  NVIC_IPR3_PRI_15                    ((uint32_t)0xFF000000)        /*!< Priority of interrupt 15 */
+
+/******************  Bit definition for NVIC_PRI4 register  *******************/
+#define  NVIC_IPR4_PRI_16                    ((uint32_t)0x000000FF)        /*!< Priority of interrupt 16 */
+#define  NVIC_IPR4_PRI_17                    ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 17 */
+#define  NVIC_IPR4_PRI_18                    ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 18 */
+#define  NVIC_IPR4_PRI_19                    ((uint32_t)0xFF000000)        /*!< Priority of interrupt 19 */
+
+/******************  Bit definition for NVIC_PRI5 register  *******************/
+#define  NVIC_IPR5_PRI_20                    ((uint32_t)0x000000FF)        /*!< Priority of interrupt 20 */
+#define  NVIC_IPR5_PRI_21                    ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 21 */
+#define  NVIC_IPR5_PRI_22                    ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 22 */
+#define  NVIC_IPR5_PRI_23                    ((uint32_t)0xFF000000)        /*!< Priority of interrupt 23 */
+
+/******************  Bit definition for NVIC_PRI6 register  *******************/
+#define  NVIC_IPR6_PRI_24                    ((uint32_t)0x000000FF)        /*!< Priority of interrupt 24 */
+#define  NVIC_IPR6_PRI_25                    ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 25 */
+#define  NVIC_IPR6_PRI_26                    ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 26 */
+#define  NVIC_IPR6_PRI_27                    ((uint32_t)0xFF000000)        /*!< Priority of interrupt 27 */
+
+/******************  Bit definition for NVIC_PRI7 register  *******************/
+#define  NVIC_IPR7_PRI_28                    ((uint32_t)0x000000FF)        /*!< Priority of interrupt 28 */
+#define  NVIC_IPR7_PRI_29                    ((uint32_t)0x0000FF00)        /*!< Priority of interrupt 29 */
+#define  NVIC_IPR7_PRI_30                    ((uint32_t)0x00FF0000)        /*!< Priority of interrupt 30 */
+#define  NVIC_IPR7_PRI_31                    ((uint32_t)0xFF000000)        /*!< Priority of interrupt 31 */
+
+/******************  Bit definition for SCB_CPUID register  *******************/
+#define  SCB_CPUID_REVISION                  ((uint32_t)0x0000000F)        /*!< Implementation defined revision number */
+#define  SCB_CPUID_PARTNO                    ((uint32_t)0x0000FFF0)        /*!< Number of processor within family */
+#define  SCB_CPUID_Constant                  ((uint32_t)0x000F0000)        /*!< Reads as 0x0F */
+#define  SCB_CPUID_VARIANT                   ((uint32_t)0x00F00000)        /*!< Implementation defined variant number */
+#define  SCB_CPUID_IMPLEMENTER               ((uint32_t)0xFF000000)        /*!< Implementer code. ARM is 0x41 */
+
+/*******************  Bit definition for SCB_ICSR register  *******************/
+#define  SCB_ICSR_VECTACTIVE                 ((uint32_t)0x000001FF)        /*!< Active ISR number field */
+#define  SCB_ICSR_RETTOBASE                  ((uint32_t)0x00000800)        /*!< All active exceptions minus the IPSR_current_exception yields the empty set */
+#define  SCB_ICSR_VECTPENDING                ((uint32_t)0x003FF000)        /*!< Pending ISR number field */
+#define  SCB_ICSR_ISRPENDING                 ((uint32_t)0x00400000)        /*!< Interrupt pending flag */
+#define  SCB_ICSR_ISRPREEMPT                 ((uint32_t)0x00800000)        /*!< It indicates that a pending interrupt becomes active in the next running cycle */
+#define  SCB_ICSR_PENDSTCLR                  ((uint32_t)0x02000000)        /*!< Clear pending SysTick bit */
+#define  SCB_ICSR_PENDSTSET                  ((uint32_t)0x04000000)        /*!< Set pending SysTick bit */
+#define  SCB_ICSR_PENDSVCLR                  ((uint32_t)0x08000000)        /*!< Clear pending pendSV bit */
+#define  SCB_ICSR_PENDSVSET                  ((uint32_t)0x10000000)        /*!< Set pending pendSV bit */
+#define  SCB_ICSR_NMIPENDSET                 ((uint32_t)0x80000000)        /*!< Set pending NMI bit */
+
+/*******************  Bit definition for SCB_VTOR register  *******************/
+#define  SCB_VTOR_TBLOFF                     ((uint32_t)0x1FFFFF80)        /*!< Vector table base offset field */
+#define  SCB_VTOR_TBLBASE                    ((uint32_t)0x20000000)        /*!< Table base in code(0) or RAM(1) */
+
+/*!<*****************  Bit definition for SCB_AIRCR register  *******************/
+#define  SCB_AIRCR_VECTRESET                 ((uint32_t)0x00000001)        /*!< System Reset bit */
+#define  SCB_AIRCR_VECTCLRACTIVE             ((uint32_t)0x00000002)        /*!< Clear active vector bit */
+#define  SCB_AIRCR_SYSRESETREQ               ((uint32_t)0x00000004)        /*!< Requests chip control logic to generate a reset */
+
+#define  SCB_AIRCR_PRIGROUP                  ((uint32_t)0x00000700)        /*!< PRIGROUP[2:0] bits (Priority group) */
+#define  SCB_AIRCR_PRIGROUP_0                ((uint32_t)0x00000100)        /*!< Bit 0 */
+#define  SCB_AIRCR_PRIGROUP_1                ((uint32_t)0x00000200)        /*!< Bit 1 */
+#define  SCB_AIRCR_PRIGROUP_2                ((uint32_t)0x00000400)        /*!< Bit 2  */
+
+/* prority group configuration */
+#define  SCB_AIRCR_PRIGROUP0                 ((uint32_t)0x00000000)        /*!< Priority group=0 (7 bits of pre-emption priority, 1 bit of subpriority) */
+#define  SCB_AIRCR_PRIGROUP1                 ((uint32_t)0x00000100)        /*!< Priority group=1 (6 bits of pre-emption priority, 2 bits of subpriority) */
+#define  SCB_AIRCR_PRIGROUP2                 ((uint32_t)0x00000200)        /*!< Priority group=2 (5 bits of pre-emption priority, 3 bits of subpriority) */
+#define  SCB_AIRCR_PRIGROUP3                 ((uint32_t)0x00000300)        /*!< Priority group=3 (4 bits of pre-emption priority, 4 bits of subpriority) */
+#define  SCB_AIRCR_PRIGROUP4                 ((uint32_t)0x00000400)        /*!< Priority group=4 (3 bits of pre-emption priority, 5 bits of subpriority) */
+#define  SCB_AIRCR_PRIGROUP5                 ((uint32_t)0x00000500)        /*!< Priority group=5 (2 bits of pre-emption priority, 6 bits of subpriority) */
+#define  SCB_AIRCR_PRIGROUP6                 ((uint32_t)0x00000600)        /*!< Priority group=6 (1 bit of pre-emption priority, 7 bits of subpriority) */
+#define  SCB_AIRCR_PRIGROUP7                 ((uint32_t)0x00000700)        /*!< Priority group=7 (no pre-emption priority, 8 bits of subpriority) */
+
+#define  SCB_AIRCR_ENDIANESS                 ((uint32_t)0x00008000)        /*!< Data endianness bit */
+#define  SCB_AIRCR_VECTKEY                   ((uint32_t)0xFFFF0000)        /*!< Register key (VECTKEY) - Reads as 0xFA05 (VECTKEYSTAT) */
+
+/*******************  Bit definition for SCB_SCR register  ********************/
+#define  SCB_SCR_SLEEPONEXIT                 ((uint8_t)0x02)               /*!< Sleep on exit bit */
+#define  SCB_SCR_SLEEPDEEP                   ((uint8_t)0x04)               /*!< Sleep deep bit */
+#define  SCB_SCR_SEVONPEND                   ((uint8_t)0x10)               /*!< Wake up from WFE */
+
+/********************  Bit definition for SCB_CCR register  *******************/
+#define  SCB_CCR_NONBASETHRDENA              ((uint16_t)0x0001)            /*!< Thread mode can be entered from any level in Handler mode by controlled return value */
+#define  SCB_CCR_USERSETMPEND                ((uint16_t)0x0002)            /*!< Enables user code to write the Software Trigger Interrupt register to trigger (pend) a Main exception */
+#define  SCB_CCR_UNALIGN_TRP                 ((uint16_t)0x0008)            /*!< Trap for unaligned access */
+#define  SCB_CCR_DIV_0_TRP                   ((uint16_t)0x0010)            /*!< Trap on Divide by 0 */
+#define  SCB_CCR_BFHFNMIGN                   ((uint16_t)0x0100)            /*!< Handlers running at priority -1 and -2 */
+#define  SCB_CCR_STKALIGN                    ((uint16_t)0x0200)            /*!< On exception entry, the SP used prior to the exception is adjusted to be 8-byte aligned */
+
+/*******************  Bit definition for SCB_SHPR register ********************/
+#define  SCB_SHPR_PRI_N                      ((uint32_t)0x000000FF)        /*!< Priority of system handler 4,8, and 12. Mem Manage, reserved and Debug Monitor */
+#define  SCB_SHPR_PRI_N1                     ((uint32_t)0x0000FF00)        /*!< Priority of system handler 5,9, and 13. Bus Fault, reserved and reserved */
+#define  SCB_SHPR_PRI_N2                     ((uint32_t)0x00FF0000)        /*!< Priority of system handler 6,10, and 14. Usage Fault, reserved and PendSV */
+#define  SCB_SHPR_PRI_N3                     ((uint32_t)0xFF000000)        /*!< Priority of system handler 7,11, and 15. Reserved, SVCall and SysTick */
+
+/******************  Bit definition for SCB_SHCSR register  *******************/
+#define  SCB_SHCSR_MEMFAULTACT               ((uint32_t)0x00000001)        /*!< MemManage is active */
+#define  SCB_SHCSR_BUSFAULTACT               ((uint32_t)0x00000002)        /*!< BusFault is active */
+#define  SCB_SHCSR_USGFAULTACT               ((uint32_t)0x00000008)        /*!< UsageFault is active */
+#define  SCB_SHCSR_SVCALLACT                 ((uint32_t)0x00000080)        /*!< SVCall is active */
+#define  SCB_SHCSR_MONITORACT                ((uint32_t)0x00000100)        /*!< Monitor is active */
+#define  SCB_SHCSR_PENDSVACT                 ((uint32_t)0x00000400)        /*!< PendSV is active */
+#define  SCB_SHCSR_SYSTICKACT                ((uint32_t)0x00000800)        /*!< SysTick is active */
+#define  SCB_SHCSR_USGFAULTPENDED            ((uint32_t)0x00001000)        /*!< Usage Fault is pended */
+#define  SCB_SHCSR_MEMFAULTPENDED            ((uint32_t)0x00002000)        /*!< MemManage is pended */
+#define  SCB_SHCSR_BUSFAULTPENDED            ((uint32_t)0x00004000)        /*!< Bus Fault is pended */
+#define  SCB_SHCSR_SVCALLPENDED              ((uint32_t)0x00008000)        /*!< SVCall is pended */
+#define  SCB_SHCSR_MEMFAULTENA               ((uint32_t)0x00010000)        /*!< MemManage enable */
+#define  SCB_SHCSR_BUSFAULTENA               ((uint32_t)0x00020000)        /*!< Bus Fault enable */
+#define  SCB_SHCSR_USGFAULTENA               ((uint32_t)0x00040000)        /*!< UsageFault enable */
+
+/*******************  Bit definition for SCB_CFSR register  *******************/
+/*!< MFSR */
+#define  SCB_CFSR_IACCVIOL                   ((uint32_t)0x00000001)        /*!< Instruction access violation */
+#define  SCB_CFSR_DACCVIOL                   ((uint32_t)0x00000002)        /*!< Data access violation */
+#define  SCB_CFSR_MUNSTKERR                  ((uint32_t)0x00000008)        /*!< Unstacking error */
+#define  SCB_CFSR_MSTKERR                    ((uint32_t)0x00000010)        /*!< Stacking error */
+#define  SCB_CFSR_MMARVALID                  ((uint32_t)0x00000080)        /*!< Memory Manage Address Register address valid flag */
+/*!< BFSR */
+#define  SCB_CFSR_IBUSERR                    ((uint32_t)0x00000100)        /*!< Instruction bus error flag */
+#define  SCB_CFSR_PRECISERR                  ((uint32_t)0x00000200)        /*!< Precise data bus error */
+#define  SCB_CFSR_IMPRECISERR                ((uint32_t)0x00000400)        /*!< Imprecise data bus error */
+#define  SCB_CFSR_UNSTKERR                   ((uint32_t)0x00000800)        /*!< Unstacking error */
+#define  SCB_CFSR_STKERR                     ((uint32_t)0x00001000)        /*!< Stacking error */
+#define  SCB_CFSR_BFARVALID                  ((uint32_t)0x00008000)        /*!< Bus Fault Address Register address valid flag */
+/*!< UFSR */
+#define  SCB_CFSR_UNDEFINSTR                 ((uint32_t)0x00010000)        /*!< The processor attempt to excecute an undefined instruction */
+#define  SCB_CFSR_INVSTATE                   ((uint32_t)0x00020000)        /*!< Invalid combination of EPSR and instruction */
+#define  SCB_CFSR_INVPC                      ((uint32_t)0x00040000)        /*!< Attempt to load EXC_RETURN into pc illegally */
+#define  SCB_CFSR_NOCP                       ((uint32_t)0x00080000)        /*!< Attempt to use a coprocessor instruction */
+#define  SCB_CFSR_UNALIGNED                  ((uint32_t)0x01000000)        /*!< Fault occurs when there is an attempt to make an unaligned memory access */
+#define  SCB_CFSR_DIVBYZERO                  ((uint32_t)0x02000000)        /*!< Fault occurs when SDIV or DIV instruction is used with a divisor of 0 */
+
+/*******************  Bit definition for SCB_HFSR register  *******************/
+#define  SCB_HFSR_VECTTBL                    ((uint32_t)0x00000002)        /*!< Fault occures because of vector table read on exception processing */
+#define  SCB_HFSR_FORCED                     ((uint32_t)0x40000000)        /*!< Hard Fault activated when a configurable Fault was received and cannot activate */
+#define  SCB_HFSR_DEBUGEVT                   ((uint32_t)0x80000000)        /*!< Fault related to debug */
+
+/*******************  Bit definition for SCB_DFSR register  *******************/
+#define  SCB_DFSR_HALTED                     ((uint8_t)0x01)               /*!< Halt request flag */
+#define  SCB_DFSR_BKPT                       ((uint8_t)0x02)               /*!< BKPT flag */
+#define  SCB_DFSR_DWTTRAP                    ((uint8_t)0x04)               /*!< Data Watchpoint and Trace (DWT) flag */
+#define  SCB_DFSR_VCATCH                     ((uint8_t)0x08)               /*!< Vector catch flag */
+#define  SCB_DFSR_EXTERNAL                   ((uint8_t)0x10)               /*!< External debug request flag */
+
+/*******************  Bit definition for SCB_MMFAR register  ******************/
+#define  SCB_MMFAR_ADDRESS                   ((uint32_t)0xFFFFFFFF)        /*!< Mem Manage fault address field */
+
+/*******************  Bit definition for SCB_BFAR register  *******************/
+#define  SCB_BFAR_ADDRESS                    ((uint32_t)0xFFFFFFFF)        /*!< Bus fault address field */
+
+/*******************  Bit definition for SCB_afsr register  *******************/
+#define  SCB_AFSR_IMPDEF                     ((uint32_t)0xFFFFFFFF)        /*!< Implementation defined */
+
+/******************************************************************************/
+/*                                                                            */
+/*                    External Interrupt/Event Controller                     */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for EXTI_IMR register  *******************/
+#define  EXTI_IMR_MR0                        ((uint32_t)0x00000001)        /*!< Interrupt Mask on line 0 */
+#define  EXTI_IMR_MR1                        ((uint32_t)0x00000002)        /*!< Interrupt Mask on line 1 */
+#define  EXTI_IMR_MR2                        ((uint32_t)0x00000004)        /*!< Interrupt Mask on line 2 */
+#define  EXTI_IMR_MR3                        ((uint32_t)0x00000008)        /*!< Interrupt Mask on line 3 */
+#define  EXTI_IMR_MR4                        ((uint32_t)0x00000010)        /*!< Interrupt Mask on line 4 */
+#define  EXTI_IMR_MR5                        ((uint32_t)0x00000020)        /*!< Interrupt Mask on line 5 */
+#define  EXTI_IMR_MR6                        ((uint32_t)0x00000040)        /*!< Interrupt Mask on line 6 */
+#define  EXTI_IMR_MR7                        ((uint32_t)0x00000080)        /*!< Interrupt Mask on line 7 */
+#define  EXTI_IMR_MR8                        ((uint32_t)0x00000100)        /*!< Interrupt Mask on line 8 */
+#define  EXTI_IMR_MR9                        ((uint32_t)0x00000200)        /*!< Interrupt Mask on line 9 */
+#define  EXTI_IMR_MR10                       ((uint32_t)0x00000400)        /*!< Interrupt Mask on line 10 */
+#define  EXTI_IMR_MR11                       ((uint32_t)0x00000800)        /*!< Interrupt Mask on line 11 */
+#define  EXTI_IMR_MR12                       ((uint32_t)0x00001000)        /*!< Interrupt Mask on line 12 */
+#define  EXTI_IMR_MR13                       ((uint32_t)0x00002000)        /*!< Interrupt Mask on line 13 */
+#define  EXTI_IMR_MR14                       ((uint32_t)0x00004000)        /*!< Interrupt Mask on line 14 */
+#define  EXTI_IMR_MR15                       ((uint32_t)0x00008000)        /*!< Interrupt Mask on line 15 */
+#define  EXTI_IMR_MR16                       ((uint32_t)0x00010000)        /*!< Interrupt Mask on line 16 */
+#define  EXTI_IMR_MR17                       ((uint32_t)0x00020000)        /*!< Interrupt Mask on line 17 */
+#define  EXTI_IMR_MR18                       ((uint32_t)0x00040000)        /*!< Interrupt Mask on line 18 */
+#define  EXTI_IMR_MR19                       ((uint32_t)0x00080000)        /*!< Interrupt Mask on line 19 */
+
+/*******************  Bit definition for EXTI_EMR register  *******************/
+#define  EXTI_EMR_MR0                        ((uint32_t)0x00000001)        /*!< Event Mask on line 0 */
+#define  EXTI_EMR_MR1                        ((uint32_t)0x00000002)        /*!< Event Mask on line 1 */
+#define  EXTI_EMR_MR2                        ((uint32_t)0x00000004)        /*!< Event Mask on line 2 */
+#define  EXTI_EMR_MR3                        ((uint32_t)0x00000008)        /*!< Event Mask on line 3 */
+#define  EXTI_EMR_MR4                        ((uint32_t)0x00000010)        /*!< Event Mask on line 4 */
+#define  EXTI_EMR_MR5                        ((uint32_t)0x00000020)        /*!< Event Mask on line 5 */
+#define  EXTI_EMR_MR6                        ((uint32_t)0x00000040)        /*!< Event Mask on line 6 */
+#define  EXTI_EMR_MR7                        ((uint32_t)0x00000080)        /*!< Event Mask on line 7 */
+#define  EXTI_EMR_MR8                        ((uint32_t)0x00000100)        /*!< Event Mask on line 8 */
+#define  EXTI_EMR_MR9                        ((uint32_t)0x00000200)        /*!< Event Mask on line 9 */
+#define  EXTI_EMR_MR10                       ((uint32_t)0x00000400)        /*!< Event Mask on line 10 */
+#define  EXTI_EMR_MR11                       ((uint32_t)0x00000800)        /*!< Event Mask on line 11 */
+#define  EXTI_EMR_MR12                       ((uint32_t)0x00001000)        /*!< Event Mask on line 12 */
+#define  EXTI_EMR_MR13                       ((uint32_t)0x00002000)        /*!< Event Mask on line 13 */
+#define  EXTI_EMR_MR14                       ((uint32_t)0x00004000)        /*!< Event Mask on line 14 */
+#define  EXTI_EMR_MR15                       ((uint32_t)0x00008000)        /*!< Event Mask on line 15 */
+#define  EXTI_EMR_MR16                       ((uint32_t)0x00010000)        /*!< Event Mask on line 16 */
+#define  EXTI_EMR_MR17                       ((uint32_t)0x00020000)        /*!< Event Mask on line 17 */
+#define  EXTI_EMR_MR18                       ((uint32_t)0x00040000)        /*!< Event Mask on line 18 */
+#define  EXTI_EMR_MR19                       ((uint32_t)0x00080000)        /*!< Event Mask on line 19 */
+
+/******************  Bit definition for EXTI_RTSR register  *******************/
+#define  EXTI_RTSR_TR0                       ((uint32_t)0x00000001)        /*!< Rising trigger event configuration bit of line 0 */
+#define  EXTI_RTSR_TR1                       ((uint32_t)0x00000002)        /*!< Rising trigger event configuration bit of line 1 */
+#define  EXTI_RTSR_TR2                       ((uint32_t)0x00000004)        /*!< Rising trigger event configuration bit of line 2 */
+#define  EXTI_RTSR_TR3                       ((uint32_t)0x00000008)        /*!< Rising trigger event configuration bit of line 3 */
+#define  EXTI_RTSR_TR4                       ((uint32_t)0x00000010)        /*!< Rising trigger event configuration bit of line 4 */
+#define  EXTI_RTSR_TR5                       ((uint32_t)0x00000020)        /*!< Rising trigger event configuration bit of line 5 */
+#define  EXTI_RTSR_TR6                       ((uint32_t)0x00000040)        /*!< Rising trigger event configuration bit of line 6 */
+#define  EXTI_RTSR_TR7                       ((uint32_t)0x00000080)        /*!< Rising trigger event configuration bit of line 7 */
+#define  EXTI_RTSR_TR8                       ((uint32_t)0x00000100)        /*!< Rising trigger event configuration bit of line 8 */
+#define  EXTI_RTSR_TR9                       ((uint32_t)0x00000200)        /*!< Rising trigger event configuration bit of line 9 */
+#define  EXTI_RTSR_TR10                      ((uint32_t)0x00000400)        /*!< Rising trigger event configuration bit of line 10 */
+#define  EXTI_RTSR_TR11                      ((uint32_t)0x00000800)        /*!< Rising trigger event configuration bit of line 11 */
+#define  EXTI_RTSR_TR12                      ((uint32_t)0x00001000)        /*!< Rising trigger event configuration bit of line 12 */
+#define  EXTI_RTSR_TR13                      ((uint32_t)0x00002000)        /*!< Rising trigger event configuration bit of line 13 */
+#define  EXTI_RTSR_TR14                      ((uint32_t)0x00004000)        /*!< Rising trigger event configuration bit of line 14 */
+#define  EXTI_RTSR_TR15                      ((uint32_t)0x00008000)        /*!< Rising trigger event configuration bit of line 15 */
+#define  EXTI_RTSR_TR16                      ((uint32_t)0x00010000)        /*!< Rising trigger event configuration bit of line 16 */
+#define  EXTI_RTSR_TR17                      ((uint32_t)0x00020000)        /*!< Rising trigger event configuration bit of line 17 */
+#define  EXTI_RTSR_TR18                      ((uint32_t)0x00040000)        /*!< Rising trigger event configuration bit of line 18 */
+#define  EXTI_RTSR_TR19                      ((uint32_t)0x00080000)        /*!< Rising trigger event configuration bit of line 19 */
+
+/******************  Bit definition for EXTI_FTSR register  *******************/
+#define  EXTI_FTSR_TR0                       ((uint32_t)0x00000001)        /*!< Falling trigger event configuration bit of line 0 */
+#define  EXTI_FTSR_TR1                       ((uint32_t)0x00000002)        /*!< Falling trigger event configuration bit of line 1 */
+#define  EXTI_FTSR_TR2                       ((uint32_t)0x00000004)        /*!< Falling trigger event configuration bit of line 2 */
+#define  EXTI_FTSR_TR3                       ((uint32_t)0x00000008)        /*!< Falling trigger event configuration bit of line 3 */
+#define  EXTI_FTSR_TR4                       ((uint32_t)0x00000010)        /*!< Falling trigger event configuration bit of line 4 */
+#define  EXTI_FTSR_TR5                       ((uint32_t)0x00000020)        /*!< Falling trigger event configuration bit of line 5 */
+#define  EXTI_FTSR_TR6                       ((uint32_t)0x00000040)        /*!< Falling trigger event configuration bit of line 6 */
+#define  EXTI_FTSR_TR7                       ((uint32_t)0x00000080)        /*!< Falling trigger event configuration bit of line 7 */
+#define  EXTI_FTSR_TR8                       ((uint32_t)0x00000100)        /*!< Falling trigger event configuration bit of line 8 */
+#define  EXTI_FTSR_TR9                       ((uint32_t)0x00000200)        /*!< Falling trigger event configuration bit of line 9 */
+#define  EXTI_FTSR_TR10                      ((uint32_t)0x00000400)        /*!< Falling trigger event configuration bit of line 10 */
+#define  EXTI_FTSR_TR11                      ((uint32_t)0x00000800)        /*!< Falling trigger event configuration bit of line 11 */
+#define  EXTI_FTSR_TR12                      ((uint32_t)0x00001000)        /*!< Falling trigger event configuration bit of line 12 */
+#define  EXTI_FTSR_TR13                      ((uint32_t)0x00002000)        /*!< Falling trigger event configuration bit of line 13 */
+#define  EXTI_FTSR_TR14                      ((uint32_t)0x00004000)        /*!< Falling trigger event configuration bit of line 14 */
+#define  EXTI_FTSR_TR15                      ((uint32_t)0x00008000)        /*!< Falling trigger event configuration bit of line 15 */
+#define  EXTI_FTSR_TR16                      ((uint32_t)0x00010000)        /*!< Falling trigger event configuration bit of line 16 */
+#define  EXTI_FTSR_TR17                      ((uint32_t)0x00020000)        /*!< Falling trigger event configuration bit of line 17 */
+#define  EXTI_FTSR_TR18                      ((uint32_t)0x00040000)        /*!< Falling trigger event configuration bit of line 18 */
+#define  EXTI_FTSR_TR19                      ((uint32_t)0x00080000)        /*!< Falling trigger event configuration bit of line 19 */
+
+/******************  Bit definition for EXTI_SWIER register  ******************/
+#define  EXTI_SWIER_SWIER0                   ((uint32_t)0x00000001)        /*!< Software Interrupt on line 0 */
+#define  EXTI_SWIER_SWIER1                   ((uint32_t)0x00000002)        /*!< Software Interrupt on line 1 */
+#define  EXTI_SWIER_SWIER2                   ((uint32_t)0x00000004)        /*!< Software Interrupt on line 2 */
+#define  EXTI_SWIER_SWIER3                   ((uint32_t)0x00000008)        /*!< Software Interrupt on line 3 */
+#define  EXTI_SWIER_SWIER4                   ((uint32_t)0x00000010)        /*!< Software Interrupt on line 4 */
+#define  EXTI_SWIER_SWIER5                   ((uint32_t)0x00000020)        /*!< Software Interrupt on line 5 */
+#define  EXTI_SWIER_SWIER6                   ((uint32_t)0x00000040)        /*!< Software Interrupt on line 6 */
+#define  EXTI_SWIER_SWIER7                   ((uint32_t)0x00000080)        /*!< Software Interrupt on line 7 */
+#define  EXTI_SWIER_SWIER8                   ((uint32_t)0x00000100)        /*!< Software Interrupt on line 8 */
+#define  EXTI_SWIER_SWIER9                   ((uint32_t)0x00000200)        /*!< Software Interrupt on line 9 */
+#define  EXTI_SWIER_SWIER10                  ((uint32_t)0x00000400)        /*!< Software Interrupt on line 10 */
+#define  EXTI_SWIER_SWIER11                  ((uint32_t)0x00000800)        /*!< Software Interrupt on line 11 */
+#define  EXTI_SWIER_SWIER12                  ((uint32_t)0x00001000)        /*!< Software Interrupt on line 12 */
+#define  EXTI_SWIER_SWIER13                  ((uint32_t)0x00002000)        /*!< Software Interrupt on line 13 */
+#define  EXTI_SWIER_SWIER14                  ((uint32_t)0x00004000)        /*!< Software Interrupt on line 14 */
+#define  EXTI_SWIER_SWIER15                  ((uint32_t)0x00008000)        /*!< Software Interrupt on line 15 */
+#define  EXTI_SWIER_SWIER16                  ((uint32_t)0x00010000)        /*!< Software Interrupt on line 16 */
+#define  EXTI_SWIER_SWIER17                  ((uint32_t)0x00020000)        /*!< Software Interrupt on line 17 */
+#define  EXTI_SWIER_SWIER18                  ((uint32_t)0x00040000)        /*!< Software Interrupt on line 18 */
+#define  EXTI_SWIER_SWIER19                  ((uint32_t)0x00080000)        /*!< Software Interrupt on line 19 */
+
+/*******************  Bit definition for EXTI_PR register  ********************/
+#define  EXTI_PR_PR0                         ((uint32_t)0x00000001)        /*!< Pending bit for line 0 */
+#define  EXTI_PR_PR1                         ((uint32_t)0x00000002)        /*!< Pending bit for line 1 */
+#define  EXTI_PR_PR2                         ((uint32_t)0x00000004)        /*!< Pending bit for line 2 */
+#define  EXTI_PR_PR3                         ((uint32_t)0x00000008)        /*!< Pending bit for line 3 */
+#define  EXTI_PR_PR4                         ((uint32_t)0x00000010)        /*!< Pending bit for line 4 */
+#define  EXTI_PR_PR5                         ((uint32_t)0x00000020)        /*!< Pending bit for line 5 */
+#define  EXTI_PR_PR6                         ((uint32_t)0x00000040)        /*!< Pending bit for line 6 */
+#define  EXTI_PR_PR7                         ((uint32_t)0x00000080)        /*!< Pending bit for line 7 */
+#define  EXTI_PR_PR8                         ((uint32_t)0x00000100)        /*!< Pending bit for line 8 */
+#define  EXTI_PR_PR9                         ((uint32_t)0x00000200)        /*!< Pending bit for line 9 */
+#define  EXTI_PR_PR10                        ((uint32_t)0x00000400)        /*!< Pending bit for line 10 */
+#define  EXTI_PR_PR11                        ((uint32_t)0x00000800)        /*!< Pending bit for line 11 */
+#define  EXTI_PR_PR12                        ((uint32_t)0x00001000)        /*!< Pending bit for line 12 */
+#define  EXTI_PR_PR13                        ((uint32_t)0x00002000)        /*!< Pending bit for line 13 */
+#define  EXTI_PR_PR14                        ((uint32_t)0x00004000)        /*!< Pending bit for line 14 */
+#define  EXTI_PR_PR15                        ((uint32_t)0x00008000)        /*!< Pending bit for line 15 */
+#define  EXTI_PR_PR16                        ((uint32_t)0x00010000)        /*!< Pending bit for line 16 */
+#define  EXTI_PR_PR17                        ((uint32_t)0x00020000)        /*!< Pending bit for line 17 */
+#define  EXTI_PR_PR18                        ((uint32_t)0x00040000)        /*!< Pending bit for line 18 */
+#define  EXTI_PR_PR19                        ((uint32_t)0x00080000)        /*!< Pending bit for line 19 */
+
+/******************************************************************************/
+/*                                                                            */
+/*                             DMA Controller                                 */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for DMA_ISR register  ********************/
+#define  DMA_ISR_GIF1                        ((uint32_t)0x00000001)        /*!< Channel 1 Global interrupt flag */
+#define  DMA_ISR_TCIF1                       ((uint32_t)0x00000002)        /*!< Channel 1 Transfer Complete flag */
+#define  DMA_ISR_HTIF1                       ((uint32_t)0x00000004)        /*!< Channel 1 Half Transfer flag */
+#define  DMA_ISR_TEIF1                       ((uint32_t)0x00000008)        /*!< Channel 1 Transfer Error flag */
+#define  DMA_ISR_GIF2                        ((uint32_t)0x00000010)        /*!< Channel 2 Global interrupt flag */
+#define  DMA_ISR_TCIF2                       ((uint32_t)0x00000020)        /*!< Channel 2 Transfer Complete flag */
+#define  DMA_ISR_HTIF2                       ((uint32_t)0x00000040)        /*!< Channel 2 Half Transfer flag */
+#define  DMA_ISR_TEIF2                       ((uint32_t)0x00000080)        /*!< Channel 2 Transfer Error flag */
+#define  DMA_ISR_GIF3                        ((uint32_t)0x00000100)        /*!< Channel 3 Global interrupt flag */
+#define  DMA_ISR_TCIF3                       ((uint32_t)0x00000200)        /*!< Channel 3 Transfer Complete flag */
+#define  DMA_ISR_HTIF3                       ((uint32_t)0x00000400)        /*!< Channel 3 Half Transfer flag */
+#define  DMA_ISR_TEIF3                       ((uint32_t)0x00000800)        /*!< Channel 3 Transfer Error flag */
+#define  DMA_ISR_GIF4                        ((uint32_t)0x00001000)        /*!< Channel 4 Global interrupt flag */
+#define  DMA_ISR_TCIF4                       ((uint32_t)0x00002000)        /*!< Channel 4 Transfer Complete flag */
+#define  DMA_ISR_HTIF4                       ((uint32_t)0x00004000)        /*!< Channel 4 Half Transfer flag */
+#define  DMA_ISR_TEIF4                       ((uint32_t)0x00008000)        /*!< Channel 4 Transfer Error flag */
+#define  DMA_ISR_GIF5                        ((uint32_t)0x00010000)        /*!< Channel 5 Global interrupt flag */
+#define  DMA_ISR_TCIF5                       ((uint32_t)0x00020000)        /*!< Channel 5 Transfer Complete flag */
+#define  DMA_ISR_HTIF5                       ((uint32_t)0x00040000)        /*!< Channel 5 Half Transfer flag */
+#define  DMA_ISR_TEIF5                       ((uint32_t)0x00080000)        /*!< Channel 5 Transfer Error flag */
+#define  DMA_ISR_GIF6                        ((uint32_t)0x00100000)        /*!< Channel 6 Global interrupt flag */
+#define  DMA_ISR_TCIF6                       ((uint32_t)0x00200000)        /*!< Channel 6 Transfer Complete flag */
+#define  DMA_ISR_HTIF6                       ((uint32_t)0x00400000)        /*!< Channel 6 Half Transfer flag */
+#define  DMA_ISR_TEIF6                       ((uint32_t)0x00800000)        /*!< Channel 6 Transfer Error flag */
+#define  DMA_ISR_GIF7                        ((uint32_t)0x01000000)        /*!< Channel 7 Global interrupt flag */
+#define  DMA_ISR_TCIF7                       ((uint32_t)0x02000000)        /*!< Channel 7 Transfer Complete flag */
+#define  DMA_ISR_HTIF7                       ((uint32_t)0x04000000)        /*!< Channel 7 Half Transfer flag */
+#define  DMA_ISR_TEIF7                       ((uint32_t)0x08000000)        /*!< Channel 7 Transfer Error flag */
+
+/*******************  Bit definition for DMA_IFCR register  *******************/
+#define  DMA_IFCR_CGIF1                      ((uint32_t)0x00000001)        /*!< Channel 1 Global interrupt clearr */
+#define  DMA_IFCR_CTCIF1                     ((uint32_t)0x00000002)        /*!< Channel 1 Transfer Complete clear */
+#define  DMA_IFCR_CHTIF1                     ((uint32_t)0x00000004)        /*!< Channel 1 Half Transfer clear */
+#define  DMA_IFCR_CTEIF1                     ((uint32_t)0x00000008)        /*!< Channel 1 Transfer Error clear */
+#define  DMA_IFCR_CGIF2                      ((uint32_t)0x00000010)        /*!< Channel 2 Global interrupt clear */
+#define  DMA_IFCR_CTCIF2                     ((uint32_t)0x00000020)        /*!< Channel 2 Transfer Complete clear */
+#define  DMA_IFCR_CHTIF2                     ((uint32_t)0x00000040)        /*!< Channel 2 Half Transfer clear */
+#define  DMA_IFCR_CTEIF2                     ((uint32_t)0x00000080)        /*!< Channel 2 Transfer Error clear */
+#define  DMA_IFCR_CGIF3                      ((uint32_t)0x00000100)        /*!< Channel 3 Global interrupt clear */
+#define  DMA_IFCR_CTCIF3                     ((uint32_t)0x00000200)        /*!< Channel 3 Transfer Complete clear */
+#define  DMA_IFCR_CHTIF3                     ((uint32_t)0x00000400)        /*!< Channel 3 Half Transfer clear */
+#define  DMA_IFCR_CTEIF3                     ((uint32_t)0x00000800)        /*!< Channel 3 Transfer Error clear */
+#define  DMA_IFCR_CGIF4                      ((uint32_t)0x00001000)        /*!< Channel 4 Global interrupt clear */
+#define  DMA_IFCR_CTCIF4                     ((uint32_t)0x00002000)        /*!< Channel 4 Transfer Complete clear */
+#define  DMA_IFCR_CHTIF4                     ((uint32_t)0x00004000)        /*!< Channel 4 Half Transfer clear */
+#define  DMA_IFCR_CTEIF4                     ((uint32_t)0x00008000)        /*!< Channel 4 Transfer Error clear */
+#define  DMA_IFCR_CGIF5                      ((uint32_t)0x00010000)        /*!< Channel 5 Global interrupt clear */
+#define  DMA_IFCR_CTCIF5                     ((uint32_t)0x00020000)        /*!< Channel 5 Transfer Complete clear */
+#define  DMA_IFCR_CHTIF5                     ((uint32_t)0x00040000)        /*!< Channel 5 Half Transfer clear */
+#define  DMA_IFCR_CTEIF5                     ((uint32_t)0x00080000)        /*!< Channel 5 Transfer Error clear */
+#define  DMA_IFCR_CGIF6                      ((uint32_t)0x00100000)        /*!< Channel 6 Global interrupt clear */
+#define  DMA_IFCR_CTCIF6                     ((uint32_t)0x00200000)        /*!< Channel 6 Transfer Complete clear */
+#define  DMA_IFCR_CHTIF6                     ((uint32_t)0x00400000)        /*!< Channel 6 Half Transfer clear */
+#define  DMA_IFCR_CTEIF6                     ((uint32_t)0x00800000)        /*!< Channel 6 Transfer Error clear */
+#define  DMA_IFCR_CGIF7                      ((uint32_t)0x01000000)        /*!< Channel 7 Global interrupt clear */
+#define  DMA_IFCR_CTCIF7                     ((uint32_t)0x02000000)        /*!< Channel 7 Transfer Complete clear */
+#define  DMA_IFCR_CHTIF7                     ((uint32_t)0x04000000)        /*!< Channel 7 Half Transfer clear */
+#define  DMA_IFCR_CTEIF7                     ((uint32_t)0x08000000)        /*!< Channel 7 Transfer Error clear */
+
+/*******************  Bit definition for DMA_CCR1 register  *******************/
+#define  DMA_CCR1_EN                         ((uint16_t)0x0001)            /*!< Channel enable*/
+#define  DMA_CCR1_TCIE                       ((uint16_t)0x0002)            /*!< Transfer complete interrupt enable */
+#define  DMA_CCR1_HTIE                       ((uint16_t)0x0004)            /*!< Half Transfer interrupt enable */
+#define  DMA_CCR1_TEIE                       ((uint16_t)0x0008)            /*!< Transfer error interrupt enable */
+#define  DMA_CCR1_DIR                        ((uint16_t)0x0010)            /*!< Data transfer direction */
+#define  DMA_CCR1_CIRC                       ((uint16_t)0x0020)            /*!< Circular mode */
+#define  DMA_CCR1_PINC                       ((uint16_t)0x0040)            /*!< Peripheral increment mode */
+#define  DMA_CCR1_MINC                       ((uint16_t)0x0080)            /*!< Memory increment mode */
+
+#define  DMA_CCR1_PSIZE                      ((uint16_t)0x0300)            /*!< PSIZE[1:0] bits (Peripheral size) */
+#define  DMA_CCR1_PSIZE_0                    ((uint16_t)0x0100)            /*!< Bit 0 */
+#define  DMA_CCR1_PSIZE_1                    ((uint16_t)0x0200)            /*!< Bit 1 */
+
+#define  DMA_CCR1_MSIZE                      ((uint16_t)0x0C00)            /*!< MSIZE[1:0] bits (Memory size) */
+#define  DMA_CCR1_MSIZE_0                    ((uint16_t)0x0400)            /*!< Bit 0 */
+#define  DMA_CCR1_MSIZE_1                    ((uint16_t)0x0800)            /*!< Bit 1 */
+
+#define  DMA_CCR1_PL                         ((uint16_t)0x3000)            /*!< PL[1:0] bits(Channel Priority level) */
+#define  DMA_CCR1_PL_0                       ((uint16_t)0x1000)            /*!< Bit 0 */
+#define  DMA_CCR1_PL_1                       ((uint16_t)0x2000)            /*!< Bit 1 */
+
+#define  DMA_CCR1_MEM2MEM                    ((uint16_t)0x4000)            /*!< Memory to memory mode */
+
+/*******************  Bit definition for DMA_CCR2 register  *******************/
+#define  DMA_CCR2_EN                         ((uint16_t)0x0001)            /*!< Channel enable */
+#define  DMA_CCR2_TCIE                       ((uint16_t)0x0002)            /*!< ransfer complete interrupt enable */
+#define  DMA_CCR2_HTIE                       ((uint16_t)0x0004)            /*!< Half Transfer interrupt enable */
+#define  DMA_CCR2_TEIE                       ((uint16_t)0x0008)            /*!< Transfer error interrupt enable */
+#define  DMA_CCR2_DIR                        ((uint16_t)0x0010)            /*!< Data transfer direction */
+#define  DMA_CCR2_CIRC                       ((uint16_t)0x0020)            /*!< Circular mode */
+#define  DMA_CCR2_PINC                       ((uint16_t)0x0040)            /*!< Peripheral increment mode */
+#define  DMA_CCR2_MINC                       ((uint16_t)0x0080)            /*!< Memory increment mode */
+
+#define  DMA_CCR2_PSIZE                      ((uint16_t)0x0300)            /*!< PSIZE[1:0] bits (Peripheral size) */
+#define  DMA_CCR2_PSIZE_0                    ((uint16_t)0x0100)            /*!< Bit 0 */
+#define  DMA_CCR2_PSIZE_1                    ((uint16_t)0x0200)            /*!< Bit 1 */
+
+#define  DMA_CCR2_MSIZE                      ((uint16_t)0x0C00)            /*!< MSIZE[1:0] bits (Memory size) */
+#define  DMA_CCR2_MSIZE_0                    ((uint16_t)0x0400)            /*!< Bit 0 */
+#define  DMA_CCR2_MSIZE_1                    ((uint16_t)0x0800)            /*!< Bit 1 */
+
+#define  DMA_CCR2_PL                         ((uint16_t)0x3000)            /*!< PL[1:0] bits (Channel Priority level) */
+#define  DMA_CCR2_PL_0                       ((uint16_t)0x1000)            /*!< Bit 0 */
+#define  DMA_CCR2_PL_1                       ((uint16_t)0x2000)            /*!< Bit 1 */
+
+#define  DMA_CCR2_MEM2MEM                    ((uint16_t)0x4000)            /*!< Memory to memory mode */
+
+/*******************  Bit definition for DMA_CCR3 register  *******************/
+#define  DMA_CCR3_EN                         ((uint16_t)0x0001)            /*!< Channel enable */
+#define  DMA_CCR3_TCIE                       ((uint16_t)0x0002)            /*!< Transfer complete interrupt enable */
+#define  DMA_CCR3_HTIE                       ((uint16_t)0x0004)            /*!< Half Transfer interrupt enable */
+#define  DMA_CCR3_TEIE                       ((uint16_t)0x0008)            /*!< Transfer error interrupt enable */
+#define  DMA_CCR3_DIR                        ((uint16_t)0x0010)            /*!< Data transfer direction */
+#define  DMA_CCR3_CIRC                       ((uint16_t)0x0020)            /*!< Circular mode */
+#define  DMA_CCR3_PINC                       ((uint16_t)0x0040)            /*!< Peripheral increment mode */
+#define  DMA_CCR3_MINC                       ((uint16_t)0x0080)            /*!< Memory increment mode */
+
+#define  DMA_CCR3_PSIZE                      ((uint16_t)0x0300)            /*!< PSIZE[1:0] bits (Peripheral size) */
+#define  DMA_CCR3_PSIZE_0                    ((uint16_t)0x0100)            /*!< Bit 0 */
+#define  DMA_CCR3_PSIZE_1                    ((uint16_t)0x0200)            /*!< Bit 1 */
+
+#define  DMA_CCR3_MSIZE                      ((uint16_t)0x0C00)            /*!< MSIZE[1:0] bits (Memory size) */
+#define  DMA_CCR3_MSIZE_0                    ((uint16_t)0x0400)            /*!< Bit 0 */
+#define  DMA_CCR3_MSIZE_1                    ((uint16_t)0x0800)            /*!< Bit 1 */
+
+#define  DMA_CCR3_PL                         ((uint16_t)0x3000)            /*!< PL[1:0] bits (Channel Priority level) */
+#define  DMA_CCR3_PL_0                       ((uint16_t)0x1000)            /*!< Bit 0 */
+#define  DMA_CCR3_PL_1                       ((uint16_t)0x2000)            /*!< Bit 1 */
+
+#define  DMA_CCR3_MEM2MEM                    ((uint16_t)0x4000)            /*!< Memory to memory mode */
+
+/*!<******************  Bit definition for DMA_CCR4 register  *******************/
+#define  DMA_CCR4_EN                         ((uint16_t)0x0001)            /*!<Channel enable */
+#define  DMA_CCR4_TCIE                       ((uint16_t)0x0002)            /*!<Transfer complete interrupt enable */
+#define  DMA_CCR4_HTIE                       ((uint16_t)0x0004)            /*!<Half Transfer interrupt enable */
+#define  DMA_CCR4_TEIE                       ((uint16_t)0x0008)            /*!<Transfer error interrupt enable */
+#define  DMA_CCR4_DIR                        ((uint16_t)0x0010)            /*!<Data transfer direction */
+#define  DMA_CCR4_CIRC                       ((uint16_t)0x0020)            /*!<Circular mode */
+#define  DMA_CCR4_PINC                       ((uint16_t)0x0040)            /*!<Peripheral increment mode */
+#define  DMA_CCR4_MINC                       ((uint16_t)0x0080)            /*!<Memory increment mode */
+
+#define  DMA_CCR4_PSIZE                      ((uint16_t)0x0300)            /*!<PSIZE[1:0] bits (Peripheral size) */
+#define  DMA_CCR4_PSIZE_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  DMA_CCR4_PSIZE_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  DMA_CCR4_MSIZE                      ((uint16_t)0x0C00)            /*!<MSIZE[1:0] bits (Memory size) */
+#define  DMA_CCR4_MSIZE_0                    ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  DMA_CCR4_MSIZE_1                    ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  DMA_CCR4_PL                         ((uint16_t)0x3000)            /*!<PL[1:0] bits (Channel Priority level) */
+#define  DMA_CCR4_PL_0                       ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  DMA_CCR4_PL_1                       ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  DMA_CCR4_MEM2MEM                    ((uint16_t)0x4000)            /*!<Memory to memory mode */
+
+/******************  Bit definition for DMA_CCR5 register  *******************/
+#define  DMA_CCR5_EN                         ((uint16_t)0x0001)            /*!<Channel enable */
+#define  DMA_CCR5_TCIE                       ((uint16_t)0x0002)            /*!<Transfer complete interrupt enable */
+#define  DMA_CCR5_HTIE                       ((uint16_t)0x0004)            /*!<Half Transfer interrupt enable */
+#define  DMA_CCR5_TEIE                       ((uint16_t)0x0008)            /*!<Transfer error interrupt enable */
+#define  DMA_CCR5_DIR                        ((uint16_t)0x0010)            /*!<Data transfer direction */
+#define  DMA_CCR5_CIRC                       ((uint16_t)0x0020)            /*!<Circular mode */
+#define  DMA_CCR5_PINC                       ((uint16_t)0x0040)            /*!<Peripheral increment mode */
+#define  DMA_CCR5_MINC                       ((uint16_t)0x0080)            /*!<Memory increment mode */
+
+#define  DMA_CCR5_PSIZE                      ((uint16_t)0x0300)            /*!<PSIZE[1:0] bits (Peripheral size) */
+#define  DMA_CCR5_PSIZE_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  DMA_CCR5_PSIZE_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  DMA_CCR5_MSIZE                      ((uint16_t)0x0C00)            /*!<MSIZE[1:0] bits (Memory size) */
+#define  DMA_CCR5_MSIZE_0                    ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  DMA_CCR5_MSIZE_1                    ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  DMA_CCR5_PL                         ((uint16_t)0x3000)            /*!<PL[1:0] bits (Channel Priority level) */
+#define  DMA_CCR5_PL_0                       ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  DMA_CCR5_PL_1                       ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  DMA_CCR5_MEM2MEM                    ((uint16_t)0x4000)            /*!<Memory to memory mode enable */
+
+/*******************  Bit definition for DMA_CCR6 register  *******************/
+#define  DMA_CCR6_EN                         ((uint16_t)0x0001)            /*!<Channel enable */
+#define  DMA_CCR6_TCIE                       ((uint16_t)0x0002)            /*!<Transfer complete interrupt enable */
+#define  DMA_CCR6_HTIE                       ((uint16_t)0x0004)            /*!<Half Transfer interrupt enable */
+#define  DMA_CCR6_TEIE                       ((uint16_t)0x0008)            /*!<Transfer error interrupt enable */
+#define  DMA_CCR6_DIR                        ((uint16_t)0x0010)            /*!<Data transfer direction */
+#define  DMA_CCR6_CIRC                       ((uint16_t)0x0020)            /*!<Circular mode */
+#define  DMA_CCR6_PINC                       ((uint16_t)0x0040)            /*!<Peripheral increment mode */
+#define  DMA_CCR6_MINC                       ((uint16_t)0x0080)            /*!<Memory increment mode */
+
+#define  DMA_CCR6_PSIZE                      ((uint16_t)0x0300)            /*!<PSIZE[1:0] bits (Peripheral size) */
+#define  DMA_CCR6_PSIZE_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  DMA_CCR6_PSIZE_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  DMA_CCR6_MSIZE                      ((uint16_t)0x0C00)            /*!<MSIZE[1:0] bits (Memory size) */
+#define  DMA_CCR6_MSIZE_0                    ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  DMA_CCR6_MSIZE_1                    ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  DMA_CCR6_PL                         ((uint16_t)0x3000)            /*!<PL[1:0] bits (Channel Priority level) */
+#define  DMA_CCR6_PL_0                       ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  DMA_CCR6_PL_1                       ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  DMA_CCR6_MEM2MEM                    ((uint16_t)0x4000)            /*!<Memory to memory mode */
+
+/*******************  Bit definition for DMA_CCR7 register  *******************/
+#define  DMA_CCR7_EN                         ((uint16_t)0x0001)            /*!<Channel enable */
+#define  DMA_CCR7_TCIE                       ((uint16_t)0x0002)            /*!<Transfer complete interrupt enable */
+#define  DMA_CCR7_HTIE                       ((uint16_t)0x0004)            /*!<Half Transfer interrupt enable */
+#define  DMA_CCR7_TEIE                       ((uint16_t)0x0008)            /*!<Transfer error interrupt enable */
+#define  DMA_CCR7_DIR                        ((uint16_t)0x0010)            /*!<Data transfer direction */
+#define  DMA_CCR7_CIRC                       ((uint16_t)0x0020)            /*!<Circular mode */
+#define  DMA_CCR7_PINC                       ((uint16_t)0x0040)            /*!<Peripheral increment mode */
+#define  DMA_CCR7_MINC                       ((uint16_t)0x0080)            /*!<Memory increment mode */
+
+#define  DMA_CCR7_PSIZE            ,         ((uint16_t)0x0300)            /*!<PSIZE[1:0] bits (Peripheral size) */
+#define  DMA_CCR7_PSIZE_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  DMA_CCR7_PSIZE_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  DMA_CCR7_MSIZE                      ((uint16_t)0x0C00)            /*!<MSIZE[1:0] bits (Memory size) */
+#define  DMA_CCR7_MSIZE_0                    ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  DMA_CCR7_MSIZE_1                    ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  DMA_CCR7_PL                         ((uint16_t)0x3000)            /*!<PL[1:0] bits (Channel Priority level) */
+#define  DMA_CCR7_PL_0                       ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  DMA_CCR7_PL_1                       ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  DMA_CCR7_MEM2MEM                    ((uint16_t)0x4000)            /*!<Memory to memory mode enable */
+
+/******************  Bit definition for DMA_CNDTR1 register  ******************/
+#define  DMA_CNDTR1_NDT                      ((uint16_t)0xFFFF)            /*!<Number of data to Transfer */
+
+/******************  Bit definition for DMA_CNDTR2 register  ******************/
+#define  DMA_CNDTR2_NDT                      ((uint16_t)0xFFFF)            /*!<Number of data to Transfer */
+
+/******************  Bit definition for DMA_CNDTR3 register  ******************/
+#define  DMA_CNDTR3_NDT                      ((uint16_t)0xFFFF)            /*!<Number of data to Transfer */
+
+/******************  Bit definition for DMA_CNDTR4 register  ******************/
+#define  DMA_CNDTR4_NDT                      ((uint16_t)0xFFFF)            /*!<Number of data to Transfer */
+
+/******************  Bit definition for DMA_CNDTR5 register  ******************/
+#define  DMA_CNDTR5_NDT                      ((uint16_t)0xFFFF)            /*!<Number of data to Transfer */
+
+/******************  Bit definition for DMA_CNDTR6 register  ******************/
+#define  DMA_CNDTR6_NDT                      ((uint16_t)0xFFFF)            /*!<Number of data to Transfer */
+
+/******************  Bit definition for DMA_CNDTR7 register  ******************/
+#define  DMA_CNDTR7_NDT                      ((uint16_t)0xFFFF)            /*!<Number of data to Transfer */
+
+/******************  Bit definition for DMA_CPAR1 register  *******************/
+#define  DMA_CPAR1_PA                        ((uint32_t)0xFFFFFFFF)        /*!<Peripheral Address */
+
+/******************  Bit definition for DMA_CPAR2 register  *******************/
+#define  DMA_CPAR2_PA                        ((uint32_t)0xFFFFFFFF)        /*!<Peripheral Address */
+
+/******************  Bit definition for DMA_CPAR3 register  *******************/
+#define  DMA_CPAR3_PA                        ((uint32_t)0xFFFFFFFF)        /*!<Peripheral Address */
+
+
+/******************  Bit definition for DMA_CPAR4 register  *******************/
+#define  DMA_CPAR4_PA                        ((uint32_t)0xFFFFFFFF)        /*!<Peripheral Address */
+
+/******************  Bit definition for DMA_CPAR5 register  *******************/
+#define  DMA_CPAR5_PA                        ((uint32_t)0xFFFFFFFF)        /*!<Peripheral Address */
+
+/******************  Bit definition for DMA_CPAR6 register  *******************/
+#define  DMA_CPAR6_PA                        ((uint32_t)0xFFFFFFFF)        /*!<Peripheral Address */
+
+
+/******************  Bit definition for DMA_CPAR7 register  *******************/
+#define  DMA_CPAR7_PA                        ((uint32_t)0xFFFFFFFF)        /*!<Peripheral Address */
+
+/******************  Bit definition for DMA_CMAR1 register  *******************/
+#define  DMA_CMAR1_MA                        ((uint32_t)0xFFFFFFFF)        /*!<Memory Address */
+
+/******************  Bit definition for DMA_CMAR2 register  *******************/
+#define  DMA_CMAR2_MA                        ((uint32_t)0xFFFFFFFF)        /*!<Memory Address */
+
+/******************  Bit definition for DMA_CMAR3 register  *******************/
+#define  DMA_CMAR3_MA                        ((uint32_t)0xFFFFFFFF)        /*!<Memory Address */
+
+
+/******************  Bit definition for DMA_CMAR4 register  *******************/
+#define  DMA_CMAR4_MA                        ((uint32_t)0xFFFFFFFF)        /*!<Memory Address */
+
+/******************  Bit definition for DMA_CMAR5 register  *******************/
+#define  DMA_CMAR5_MA                        ((uint32_t)0xFFFFFFFF)        /*!<Memory Address */
+
+/******************  Bit definition for DMA_CMAR6 register  *******************/
+#define  DMA_CMAR6_MA                        ((uint32_t)0xFFFFFFFF)        /*!<Memory Address */
+
+/******************  Bit definition for DMA_CMAR7 register  *******************/
+#define  DMA_CMAR7_MA                        ((uint32_t)0xFFFFFFFF)        /*!<Memory Address */
+
+/******************************************************************************/
+/*                                                                            */
+/*                        Analog to Digital Converter                         */
+/*                                                                            */
+/******************************************************************************/
+
+/********************  Bit definition for ADC_SR register  ********************/
+#define  ADC_SR_AWD                          ((uint8_t)0x01)               /*!<Analog watchdog flag */
+#define  ADC_SR_EOC                          ((uint8_t)0x02)               /*!<End of conversion */
+#define  ADC_SR_JEOC                         ((uint8_t)0x04)               /*!<Injected channel end of conversion */
+#define  ADC_SR_JSTRT                        ((uint8_t)0x08)               /*!<Injected channel Start flag */
+#define  ADC_SR_STRT                         ((uint8_t)0x10)               /*!<Regular channel Start flag */
+
+/*******************  Bit definition for ADC_CR1 register  ********************/
+#define  ADC_CR1_AWDCH                       ((uint32_t)0x0000001F)        /*!<AWDCH[4:0] bits (Analog watchdog channel select bits) */
+#define  ADC_CR1_AWDCH_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_CR1_AWDCH_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_CR1_AWDCH_2                     ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_CR1_AWDCH_3                     ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_CR1_AWDCH_4                     ((uint32_t)0x00000010)        /*!<Bit 4 */
+
+#define  ADC_CR1_EOCIE                       ((uint32_t)0x00000020)        /*!<Interrupt enable for EOC */
+#define  ADC_CR1_AWDIE                       ((uint32_t)0x00000040)        /*!<AAnalog Watchdog interrupt enable */
+#define  ADC_CR1_JEOCIE                      ((uint32_t)0x00000080)        /*!<Interrupt enable for injected channels */
+#define  ADC_CR1_SCAN                        ((uint32_t)0x00000100)        /*!<Scan mode */
+#define  ADC_CR1_AWDSGL                      ((uint32_t)0x00000200)        /*!<Enable the watchdog on a single channel in scan mode */
+#define  ADC_CR1_JAUTO                       ((uint32_t)0x00000400)        /*!<Automatic injected group conversion */
+#define  ADC_CR1_DISCEN                      ((uint32_t)0x00000800)        /*!<Discontinuous mode on regular channels */
+#define  ADC_CR1_JDISCEN                     ((uint32_t)0x00001000)        /*!<Discontinuous mode on injected channels */
+
+#define  ADC_CR1_DISCNUM                     ((uint32_t)0x0000E000)        /*!<DISCNUM[2:0] bits (Discontinuous mode channel count) */
+#define  ADC_CR1_DISCNUM_0                   ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  ADC_CR1_DISCNUM_1                   ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  ADC_CR1_DISCNUM_2                   ((uint32_t)0x00008000)        /*!<Bit 2 */
+
+#define  ADC_CR1_DUALMOD                     ((uint32_t)0x000F0000)        /*!<DUALMOD[3:0] bits (Dual mode selection) */
+#define  ADC_CR1_DUALMOD_0                   ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  ADC_CR1_DUALMOD_1                   ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  ADC_CR1_DUALMOD_2                   ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  ADC_CR1_DUALMOD_3                   ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  ADC_CR1_JAWDEN                      ((uint32_t)0x00400000)        /*!<Analog watchdog enable on injected channels */
+#define  ADC_CR1_AWDEN                       ((uint32_t)0x00800000)        /*!<Analog watchdog enable on regular channels */
+
+  
+/*******************  Bit definition for ADC_CR2 register  ********************/
+#define  ADC_CR2_ADON                        ((uint32_t)0x00000001)        /*!<A/D Converter ON / OFF */
+#define  ADC_CR2_CONT                        ((uint32_t)0x00000002)        /*!<Continuous Conversion */
+#define  ADC_CR2_CAL                         ((uint32_t)0x00000004)        /*!<A/D Calibration */
+#define  ADC_CR2_RSTCAL                      ((uint32_t)0x00000008)        /*!<Reset Calibration */
+#define  ADC_CR2_DMA                         ((uint32_t)0x00000100)        /*!<Direct Memory access mode */
+#define  ADC_CR2_ALIGN                       ((uint32_t)0x00000800)        /*!<Data Alignment */
+
+#define  ADC_CR2_JEXTSEL                     ((uint32_t)0x00007000)        /*!<JEXTSEL[2:0] bits (External event select for injected group) */
+#define  ADC_CR2_JEXTSEL_0                   ((uint32_t)0x00001000)        /*!<Bit 0 */
+#define  ADC_CR2_JEXTSEL_1                   ((uint32_t)0x00002000)        /*!<Bit 1 */
+#define  ADC_CR2_JEXTSEL_2                   ((uint32_t)0x00004000)        /*!<Bit 2 */
+
+#define  ADC_CR2_JEXTTRIG                    ((uint32_t)0x00008000)        /*!<External Trigger Conversion mode for injected channels */
+
+#define  ADC_CR2_EXTSEL                      ((uint32_t)0x000E0000)        /*!<EXTSEL[2:0] bits (External Event Select for regular group) */
+#define  ADC_CR2_EXTSEL_0                    ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  ADC_CR2_EXTSEL_1                    ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  ADC_CR2_EXTSEL_2                    ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+#define  ADC_CR2_EXTTRIG                     ((uint32_t)0x00100000)        /*!<External Trigger Conversion mode for regular channels */
+#define  ADC_CR2_JSWSTART                    ((uint32_t)0x00200000)        /*!<Start Conversion of injected channels */
+#define  ADC_CR2_SWSTART                     ((uint32_t)0x00400000)        /*!<Start Conversion of regular channels */
+#define  ADC_CR2_TSVREFE                     ((uint32_t)0x00800000)        /*!<Temperature Sensor and VREFINT Enable */
+
+/******************  Bit definition for ADC_SMPR1 register  *******************/
+#define  ADC_SMPR1_SMP10                     ((uint32_t)0x00000007)        /*!<SMP10[2:0] bits (Channel 10 Sample time selection) */
+#define  ADC_SMPR1_SMP10_0                   ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP10_1                   ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP10_2                   ((uint32_t)0x00000004)        /*!<Bit 2 */
+
+#define  ADC_SMPR1_SMP11                     ((uint32_t)0x00000038)        /*!<SMP11[2:0] bits (Channel 11 Sample time selection) */
+#define  ADC_SMPR1_SMP11_0                   ((uint32_t)0x00000008)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP11_1                   ((uint32_t)0x00000010)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP11_2                   ((uint32_t)0x00000020)        /*!<Bit 2 */
+
+#define  ADC_SMPR1_SMP12                     ((uint32_t)0x000001C0)        /*!<SMP12[2:0] bits (Channel 12 Sample time selection) */
+#define  ADC_SMPR1_SMP12_0                   ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP12_1                   ((uint32_t)0x00000080)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP12_2                   ((uint32_t)0x00000100)        /*!<Bit 2 */
+
+#define  ADC_SMPR1_SMP13                     ((uint32_t)0x00000E00)        /*!<SMP13[2:0] bits (Channel 13 Sample time selection) */
+#define  ADC_SMPR1_SMP13_0                   ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP13_1                   ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP13_2                   ((uint32_t)0x00000800)        /*!<Bit 2 */
+
+#define  ADC_SMPR1_SMP14                     ((uint32_t)0x00007000)        /*!<SMP14[2:0] bits (Channel 14 Sample time selection) */
+#define  ADC_SMPR1_SMP14_0                   ((uint32_t)0x00001000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP14_1                   ((uint32_t)0x00002000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP14_2                   ((uint32_t)0x00004000)        /*!<Bit 2 */
+
+#define  ADC_SMPR1_SMP15                     ((uint32_t)0x00038000)        /*!<SMP15[2:0] bits (Channel 15 Sample time selection) */
+#define  ADC_SMPR1_SMP15_0                   ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP15_1                   ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP15_2                   ((uint32_t)0x00020000)        /*!<Bit 2 */
+
+#define  ADC_SMPR1_SMP16                     ((uint32_t)0x001C0000)        /*!<SMP16[2:0] bits (Channel 16 Sample time selection) */
+#define  ADC_SMPR1_SMP16_0                   ((uint32_t)0x00040000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP16_1                   ((uint32_t)0x00080000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP16_2                   ((uint32_t)0x00100000)        /*!<Bit 2 */
+
+#define  ADC_SMPR1_SMP17                     ((uint32_t)0x00E00000)        /*!<SMP17[2:0] bits (Channel 17 Sample time selection) */
+#define  ADC_SMPR1_SMP17_0                   ((uint32_t)0x00200000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP17_1                   ((uint32_t)0x00400000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP17_2                   ((uint32_t)0x00800000)        /*!<Bit 2 */
+
+/******************  Bit definition for ADC_SMPR2 register  *******************/
+#define  ADC_SMPR2_SMP0                      ((uint32_t)0x00000007)        /*!<SMP0[2:0] bits (Channel 0 Sample time selection) */
+#define  ADC_SMPR2_SMP0_0                    ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP0_1                    ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP0_2                    ((uint32_t)0x00000004)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP1                      ((uint32_t)0x00000038)        /*!<SMP1[2:0] bits (Channel 1 Sample time selection) */
+#define  ADC_SMPR2_SMP1_0                    ((uint32_t)0x00000008)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP1_1                    ((uint32_t)0x00000010)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP1_2                    ((uint32_t)0x00000020)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP2                      ((uint32_t)0x000001C0)        /*!<SMP2[2:0] bits (Channel 2 Sample time selection) */
+#define  ADC_SMPR2_SMP2_0                    ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP2_1                    ((uint32_t)0x00000080)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP2_2                    ((uint32_t)0x00000100)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP3                      ((uint32_t)0x00000E00)        /*!<SMP3[2:0] bits (Channel 3 Sample time selection) */
+#define  ADC_SMPR2_SMP3_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP3_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP3_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP4                      ((uint32_t)0x00007000)        /*!<SMP4[2:0] bits (Channel 4 Sample time selection) */
+#define  ADC_SMPR2_SMP4_0                    ((uint32_t)0x00001000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP4_1                    ((uint32_t)0x00002000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP4_2                    ((uint32_t)0x00004000)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP5                      ((uint32_t)0x00038000)        /*!<SMP5[2:0] bits (Channel 5 Sample time selection) */
+#define  ADC_SMPR2_SMP5_0                    ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP5_1                    ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP5_2                    ((uint32_t)0x00020000)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP6                      ((uint32_t)0x001C0000)        /*!<SMP6[2:0] bits (Channel 6 Sample time selection) */
+#define  ADC_SMPR2_SMP6_0                    ((uint32_t)0x00040000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP6_1                    ((uint32_t)0x00080000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP6_2                    ((uint32_t)0x00100000)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP7                      ((uint32_t)0x00E00000)        /*!<SMP7[2:0] bits (Channel 7 Sample time selection) */
+#define  ADC_SMPR2_SMP7_0                    ((uint32_t)0x00200000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP7_1                    ((uint32_t)0x00400000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP7_2                    ((uint32_t)0x00800000)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP8                      ((uint32_t)0x07000000)        /*!<SMP8[2:0] bits (Channel 8 Sample time selection) */
+#define  ADC_SMPR2_SMP8_0                    ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP8_1                    ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP8_2                    ((uint32_t)0x04000000)        /*!<Bit 2 */
+
+#define  ADC_SMPR2_SMP9                      ((uint32_t)0x38000000)        /*!<SMP9[2:0] bits (Channel 9 Sample time selection) */
+#define  ADC_SMPR2_SMP9_0                    ((uint32_t)0x08000000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP9_1                    ((uint32_t)0x10000000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP9_2                    ((uint32_t)0x20000000)        /*!<Bit 2 */
+
+/******************  Bit definition for ADC_JOFR1 register  *******************/
+#define  ADC_JOFR1_JOFFSET1                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 1 */
+
+/******************  Bit definition for ADC_JOFR2 register  *******************/
+#define  ADC_JOFR2_JOFFSET2                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 2 */
+
+/******************  Bit definition for ADC_JOFR3 register  *******************/
+#define  ADC_JOFR3_JOFFSET3                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 3 */
+
+/******************  Bit definition for ADC_JOFR4 register  *******************/
+#define  ADC_JOFR4_JOFFSET4                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 4 */
+
+/*******************  Bit definition for ADC_HTR register  ********************/
+#define  ADC_HTR_HT                          ((uint16_t)0x0FFF)            /*!<Analog watchdog high threshold */
+
+/*******************  Bit definition for ADC_LTR register  ********************/
+#define  ADC_LTR_LT                          ((uint16_t)0x0FFF)            /*!<Analog watchdog low threshold */
+
+/*******************  Bit definition for ADC_SQR1 register  *******************/
+#define  ADC_SQR1_SQ13                       ((uint32_t)0x0000001F)        /*!<SQ13[4:0] bits (13th conversion in regular sequence) */
+#define  ADC_SQR1_SQ13_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ13_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ13_2                     ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ13_3                     ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ13_4                     ((uint32_t)0x00000010)        /*!<Bit 4 */
+
+#define  ADC_SQR1_SQ14                       ((uint32_t)0x000003E0)        /*!<SQ14[4:0] bits (14th conversion in regular sequence) */
+#define  ADC_SQR1_SQ14_0                     ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ14_1                     ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ14_2                     ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ14_3                     ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ14_4                     ((uint32_t)0x00000200)        /*!<Bit 4 */
+
+#define  ADC_SQR1_SQ15                       ((uint32_t)0x00007C00)        /*!<SQ15[4:0] bits (15th conversion in regular sequence) */
+#define  ADC_SQR1_SQ15_0                     ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ15_1                     ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ15_2                     ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ15_3                     ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ15_4                     ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  ADC_SQR1_SQ16                       ((uint32_t)0x000F8000)        /*!<SQ16[4:0] bits (16th conversion in regular sequence) */
+#define  ADC_SQR1_SQ16_0                     ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ16_1                     ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ16_2                     ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ16_3                     ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ16_4                     ((uint32_t)0x00080000)        /*!<Bit 4 */
+
+#define  ADC_SQR1_L                          ((uint32_t)0x00F00000)        /*!<L[3:0] bits (Regular channel sequence length) */
+#define  ADC_SQR1_L_0                        ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_SQR1_L_1                        ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  ADC_SQR1_L_2                        ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  ADC_SQR1_L_3                        ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+/*******************  Bit definition for ADC_SQR2 register  *******************/
+#define  ADC_SQR2_SQ7                        ((uint32_t)0x0000001F)        /*!<SQ7[4:0] bits (7th conversion in regular sequence) */
+#define  ADC_SQR2_SQ7_0                      ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ7_1                      ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ7_2                      ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ7_3                      ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ7_4                      ((uint32_t)0x00000010)        /*!<Bit 4 */
+
+#define  ADC_SQR2_SQ8                        ((uint32_t)0x000003E0)        /*!<SQ8[4:0] bits (8th conversion in regular sequence) */
+#define  ADC_SQR2_SQ8_0                      ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ8_1                      ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ8_2                      ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ8_3                      ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ8_4                      ((uint32_t)0x00000200)        /*!<Bit 4 */
+
+#define  ADC_SQR2_SQ9                        ((uint32_t)0x00007C00)        /*!<SQ9[4:0] bits (9th conversion in regular sequence) */
+#define  ADC_SQR2_SQ9_0                      ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ9_1                      ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ9_2                      ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ9_3                      ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ9_4                      ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  ADC_SQR2_SQ10                       ((uint32_t)0x000F8000)        /*!<SQ10[4:0] bits (10th conversion in regular sequence) */
+#define  ADC_SQR2_SQ10_0                     ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ10_1                     ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ10_2                     ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ10_3                     ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ10_4                     ((uint32_t)0x00080000)        /*!<Bit 4 */
+
+#define  ADC_SQR2_SQ11                       ((uint32_t)0x01F00000)        /*!<SQ11[4:0] bits (11th conversion in regular sequence) */
+#define  ADC_SQR2_SQ11_0                     ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ11_1                     ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ11_2                     ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ11_3                     ((uint32_t)0x00800000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ11_4                     ((uint32_t)0x01000000)        /*!<Bit 4 */
+
+#define  ADC_SQR2_SQ12                       ((uint32_t)0x3E000000)        /*!<SQ12[4:0] bits (12th conversion in regular sequence) */
+#define  ADC_SQR2_SQ12_0                     ((uint32_t)0x02000000)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ12_1                     ((uint32_t)0x04000000)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ12_2                     ((uint32_t)0x08000000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ12_3                     ((uint32_t)0x10000000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ12_4                     ((uint32_t)0x20000000)        /*!<Bit 4 */
+
+/*******************  Bit definition for ADC_SQR3 register  *******************/
+#define  ADC_SQR3_SQ1                        ((uint32_t)0x0000001F)        /*!<SQ1[4:0] bits (1st conversion in regular sequence) */
+#define  ADC_SQR3_SQ1_0                      ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ1_1                      ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ1_2                      ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ1_3                      ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ1_4                      ((uint32_t)0x00000010)        /*!<Bit 4 */
+
+#define  ADC_SQR3_SQ2                        ((uint32_t)0x000003E0)        /*!<SQ2[4:0] bits (2nd conversion in regular sequence) */
+#define  ADC_SQR3_SQ2_0                      ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ2_1                      ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ2_2                      ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ2_3                      ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ2_4                      ((uint32_t)0x00000200)        /*!<Bit 4 */
+
+#define  ADC_SQR3_SQ3                        ((uint32_t)0x00007C00)        /*!<SQ3[4:0] bits (3rd conversion in regular sequence) */
+#define  ADC_SQR3_SQ3_0                      ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ3_1                      ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ3_2                      ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ3_3                      ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ3_4                      ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  ADC_SQR3_SQ4                        ((uint32_t)0x000F8000)        /*!<SQ4[4:0] bits (4th conversion in regular sequence) */
+#define  ADC_SQR3_SQ4_0                      ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ4_1                      ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ4_2                      ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ4_3                      ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ4_4                      ((uint32_t)0x00080000)        /*!<Bit 4 */
+
+#define  ADC_SQR3_SQ5                        ((uint32_t)0x01F00000)        /*!<SQ5[4:0] bits (5th conversion in regular sequence) */
+#define  ADC_SQR3_SQ5_0                      ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ5_1                      ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ5_2                      ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ5_3                      ((uint32_t)0x00800000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ5_4                      ((uint32_t)0x01000000)        /*!<Bit 4 */
+
+#define  ADC_SQR3_SQ6                        ((uint32_t)0x3E000000)        /*!<SQ6[4:0] bits (6th conversion in regular sequence) */
+#define  ADC_SQR3_SQ6_0                      ((uint32_t)0x02000000)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ6_1                      ((uint32_t)0x04000000)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ6_2                      ((uint32_t)0x08000000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ6_3                      ((uint32_t)0x10000000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ6_4                      ((uint32_t)0x20000000)        /*!<Bit 4 */
+
+/*******************  Bit definition for ADC_JSQR register  *******************/
+#define  ADC_JSQR_JSQ1                       ((uint32_t)0x0000001F)        /*!<JSQ1[4:0] bits (1st conversion in injected sequence) */  
+#define  ADC_JSQR_JSQ1_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ1_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ1_2                     ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ1_3                     ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ1_4                     ((uint32_t)0x00000010)        /*!<Bit 4 */
+
+#define  ADC_JSQR_JSQ2                       ((uint32_t)0x000003E0)        /*!<JSQ2[4:0] bits (2nd conversion in injected sequence) */
+#define  ADC_JSQR_JSQ2_0                     ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ2_1                     ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ2_2                     ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ2_3                     ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ2_4                     ((uint32_t)0x00000200)        /*!<Bit 4 */
+
+#define  ADC_JSQR_JSQ3                       ((uint32_t)0x00007C00)        /*!<JSQ3[4:0] bits (3rd conversion in injected sequence) */
+#define  ADC_JSQR_JSQ3_0                     ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ3_1                     ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ3_2                     ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ3_3                     ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ3_4                     ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  ADC_JSQR_JSQ4                       ((uint32_t)0x000F8000)        /*!<JSQ4[4:0] bits (4th conversion in injected sequence) */
+#define  ADC_JSQR_JSQ4_0                     ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ4_1                     ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ4_2                     ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ4_3                     ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ4_4                     ((uint32_t)0x00080000)        /*!<Bit 4 */
+
+#define  ADC_JSQR_JL                         ((uint32_t)0x00300000)        /*!<JL[1:0] bits (Injected Sequence length) */
+#define  ADC_JSQR_JL_0                       ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_JSQR_JL_1                       ((uint32_t)0x00200000)        /*!<Bit 1 */
+
+/*******************  Bit definition for ADC_JDR1 register  *******************/
+#define  ADC_JDR1_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/*******************  Bit definition for ADC_JDR2 register  *******************/
+#define  ADC_JDR2_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/*******************  Bit definition for ADC_JDR3 register  *******************/
+#define  ADC_JDR3_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/*******************  Bit definition for ADC_JDR4 register  *******************/
+#define  ADC_JDR4_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/********************  Bit definition for ADC_DR register  ********************/
+#define  ADC_DR_DATA                         ((uint32_t)0x0000FFFF)        /*!<Regular data */
+#define  ADC_DR_ADC2DATA                     ((uint32_t)0xFFFF0000)        /*!<ADC2 data */
+
+/******************************************************************************/
+/*                                                                            */
+/*                      Digital to Analog Converter                           */
+/*                                                                            */
+/******************************************************************************/
+
+/********************  Bit definition for DAC_CR register  ********************/
+#define  DAC_CR_EN1                          ((uint32_t)0x00000001)        /*!<DAC channel1 enable */
+#define  DAC_CR_BOFF1                        ((uint32_t)0x00000002)        /*!<DAC channel1 output buffer disable */
+#define  DAC_CR_TEN1                         ((uint32_t)0x00000004)        /*!<DAC channel1 Trigger enable */
+
+#define  DAC_CR_TSEL1                        ((uint32_t)0x00000038)        /*!<TSEL1[2:0] (DAC channel1 Trigger selection) */
+#define  DAC_CR_TSEL1_0                      ((uint32_t)0x00000008)        /*!<Bit 0 */
+#define  DAC_CR_TSEL1_1                      ((uint32_t)0x00000010)        /*!<Bit 1 */
+#define  DAC_CR_TSEL1_2                      ((uint32_t)0x00000020)        /*!<Bit 2 */
+
+#define  DAC_CR_WAVE1                        ((uint32_t)0x000000C0)        /*!<WAVE1[1:0] (DAC channel1 noise/triangle wave generation enable) */
+#define  DAC_CR_WAVE1_0                      ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  DAC_CR_WAVE1_1                      ((uint32_t)0x00000080)        /*!<Bit 1 */
+
+#define  DAC_CR_MAMP1                        ((uint32_t)0x00000F00)        /*!<MAMP1[3:0] (DAC channel1 Mask/Amplitude selector) */
+#define  DAC_CR_MAMP1_0                      ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  DAC_CR_MAMP1_1                      ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  DAC_CR_MAMP1_2                      ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  DAC_CR_MAMP1_3                      ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  DAC_CR_DMAEN1                       ((uint32_t)0x00001000)        /*!<DAC channel1 DMA enable */
+#define  DAC_CR_EN2                          ((uint32_t)0x00010000)        /*!<DAC channel2 enable */
+#define  DAC_CR_BOFF2                        ((uint32_t)0x00020000)        /*!<DAC channel2 output buffer disable */
+#define  DAC_CR_TEN2                         ((uint32_t)0x00040000)        /*!<DAC channel2 Trigger enable */
+
+#define  DAC_CR_TSEL2                        ((uint32_t)0x00380000)        /*!<TSEL2[2:0] (DAC channel2 Trigger selection) */
+#define  DAC_CR_TSEL2_0                      ((uint32_t)0x00080000)        /*!<Bit 0 */
+#define  DAC_CR_TSEL2_1                      ((uint32_t)0x00100000)        /*!<Bit 1 */
+#define  DAC_CR_TSEL2_2                      ((uint32_t)0x00200000)        /*!<Bit 2 */
+
+#define  DAC_CR_WAVE2                        ((uint32_t)0x00C00000)        /*!<WAVE2[1:0] (DAC channel2 noise/triangle wave generation enable) */
+#define  DAC_CR_WAVE2_0                      ((uint32_t)0x00400000)        /*!<Bit 0 */
+#define  DAC_CR_WAVE2_1                      ((uint32_t)0x00800000)        /*!<Bit 1 */
+
+#define  DAC_CR_MAMP2                        ((uint32_t)0x0F000000)        /*!<MAMP2[3:0] (DAC channel2 Mask/Amplitude selector) */
+#define  DAC_CR_MAMP2_0                      ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  DAC_CR_MAMP2_1                      ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  DAC_CR_MAMP2_2                      ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  DAC_CR_MAMP2_3                      ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  DAC_CR_DMAEN2                       ((uint32_t)0x10000000)        /*!<DAC channel2 DMA enabled */
+
+/*****************  Bit definition for DAC_SWTRIGR register  ******************/
+#define  DAC_SWTRIGR_SWTRIG1                 ((uint8_t)0x01)               /*!<DAC channel1 software trigger */
+#define  DAC_SWTRIGR_SWTRIG2                 ((uint8_t)0x02)               /*!<DAC channel2 software trigger */
+
+/*****************  Bit definition for DAC_DHR12R1 register  ******************/
+#define  DAC_DHR12R1_DACC1DHR                ((uint16_t)0x0FFF)            /*!<DAC channel1 12-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12L1 register  ******************/
+#define  DAC_DHR12L1_DACC1DHR                ((uint16_t)0xFFF0)            /*!<DAC channel1 12-bit Left aligned data */
+
+/******************  Bit definition for DAC_DHR8R1 register  ******************/
+#define  DAC_DHR8R1_DACC1DHR                 ((uint8_t)0xFF)               /*!<DAC channel1 8-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12R2 register  ******************/
+#define  DAC_DHR12R2_DACC2DHR                ((uint16_t)0x0FFF)            /*!<DAC channel2 12-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12L2 register  ******************/
+#define  DAC_DHR12L2_DACC2DHR                ((uint16_t)0xFFF0)            /*!<DAC channel2 12-bit Left aligned data */
+
+/******************  Bit definition for DAC_DHR8R2 register  ******************/
+#define  DAC_DHR8R2_DACC2DHR                 ((uint8_t)0xFF)               /*!<DAC channel2 8-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12RD register  ******************/
+#define  DAC_DHR12RD_DACC1DHR                ((uint32_t)0x00000FFF)        /*!<DAC channel1 12-bit Right aligned data */
+#define  DAC_DHR12RD_DACC2DHR                ((uint32_t)0x0FFF0000)        /*!<DAC channel2 12-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12LD register  ******************/
+#define  DAC_DHR12LD_DACC1DHR                ((uint32_t)0x0000FFF0)        /*!<DAC channel1 12-bit Left aligned data */
+#define  DAC_DHR12LD_DACC2DHR                ((uint32_t)0xFFF00000)        /*!<DAC channel2 12-bit Left aligned data */
+
+/******************  Bit definition for DAC_DHR8RD register  ******************/
+#define  DAC_DHR8RD_DACC1DHR                 ((uint16_t)0x00FF)            /*!<DAC channel1 8-bit Right aligned data */
+#define  DAC_DHR8RD_DACC2DHR                 ((uint16_t)0xFF00)            /*!<DAC channel2 8-bit Right aligned data */
+
+/*******************  Bit definition for DAC_DOR1 register  *******************/
+#define  DAC_DOR1_DACC1DOR                   ((uint16_t)0x0FFF)            /*!<DAC channel1 data output */
+
+/*******************  Bit definition for DAC_DOR2 register  *******************/
+#define  DAC_DOR2_DACC2DOR                   ((uint16_t)0x0FFF)            /*!<DAC channel2 data output */
+
+/******************************************************************************/
+/*                                                                            */
+/*                                    TIM                                     */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for TIM_CR1 register  ********************/
+#define  TIM_CR1_CEN                         ((uint16_t)0x0001)            /*!<Counter enable */
+#define  TIM_CR1_UDIS                        ((uint16_t)0x0002)            /*!<Update disable */
+#define  TIM_CR1_URS                         ((uint16_t)0x0004)            /*!<Update request source */
+#define  TIM_CR1_OPM                         ((uint16_t)0x0008)            /*!<One pulse mode */
+#define  TIM_CR1_DIR                         ((uint16_t)0x0010)            /*!<Direction */
+
+#define  TIM_CR1_CMS                         ((uint16_t)0x0060)            /*!<CMS[1:0] bits (Center-aligned mode selection) */
+#define  TIM_CR1_CMS_0                       ((uint16_t)0x0020)            /*!<Bit 0 */
+#define  TIM_CR1_CMS_1                       ((uint16_t)0x0040)            /*!<Bit 1 */
+
+#define  TIM_CR1_ARPE                        ((uint16_t)0x0080)            /*!<Auto-reload preload enable */
+
+#define  TIM_CR1_CKD                         ((uint16_t)0x0300)            /*!<CKD[1:0] bits (clock division) */
+#define  TIM_CR1_CKD_0                       ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_CR1_CKD_1                       ((uint16_t)0x0200)            /*!<Bit 1 */
+
+/*******************  Bit definition for TIM_CR2 register  ********************/
+#define  TIM_CR2_CCPC                        ((uint16_t)0x0001)            /*!<Capture/Compare Preloaded Control */
+#define  TIM_CR2_CCUS                        ((uint16_t)0x0004)            /*!<Capture/Compare Control Update Selection */
+#define  TIM_CR2_CCDS                        ((uint16_t)0x0008)            /*!<Capture/Compare DMA Selection */
+
+#define  TIM_CR2_MMS                         ((uint16_t)0x0070)            /*!<MMS[2:0] bits (Master Mode Selection) */
+#define  TIM_CR2_MMS_0                       ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CR2_MMS_1                       ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CR2_MMS_2                       ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_CR2_TI1S                        ((uint16_t)0x0080)            /*!<TI1 Selection */
+#define  TIM_CR2_OIS1                        ((uint16_t)0x0100)            /*!<Output Idle state 1 (OC1 output) */
+#define  TIM_CR2_OIS1N                       ((uint16_t)0x0200)            /*!<Output Idle state 1 (OC1N output) */
+#define  TIM_CR2_OIS2                        ((uint16_t)0x0400)            /*!<Output Idle state 2 (OC2 output) */
+#define  TIM_CR2_OIS2N                       ((uint16_t)0x0800)            /*!<Output Idle state 2 (OC2N output) */
+#define  TIM_CR2_OIS3                        ((uint16_t)0x1000)            /*!<Output Idle state 3 (OC3 output) */
+#define  TIM_CR2_OIS3N                       ((uint16_t)0x2000)            /*!<Output Idle state 3 (OC3N output) */
+#define  TIM_CR2_OIS4                        ((uint16_t)0x4000)            /*!<Output Idle state 4 (OC4 output) */
+
+/*******************  Bit definition for TIM_SMCR register  *******************/
+#define  TIM_SMCR_SMS                        ((uint16_t)0x0007)            /*!<SMS[2:0] bits (Slave mode selection) */
+#define  TIM_SMCR_SMS_0                      ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_SMCR_SMS_1                      ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  TIM_SMCR_SMS_2                      ((uint16_t)0x0004)            /*!<Bit 2 */
+
+#define  TIM_SMCR_TS                         ((uint16_t)0x0070)            /*!<TS[2:0] bits (Trigger selection) */
+#define  TIM_SMCR_TS_0                       ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_SMCR_TS_1                       ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_SMCR_TS_2                       ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_SMCR_MSM                        ((uint16_t)0x0080)            /*!<Master/slave mode */
+
+#define  TIM_SMCR_ETF                        ((uint16_t)0x0F00)            /*!<ETF[3:0] bits (External trigger filter) */
+#define  TIM_SMCR_ETF_0                      ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_SMCR_ETF_1                      ((uint16_t)0x0200)            /*!<Bit 1 */
+#define  TIM_SMCR_ETF_2                      ((uint16_t)0x0400)            /*!<Bit 2 */
+#define  TIM_SMCR_ETF_3                      ((uint16_t)0x0800)            /*!<Bit 3 */
+
+#define  TIM_SMCR_ETPS                       ((uint16_t)0x3000)            /*!<ETPS[1:0] bits (External trigger prescaler) */
+#define  TIM_SMCR_ETPS_0                     ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_SMCR_ETPS_1                     ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  TIM_SMCR_ECE                        ((uint16_t)0x4000)            /*!<External clock enable */
+#define  TIM_SMCR_ETP                        ((uint16_t)0x8000)            /*!<External trigger polarity */
+
+/*******************  Bit definition for TIM_DIER register  *******************/
+#define  TIM_DIER_UIE                        ((uint16_t)0x0001)            /*!<Update interrupt enable */
+#define  TIM_DIER_CC1IE                      ((uint16_t)0x0002)            /*!<Capture/Compare 1 interrupt enable */
+#define  TIM_DIER_CC2IE                      ((uint16_t)0x0004)            /*!<Capture/Compare 2 interrupt enable */
+#define  TIM_DIER_CC3IE                      ((uint16_t)0x0008)            /*!<Capture/Compare 3 interrupt enable */
+#define  TIM_DIER_CC4IE                      ((uint16_t)0x0010)            /*!<Capture/Compare 4 interrupt enable */
+#define  TIM_DIER_COMIE                      ((uint16_t)0x0020)            /*!<COM interrupt enable */
+#define  TIM_DIER_TIE                        ((uint16_t)0x0040)            /*!<Trigger interrupt enable */
+#define  TIM_DIER_BIE                        ((uint16_t)0x0080)            /*!<Break interrupt enable */
+#define  TIM_DIER_UDE                        ((uint16_t)0x0100)            /*!<Update DMA request enable */
+#define  TIM_DIER_CC1DE                      ((uint16_t)0x0200)            /*!<Capture/Compare 1 DMA request enable */
+#define  TIM_DIER_CC2DE                      ((uint16_t)0x0400)            /*!<Capture/Compare 2 DMA request enable */
+#define  TIM_DIER_CC3DE                      ((uint16_t)0x0800)            /*!<Capture/Compare 3 DMA request enable */
+#define  TIM_DIER_CC4DE                      ((uint16_t)0x1000)            /*!<Capture/Compare 4 DMA request enable */
+#define  TIM_DIER_COMDE                      ((uint16_t)0x2000)            /*!<COM DMA request enable */
+#define  TIM_DIER_TDE                        ((uint16_t)0x4000)            /*!<Trigger DMA request enable */
+
+/********************  Bit definition for TIM_SR register  ********************/
+#define  TIM_SR_UIF                          ((uint16_t)0x0001)            /*!<Update interrupt Flag */
+#define  TIM_SR_CC1IF                        ((uint16_t)0x0002)            /*!<Capture/Compare 1 interrupt Flag */
+#define  TIM_SR_CC2IF                        ((uint16_t)0x0004)            /*!<Capture/Compare 2 interrupt Flag */
+#define  TIM_SR_CC3IF                        ((uint16_t)0x0008)            /*!<Capture/Compare 3 interrupt Flag */
+#define  TIM_SR_CC4IF                        ((uint16_t)0x0010)            /*!<Capture/Compare 4 interrupt Flag */
+#define  TIM_SR_COMIF                        ((uint16_t)0x0020)            /*!<COM interrupt Flag */
+#define  TIM_SR_TIF                          ((uint16_t)0x0040)            /*!<Trigger interrupt Flag */
+#define  TIM_SR_BIF                          ((uint16_t)0x0080)            /*!<Break interrupt Flag */
+#define  TIM_SR_CC1OF                        ((uint16_t)0x0200)            /*!<Capture/Compare 1 Overcapture Flag */
+#define  TIM_SR_CC2OF                        ((uint16_t)0x0400)            /*!<Capture/Compare 2 Overcapture Flag */
+#define  TIM_SR_CC3OF                        ((uint16_t)0x0800)            /*!<Capture/Compare 3 Overcapture Flag */
+#define  TIM_SR_CC4OF                        ((uint16_t)0x1000)            /*!<Capture/Compare 4 Overcapture Flag */
+
+/*******************  Bit definition for TIM_EGR register  ********************/
+#define  TIM_EGR_UG                          ((uint8_t)0x01)               /*!<Update Generation */
+#define  TIM_EGR_CC1G                        ((uint8_t)0x02)               /*!<Capture/Compare 1 Generation */
+#define  TIM_EGR_CC2G                        ((uint8_t)0x04)               /*!<Capture/Compare 2 Generation */
+#define  TIM_EGR_CC3G                        ((uint8_t)0x08)               /*!<Capture/Compare 3 Generation */
+#define  TIM_EGR_CC4G                        ((uint8_t)0x10)               /*!<Capture/Compare 4 Generation */
+#define  TIM_EGR_COMG                        ((uint8_t)0x20)               /*!<Capture/Compare Control Update Generation */
+#define  TIM_EGR_TG                          ((uint8_t)0x40)               /*!<Trigger Generation */
+#define  TIM_EGR_BG                          ((uint8_t)0x80)               /*!<Break Generation */
+
+/******************  Bit definition for TIM_CCMR1 register  *******************/
+#define  TIM_CCMR1_CC1S                      ((uint16_t)0x0003)            /*!<CC1S[1:0] bits (Capture/Compare 1 Selection) */
+#define  TIM_CCMR1_CC1S_0                    ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_CCMR1_CC1S_1                    ((uint16_t)0x0002)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_OC1FE                     ((uint16_t)0x0004)            /*!<Output Compare 1 Fast enable */
+#define  TIM_CCMR1_OC1PE                     ((uint16_t)0x0008)            /*!<Output Compare 1 Preload enable */
+
+#define  TIM_CCMR1_OC1M                      ((uint16_t)0x0070)            /*!<OC1M[2:0] bits (Output Compare 1 Mode) */
+#define  TIM_CCMR1_OC1M_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR1_OC1M_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR1_OC1M_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_CCMR1_OC1CE                     ((uint16_t)0x0080)            /*!<Output Compare 1Clear Enable */
+
+#define  TIM_CCMR1_CC2S                      ((uint16_t)0x0300)            /*!<CC2S[1:0] bits (Capture/Compare 2 Selection) */
+#define  TIM_CCMR1_CC2S_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_CCMR1_CC2S_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_OC2FE                     ((uint16_t)0x0400)            /*!<Output Compare 2 Fast enable */
+#define  TIM_CCMR1_OC2PE                     ((uint16_t)0x0800)            /*!<Output Compare 2 Preload enable */
+
+#define  TIM_CCMR1_OC2M                      ((uint16_t)0x7000)            /*!<OC2M[2:0] bits (Output Compare 2 Mode) */
+#define  TIM_CCMR1_OC2M_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR1_OC2M_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR1_OC2M_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+
+#define  TIM_CCMR1_OC2CE                     ((uint16_t)0x8000)            /*!<Output Compare 2 Clear Enable */
+
+/*----------------------------------------------------------------------------*/
+
+#define  TIM_CCMR1_IC1PSC                    ((uint16_t)0x000C)            /*!<IC1PSC[1:0] bits (Input Capture 1 Prescaler) */
+#define  TIM_CCMR1_IC1PSC_0                  ((uint16_t)0x0004)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC1PSC_1                  ((uint16_t)0x0008)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_IC1F                      ((uint16_t)0x00F0)            /*!<IC1F[3:0] bits (Input Capture 1 Filter) */
+#define  TIM_CCMR1_IC1F_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC1F_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR1_IC1F_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+#define  TIM_CCMR1_IC1F_3                    ((uint16_t)0x0080)            /*!<Bit 3 */
+
+#define  TIM_CCMR1_IC2PSC                    ((uint16_t)0x0C00)            /*!<IC2PSC[1:0] bits (Input Capture 2 Prescaler) */
+#define  TIM_CCMR1_IC2PSC_0                  ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC2PSC_1                  ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_IC2F                      ((uint16_t)0xF000)            /*!<IC2F[3:0] bits (Input Capture 2 Filter) */
+#define  TIM_CCMR1_IC2F_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC2F_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR1_IC2F_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+#define  TIM_CCMR1_IC2F_3                    ((uint16_t)0x8000)            /*!<Bit 3 */
+
+/******************  Bit definition for TIM_CCMR2 register  *******************/
+#define  TIM_CCMR2_CC3S                      ((uint16_t)0x0003)            /*!<CC3S[1:0] bits (Capture/Compare 3 Selection) */
+#define  TIM_CCMR2_CC3S_0                    ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_CCMR2_CC3S_1                    ((uint16_t)0x0002)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_OC3FE                     ((uint16_t)0x0004)            /*!<Output Compare 3 Fast enable */
+#define  TIM_CCMR2_OC3PE                     ((uint16_t)0x0008)            /*!<Output Compare 3 Preload enable */
+
+#define  TIM_CCMR2_OC3M                      ((uint16_t)0x0070)            /*!<OC3M[2:0] bits (Output Compare 3 Mode) */
+#define  TIM_CCMR2_OC3M_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR2_OC3M_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR2_OC3M_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_CCMR2_OC3CE                     ((uint16_t)0x0080)            /*!<Output Compare 3 Clear Enable */
+
+#define  TIM_CCMR2_CC4S                      ((uint16_t)0x0300)            /*!<CC4S[1:0] bits (Capture/Compare 4 Selection) */
+#define  TIM_CCMR2_CC4S_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_CCMR2_CC4S_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_OC4FE                     ((uint16_t)0x0400)            /*!<Output Compare 4 Fast enable */
+#define  TIM_CCMR2_OC4PE                     ((uint16_t)0x0800)            /*!<Output Compare 4 Preload enable */
+
+#define  TIM_CCMR2_OC4M                      ((uint16_t)0x7000)            /*!<OC4M[2:0] bits (Output Compare 4 Mode) */
+#define  TIM_CCMR2_OC4M_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR2_OC4M_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR2_OC4M_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+
+#define  TIM_CCMR2_OC4CE                     ((uint16_t)0x8000)            /*!<Output Compare 4 Clear Enable */
+
+/*----------------------------------------------------------------------------*/
+
+#define  TIM_CCMR2_IC3PSC                    ((uint16_t)0x000C)            /*!<IC3PSC[1:0] bits (Input Capture 3 Prescaler) */
+#define  TIM_CCMR2_IC3PSC_0                  ((uint16_t)0x0004)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC3PSC_1                  ((uint16_t)0x0008)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_IC3F                      ((uint16_t)0x00F0)            /*!<IC3F[3:0] bits (Input Capture 3 Filter) */
+#define  TIM_CCMR2_IC3F_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC3F_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR2_IC3F_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+#define  TIM_CCMR2_IC3F_3                    ((uint16_t)0x0080)            /*!<Bit 3 */
+
+#define  TIM_CCMR2_IC4PSC                    ((uint16_t)0x0C00)            /*!<IC4PSC[1:0] bits (Input Capture 4 Prescaler) */
+#define  TIM_CCMR2_IC4PSC_0                  ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC4PSC_1                  ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_IC4F                      ((uint16_t)0xF000)            /*!<IC4F[3:0] bits (Input Capture 4 Filter) */
+#define  TIM_CCMR2_IC4F_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC4F_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR2_IC4F_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+#define  TIM_CCMR2_IC4F_3                    ((uint16_t)0x8000)            /*!<Bit 3 */
+
+/*******************  Bit definition for TIM_CCER register  *******************/
+#define  TIM_CCER_CC1E                       ((uint16_t)0x0001)            /*!<Capture/Compare 1 output enable */
+#define  TIM_CCER_CC1P                       ((uint16_t)0x0002)            /*!<Capture/Compare 1 output Polarity */
+#define  TIM_CCER_CC1NE                      ((uint16_t)0x0004)            /*!<Capture/Compare 1 Complementary output enable */
+#define  TIM_CCER_CC1NP                      ((uint16_t)0x0008)            /*!<Capture/Compare 1 Complementary output Polarity */
+#define  TIM_CCER_CC2E                       ((uint16_t)0x0010)            /*!<Capture/Compare 2 output enable */
+#define  TIM_CCER_CC2P                       ((uint16_t)0x0020)            /*!<Capture/Compare 2 output Polarity */
+#define  TIM_CCER_CC2NE                      ((uint16_t)0x0040)            /*!<Capture/Compare 2 Complementary output enable */
+#define  TIM_CCER_CC2NP                      ((uint16_t)0x0080)            /*!<Capture/Compare 2 Complementary output Polarity */
+#define  TIM_CCER_CC3E                       ((uint16_t)0x0100)            /*!<Capture/Compare 3 output enable */
+#define  TIM_CCER_CC3P                       ((uint16_t)0x0200)            /*!<Capture/Compare 3 output Polarity */
+#define  TIM_CCER_CC3NE                      ((uint16_t)0x0400)            /*!<Capture/Compare 3 Complementary output enable */
+#define  TIM_CCER_CC3NP                      ((uint16_t)0x0800)            /*!<Capture/Compare 3 Complementary output Polarity */
+#define  TIM_CCER_CC4E                       ((uint16_t)0x1000)            /*!<Capture/Compare 4 output enable */
+#define  TIM_CCER_CC4P                       ((uint16_t)0x2000)            /*!<Capture/Compare 4 output Polarity */
+
+/*******************  Bit definition for TIM_CNT register  ********************/
+#define  TIM_CNT_CNT                         ((uint16_t)0xFFFF)            /*!<Counter Value */
+
+/*******************  Bit definition for TIM_PSC register  ********************/
+#define  TIM_PSC_PSC                         ((uint16_t)0xFFFF)            /*!<Prescaler Value */
+
+/*******************  Bit definition for TIM_ARR register  ********************/
+#define  TIM_ARR_ARR                         ((uint16_t)0xFFFF)            /*!<actual auto-reload Value */
+
+/*******************  Bit definition for TIM_RCR register  ********************/
+#define  TIM_RCR_REP                         ((uint8_t)0xFF)               /*!<Repetition Counter Value */
+
+/*******************  Bit definition for TIM_CCR1 register  *******************/
+#define  TIM_CCR1_CCR1                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 1 Value */
+
+/*******************  Bit definition for TIM_CCR2 register  *******************/
+#define  TIM_CCR2_CCR2                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 2 Value */
+
+/*******************  Bit definition for TIM_CCR3 register  *******************/
+#define  TIM_CCR3_CCR3                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 3 Value */
+
+/*******************  Bit definition for TIM_CCR4 register  *******************/
+#define  TIM_CCR4_CCR4                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 4 Value */
+
+/*******************  Bit definition for TIM_BDTR register  *******************/
+#define  TIM_BDTR_DTG                        ((uint16_t)0x00FF)            /*!<DTG[0:7] bits (Dead-Time Generator set-up) */
+#define  TIM_BDTR_DTG_0                      ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_BDTR_DTG_1                      ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  TIM_BDTR_DTG_2                      ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  TIM_BDTR_DTG_3                      ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  TIM_BDTR_DTG_4                      ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  TIM_BDTR_DTG_5                      ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  TIM_BDTR_DTG_6                      ((uint16_t)0x0040)            /*!<Bit 6 */
+#define  TIM_BDTR_DTG_7                      ((uint16_t)0x0080)            /*!<Bit 7 */
+
+#define  TIM_BDTR_LOCK                       ((uint16_t)0x0300)            /*!<LOCK[1:0] bits (Lock Configuration) */
+#define  TIM_BDTR_LOCK_0                     ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_BDTR_LOCK_1                     ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  TIM_BDTR_OSSI                       ((uint16_t)0x0400)            /*!<Off-State Selection for Idle mode */
+#define  TIM_BDTR_OSSR                       ((uint16_t)0x0800)            /*!<Off-State Selection for Run mode */
+#define  TIM_BDTR_BKE                        ((uint16_t)0x1000)            /*!<Break enable */
+#define  TIM_BDTR_BKP                        ((uint16_t)0x2000)            /*!<Break Polarity */
+#define  TIM_BDTR_AOE                        ((uint16_t)0x4000)            /*!<Automatic Output enable */
+#define  TIM_BDTR_MOE                        ((uint16_t)0x8000)            /*!<Main Output enable */
+
+/*******************  Bit definition for TIM_DCR register  ********************/
+#define  TIM_DCR_DBA                         ((uint16_t)0x001F)            /*!<DBA[4:0] bits (DMA Base Address) */
+#define  TIM_DCR_DBA_0                       ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_DCR_DBA_1                       ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  TIM_DCR_DBA_2                       ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  TIM_DCR_DBA_3                       ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  TIM_DCR_DBA_4                       ((uint16_t)0x0010)            /*!<Bit 4 */
+
+#define  TIM_DCR_DBL                         ((uint16_t)0x1F00)            /*!<DBL[4:0] bits (DMA Burst Length) */
+#define  TIM_DCR_DBL_0                       ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_DCR_DBL_1                       ((uint16_t)0x0200)            /*!<Bit 1 */
+#define  TIM_DCR_DBL_2                       ((uint16_t)0x0400)            /*!<Bit 2 */
+#define  TIM_DCR_DBL_3                       ((uint16_t)0x0800)            /*!<Bit 3 */
+#define  TIM_DCR_DBL_4                       ((uint16_t)0x1000)            /*!<Bit 4 */
+
+/*******************  Bit definition for TIM_DMAR register  *******************/
+#define  TIM_DMAR_DMAB                       ((uint16_t)0xFFFF)            /*!<DMA register for burst accesses */
+
+/******************************************************************************/
+/*                                                                            */
+/*                             Real-Time Clock                                */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for RTC_CRH register  ********************/
+#define  RTC_CRH_SECIE                       ((uint8_t)0x01)               /*!<Second Interrupt Enable */
+#define  RTC_CRH_ALRIE                       ((uint8_t)0x02)               /*!<Alarm Interrupt Enable */
+#define  RTC_CRH_OWIE                        ((uint8_t)0x04)               /*!<OverfloW Interrupt Enable */
+
+/*******************  Bit definition for RTC_CRL register  ********************/
+#define  RTC_CRL_SECF                        ((uint8_t)0x01)               /*!<Second Flag */
+#define  RTC_CRL_ALRF                        ((uint8_t)0x02)               /*!<Alarm Flag */
+#define  RTC_CRL_OWF                         ((uint8_t)0x04)               /*!<OverfloW Flag */
+#define  RTC_CRL_RSF                         ((uint8_t)0x08)               /*!<Registers Synchronized Flag */
+#define  RTC_CRL_CNF                         ((uint8_t)0x10)               /*!<Configuration Flag */
+#define  RTC_CRL_RTOFF                       ((uint8_t)0x20)               /*!<RTC operation OFF */
+
+/*******************  Bit definition for RTC_PRLH register  *******************/
+#define  RTC_PRLH_PRL                        ((uint16_t)0x000F)            /*!<RTC Prescaler Reload Value High */
+
+/*******************  Bit definition for RTC_PRLL register  *******************/
+#define  RTC_PRLL_PRL                        ((uint16_t)0xFFFF)            /*!<RTC Prescaler Reload Value Low */
+
+/*******************  Bit definition for RTC_DIVH register  *******************/
+#define  RTC_DIVH_RTC_DIV                    ((uint16_t)0x000F)            /*!<RTC Clock Divider High */
+
+/*******************  Bit definition for RTC_DIVL register  *******************/
+#define  RTC_DIVL_RTC_DIV                    ((uint16_t)0xFFFF)            /*!<RTC Clock Divider Low */
+
+/*******************  Bit definition for RTC_CNTH register  *******************/
+#define  RTC_CNTH_RTC_CNT                    ((uint16_t)0xFFFF)            /*!<RTC Counter High */
+
+/*******************  Bit definition for RTC_CNTL register  *******************/
+#define  RTC_CNTL_RTC_CNT                    ((uint16_t)0xFFFF)            /*!<RTC Counter Low */
+
+/*******************  Bit definition for RTC_ALRH register  *******************/
+#define  RTC_ALRH_RTC_ALR                    ((uint16_t)0xFFFF)            /*!<RTC Alarm High */
+
+/*******************  Bit definition for RTC_ALRL register  *******************/
+#define  RTC_ALRL_RTC_ALR                    ((uint16_t)0xFFFF)            /*!<RTC Alarm Low */
+
+/******************************************************************************/
+/*                                                                            */
+/*                           Independent WATCHDOG                             */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for IWDG_KR register  ********************/
+#define  IWDG_KR_KEY                         ((uint16_t)0xFFFF)            /*!<Key value (write only, read 0000h) */
+
+/*******************  Bit definition for IWDG_PR register  ********************/
+#define  IWDG_PR_PR                          ((uint8_t)0x07)               /*!<PR[2:0] (Prescaler divider) */
+#define  IWDG_PR_PR_0                        ((uint8_t)0x01)               /*!<Bit 0 */
+#define  IWDG_PR_PR_1                        ((uint8_t)0x02)               /*!<Bit 1 */
+#define  IWDG_PR_PR_2                        ((uint8_t)0x04)               /*!<Bit 2 */
+
+/*******************  Bit definition for IWDG_RLR register  *******************/
+#define  IWDG_RLR_RL                         ((uint16_t)0x0FFF)            /*!<Watchdog counter reload value */
+
+/*******************  Bit definition for IWDG_SR register  ********************/
+#define  IWDG_SR_PVU                         ((uint8_t)0x01)               /*!<Watchdog prescaler value update */
+#define  IWDG_SR_RVU                         ((uint8_t)0x02)               /*!<Watchdog counter reload value update */
+
+/******************************************************************************/
+/*                                                                            */
+/*                            Window WATCHDOG                                 */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for WWDG_CR register  ********************/
+#define  WWDG_CR_T                           ((uint8_t)0x7F)               /*!<T[6:0] bits (7-Bit counter (MSB to LSB)) */
+#define  WWDG_CR_T0                          ((uint8_t)0x01)               /*!<Bit 0 */
+#define  WWDG_CR_T1                          ((uint8_t)0x02)               /*!<Bit 1 */
+#define  WWDG_CR_T2                          ((uint8_t)0x04)               /*!<Bit 2 */
+#define  WWDG_CR_T3                          ((uint8_t)0x08)               /*!<Bit 3 */
+#define  WWDG_CR_T4                          ((uint8_t)0x10)               /*!<Bit 4 */
+#define  WWDG_CR_T5                          ((uint8_t)0x20)               /*!<Bit 5 */
+#define  WWDG_CR_T6                          ((uint8_t)0x40)               /*!<Bit 6 */
+
+#define  WWDG_CR_WDGA                        ((uint8_t)0x80)               /*!<Activation bit */
+
+/*******************  Bit definition for WWDG_CFR register  *******************/
+#define  WWDG_CFR_W                          ((uint16_t)0x007F)            /*!<W[6:0] bits (7-bit window value) */
+#define  WWDG_CFR_W0                         ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  WWDG_CFR_W1                         ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  WWDG_CFR_W2                         ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  WWDG_CFR_W3                         ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  WWDG_CFR_W4                         ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  WWDG_CFR_W5                         ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  WWDG_CFR_W6                         ((uint16_t)0x0040)            /*!<Bit 6 */
+
+#define  WWDG_CFR_WDGTB                      ((uint16_t)0x0180)            /*!<WDGTB[1:0] bits (Timer Base) */
+#define  WWDG_CFR_WDGTB0                     ((uint16_t)0x0080)            /*!<Bit 0 */
+#define  WWDG_CFR_WDGTB1                     ((uint16_t)0x0100)            /*!<Bit 1 */
+
+#define  WWDG_CFR_EWI                        ((uint16_t)0x0200)            /*!<Early Wakeup Interrupt */
+
+/*******************  Bit definition for WWDG_SR register  ********************/
+#define  WWDG_SR_EWIF                        ((uint8_t)0x01)               /*!<Early Wakeup Interrupt Flag */
+
+/******************************************************************************/
+/*                                                                            */
+/*                       Flexible Static Memory Controller                    */
+/*                                                                            */
+/******************************************************************************/
+
+/******************  Bit definition for FSMC_BCR1 register  *******************/
+#define  FSMC_BCR1_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit */
+#define  FSMC_BCR1_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit */
+
+#define  FSMC_BCR1_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type) */
+#define  FSMC_BCR1_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR1_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR1_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR1_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR1_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR1_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable */
+#define  FSMC_BCR1_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit */
+#define  FSMC_BCR1_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit */
+#define  FSMC_BCR1_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FSMC_BCR1_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration */
+#define  FSMC_BCR1_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit */
+#define  FSMC_BCR1_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit */
+#define  FSMC_BCR1_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable */
+#define  FSMC_BCR1_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable */
+
+/******************  Bit definition for FSMC_BCR2 register  *******************/
+#define  FSMC_BCR2_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit */
+#define  FSMC_BCR2_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit */
+
+#define  FSMC_BCR2_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type) */
+#define  FSMC_BCR2_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR2_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR2_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR2_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR2_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR2_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable */
+#define  FSMC_BCR2_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit */
+#define  FSMC_BCR2_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit */
+#define  FSMC_BCR2_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FSMC_BCR2_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration */
+#define  FSMC_BCR2_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit */
+#define  FSMC_BCR2_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit */
+#define  FSMC_BCR2_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable */
+#define  FSMC_BCR2_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable */
+
+/******************  Bit definition for FSMC_BCR3 register  *******************/
+#define  FSMC_BCR3_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit */
+#define  FSMC_BCR3_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit */
+
+#define  FSMC_BCR3_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type) */
+#define  FSMC_BCR3_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR3_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR3_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR3_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR3_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR3_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable */
+#define  FSMC_BCR3_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit */
+#define  FSMC_BCR3_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit. */
+#define  FSMC_BCR3_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FSMC_BCR3_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration */
+#define  FSMC_BCR3_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit */
+#define  FSMC_BCR3_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit */
+#define  FSMC_BCR3_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable */
+#define  FSMC_BCR3_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable */
+
+/******************  Bit definition for FSMC_BCR4 register  *******************/
+#define  FSMC_BCR4_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit */
+#define  FSMC_BCR4_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit */
+
+#define  FSMC_BCR4_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type) */
+#define  FSMC_BCR4_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR4_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR4_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR4_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR4_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR4_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable */
+#define  FSMC_BCR4_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit */
+#define  FSMC_BCR4_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit */
+#define  FSMC_BCR4_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FSMC_BCR4_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration */
+#define  FSMC_BCR4_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit */
+#define  FSMC_BCR4_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit */
+#define  FSMC_BCR4_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable */
+#define  FSMC_BCR4_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable */
+
+/******************  Bit definition for FSMC_BTR1 register  ******************/
+#define  FSMC_BTR1_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR1_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR1_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR1_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR1_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR1_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR1_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR1_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR1_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR1_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR1_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR1_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR1_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR1_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR1_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR1_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR1_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR1_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR1_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR1_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR1_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR1_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR1_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR1_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR1_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR1_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR1_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BTR2 register  *******************/
+#define  FSMC_BTR2_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR2_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR2_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR2_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR2_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR2_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR2_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR2_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR2_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR2_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR2_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR2_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR2_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR2_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR2_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR2_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR2_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR2_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR2_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR2_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR2_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR2_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR2_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR2_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR2_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR2_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR2_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/*******************  Bit definition for FSMC_BTR3 register  *******************/
+#define  FSMC_BTR3_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR3_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR3_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR3_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR3_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR3_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR3_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR3_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR3_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR3_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR3_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR3_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR3_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR3_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR3_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR3_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR3_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR3_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR3_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR3_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR3_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR3_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR3_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR3_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR3_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR3_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR3_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BTR4 register  *******************/
+#define  FSMC_BTR4_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR4_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR4_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR4_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR4_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR4_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR4_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR4_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR4_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR4_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR4_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR4_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR4_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR4_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR4_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR4_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR4_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR4_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR4_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR4_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR4_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR4_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR4_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR4_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR4_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR4_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR4_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR1 register  ******************/
+#define  FSMC_BWTR1_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR1_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR1_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR1_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR1_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR1_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR1_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR1_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR1_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR1_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR1_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR1_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR1_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR1_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR1_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BWTR1_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR1_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR1_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR1_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR1_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR1_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR1_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR1_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR2 register  ******************/
+#define  FSMC_BWTR2_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR2_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR2_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR2_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR2_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR2_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR2_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR2_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR2_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR2_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR2_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR2_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR2_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR2_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR2_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1*/
+#define  FSMC_BWTR2_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR2_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR2_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR2_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR2_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR2_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR2_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR2_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR3 register  ******************/
+#define  FSMC_BWTR3_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR3_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR3_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR3_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR3_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR3_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR3_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR3_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR3_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR3_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR3_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR3_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR3_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR3_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR3_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BWTR3_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR3_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR3_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR3_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR3_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR3_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR3_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR3_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR4 register  ******************/
+#define  FSMC_BWTR4_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR4_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR4_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR4_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR4_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR4_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR4_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR4_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR4_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR4_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR4_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR4_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR4_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR4_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR4_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BWTR4_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR4_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR4_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR4_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR4_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR4_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR4_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR4_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_PCR2 register  *******************/
+#define  FSMC_PCR2_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit */
+#define  FSMC_PCR2_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FSMC_PCR2_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type */
+
+#define  FSMC_PCR2_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FSMC_PCR2_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_PCR2_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_PCR2_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit */
+
+#define  FSMC_PCR2_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay) */
+#define  FSMC_PCR2_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FSMC_PCR2_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FSMC_PCR2_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FSMC_PCR2_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FSMC_PCR2_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay) */
+#define  FSMC_PCR2_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FSMC_PCR2_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FSMC_PCR2_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FSMC_PCR2_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FSMC_PCR2_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[1:0] bits (ECC page size) */
+#define  FSMC_PCR2_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FSMC_PCR2_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FSMC_PCR2_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/******************  Bit definition for FSMC_PCR3 register  *******************/
+#define  FSMC_PCR3_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit */
+#define  FSMC_PCR3_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FSMC_PCR3_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type */
+
+#define  FSMC_PCR3_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FSMC_PCR3_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_PCR3_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_PCR3_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit */
+
+#define  FSMC_PCR3_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay) */
+#define  FSMC_PCR3_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FSMC_PCR3_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FSMC_PCR3_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FSMC_PCR3_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FSMC_PCR3_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay) */
+#define  FSMC_PCR3_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FSMC_PCR3_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FSMC_PCR3_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FSMC_PCR3_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FSMC_PCR3_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[2:0] bits (ECC page size) */
+#define  FSMC_PCR3_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FSMC_PCR3_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FSMC_PCR3_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/******************  Bit definition for FSMC_PCR4 register  *******************/
+#define  FSMC_PCR4_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit */
+#define  FSMC_PCR4_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FSMC_PCR4_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type */
+
+#define  FSMC_PCR4_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FSMC_PCR4_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_PCR4_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_PCR4_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit */
+
+#define  FSMC_PCR4_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay) */
+#define  FSMC_PCR4_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FSMC_PCR4_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FSMC_PCR4_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FSMC_PCR4_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FSMC_PCR4_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay) */
+#define  FSMC_PCR4_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FSMC_PCR4_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FSMC_PCR4_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FSMC_PCR4_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FSMC_PCR4_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[2:0] bits (ECC page size) */
+#define  FSMC_PCR4_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FSMC_PCR4_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FSMC_PCR4_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/*******************  Bit definition for FSMC_SR2 register  *******************/
+#define  FSMC_SR2_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status */
+#define  FSMC_SR2_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status */
+#define  FSMC_SR2_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status */
+#define  FSMC_SR2_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit */
+#define  FSMC_SR2_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit */
+#define  FSMC_SR2_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FSMC_SR2_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty */
+
+/*******************  Bit definition for FSMC_SR3 register  *******************/
+#define  FSMC_SR3_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status */
+#define  FSMC_SR3_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status */
+#define  FSMC_SR3_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status */
+#define  FSMC_SR3_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit */
+#define  FSMC_SR3_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit */
+#define  FSMC_SR3_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FSMC_SR3_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty */
+
+/*******************  Bit definition for FSMC_SR4 register  *******************/
+#define  FSMC_SR4_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status */
+#define  FSMC_SR4_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status */
+#define  FSMC_SR4_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status */
+#define  FSMC_SR4_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit */
+#define  FSMC_SR4_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit */
+#define  FSMC_SR4_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FSMC_SR4_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty */
+
+/******************  Bit definition for FSMC_PMEM2 register  ******************/
+#define  FSMC_PMEM2_MEMSET2                  ((uint32_t)0x000000FF)        /*!<MEMSET2[7:0] bits (Common memory 2 setup time) */
+#define  FSMC_PMEM2_MEMSET2_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMSET2_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMSET2_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMSET2_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMSET2_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMSET2_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMSET2_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMSET2_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PMEM2_MEMWAIT2                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT2[7:0] bits (Common memory 2 wait time) */
+#define  FSMC_PMEM2_MEMWAIT2_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMWAIT2_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMWAIT2_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMWAIT2_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMWAIT2_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMWAIT2_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMWAIT2_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMWAIT2_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM2_MEMHOLD2                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD2[7:0] bits (Common memory 2 hold time) */
+#define  FSMC_PMEM2_MEMHOLD2_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMHOLD2_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMHOLD2_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMHOLD2_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMHOLD2_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMHOLD2_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMHOLD2_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMHOLD2_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM2_MEMHIZ2                  ((uint32_t)0xFF000000)        /*!<MEMHIZ2[7:0] bits (Common memory 2 databus HiZ time) */
+#define  FSMC_PMEM2_MEMHIZ2_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMHIZ2_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMHIZ2_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMHIZ2_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMHIZ2_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMHIZ2_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMHIZ2_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMHIZ2_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PMEM3 register  ******************/
+#define  FSMC_PMEM3_MEMSET3                  ((uint32_t)0x000000FF)        /*!<MEMSET3[7:0] bits (Common memory 3 setup time) */
+#define  FSMC_PMEM3_MEMSET3_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMSET3_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMSET3_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMSET3_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMSET3_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMSET3_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMSET3_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMSET3_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PMEM3_MEMWAIT3                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT3[7:0] bits (Common memory 3 wait time) */
+#define  FSMC_PMEM3_MEMWAIT3_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMWAIT3_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMWAIT3_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMWAIT3_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMWAIT3_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMWAIT3_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMWAIT3_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMWAIT3_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM3_MEMHOLD3                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD3[7:0] bits (Common memory 3 hold time) */
+#define  FSMC_PMEM3_MEMHOLD3_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMHOLD3_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMHOLD3_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMHOLD3_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMHOLD3_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMHOLD3_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMHOLD3_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMHOLD3_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM3_MEMHIZ3                  ((uint32_t)0xFF000000)        /*!<MEMHIZ3[7:0] bits (Common memory 3 databus HiZ time) */
+#define  FSMC_PMEM3_MEMHIZ3_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMHIZ3_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMHIZ3_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMHIZ3_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMHIZ3_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMHIZ3_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMHIZ3_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMHIZ3_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PMEM4 register  ******************/
+#define  FSMC_PMEM4_MEMSET4                  ((uint32_t)0x000000FF)        /*!<MEMSET4[7:0] bits (Common memory 4 setup time) */
+#define  FSMC_PMEM4_MEMSET4_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMSET4_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMSET4_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMSET4_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMSET4_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMSET4_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMSET4_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMSET4_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PMEM4_MEMWAIT4                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT4[7:0] bits (Common memory 4 wait time) */
+#define  FSMC_PMEM4_MEMWAIT4_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMWAIT4_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMWAIT4_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMWAIT4_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMWAIT4_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMWAIT4_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMWAIT4_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMWAIT4_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM4_MEMHOLD4                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD4[7:0] bits (Common memory 4 hold time) */
+#define  FSMC_PMEM4_MEMHOLD4_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMHOLD4_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMHOLD4_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMHOLD4_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMHOLD4_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMHOLD4_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMHOLD4_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMHOLD4_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM4_MEMHIZ4                  ((uint32_t)0xFF000000)        /*!<MEMHIZ4[7:0] bits (Common memory 4 databus HiZ time) */
+#define  FSMC_PMEM4_MEMHIZ4_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMHIZ4_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMHIZ4_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMHIZ4_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMHIZ4_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMHIZ4_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMHIZ4_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMHIZ4_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PATT2 register  ******************/
+#define  FSMC_PATT2_ATTSET2                  ((uint32_t)0x000000FF)        /*!<ATTSET2[7:0] bits (Attribute memory 2 setup time) */
+#define  FSMC_PATT2_ATTSET2_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTSET2_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTSET2_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTSET2_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTSET2_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTSET2_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTSET2_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTSET2_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PATT2_ATTWAIT2                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT2[7:0] bits (Attribute memory 2 wait time) */
+#define  FSMC_PATT2_ATTWAIT2_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTWAIT2_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTWAIT2_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTWAIT2_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTWAIT2_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTWAIT2_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTWAIT2_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTWAIT2_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PATT2_ATTHOLD2                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD2[7:0] bits (Attribute memory 2 hold time) */
+#define  FSMC_PATT2_ATTHOLD2_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTHOLD2_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTHOLD2_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTHOLD2_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTHOLD2_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTHOLD2_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTHOLD2_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTHOLD2_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PATT2_ATTHIZ2                  ((uint32_t)0xFF000000)        /*!<ATTHIZ2[7:0] bits (Attribute memory 2 databus HiZ time) */
+#define  FSMC_PATT2_ATTHIZ2_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTHIZ2_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTHIZ2_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTHIZ2_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTHIZ2_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTHIZ2_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTHIZ2_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTHIZ2_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PATT3 register  ******************/
+#define  FSMC_PATT3_ATTSET3                  ((uint32_t)0x000000FF)        /*!<ATTSET3[7:0] bits (Attribute memory 3 setup time) */
+#define  FSMC_PATT3_ATTSET3_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTSET3_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTSET3_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTSET3_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTSET3_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTSET3_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTSET3_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTSET3_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PATT3_ATTWAIT3                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT3[7:0] bits (Attribute memory 3 wait time) */
+#define  FSMC_PATT3_ATTWAIT3_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTWAIT3_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTWAIT3_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTWAIT3_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTWAIT3_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTWAIT3_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTWAIT3_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTWAIT3_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PATT3_ATTHOLD3                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD3[7:0] bits (Attribute memory 3 hold time) */
+#define  FSMC_PATT3_ATTHOLD3_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTHOLD3_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTHOLD3_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTHOLD3_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTHOLD3_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTHOLD3_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTHOLD3_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTHOLD3_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PATT3_ATTHIZ3                  ((uint32_t)0xFF000000)        /*!<ATTHIZ3[7:0] bits (Attribute memory 3 databus HiZ time) */
+#define  FSMC_PATT3_ATTHIZ3_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTHIZ3_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTHIZ3_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTHIZ3_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTHIZ3_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTHIZ3_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTHIZ3_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTHIZ3_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PATT4 register  ******************/
+#define  FSMC_PATT4_ATTSET4                  ((uint32_t)0x000000FF)        /*!<ATTSET4[7:0] bits (Attribute memory 4 setup time) */
+#define  FSMC_PATT4_ATTSET4_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTSET4_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTSET4_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTSET4_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTSET4_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTSET4_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTSET4_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTSET4_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PATT4_ATTWAIT4                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT4[7:0] bits (Attribute memory 4 wait time) */
+#define  FSMC_PATT4_ATTWAIT4_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTWAIT4_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTWAIT4_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTWAIT4_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTWAIT4_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTWAIT4_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTWAIT4_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTWAIT4_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PATT4_ATTHOLD4                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD4[7:0] bits (Attribute memory 4 hold time) */
+#define  FSMC_PATT4_ATTHOLD4_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTHOLD4_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTHOLD4_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTHOLD4_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTHOLD4_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTHOLD4_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTHOLD4_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTHOLD4_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PATT4_ATTHIZ4                  ((uint32_t)0xFF000000)        /*!<ATTHIZ4[7:0] bits (Attribute memory 4 databus HiZ time) */
+#define  FSMC_PATT4_ATTHIZ4_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTHIZ4_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTHIZ4_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTHIZ4_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTHIZ4_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTHIZ4_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTHIZ4_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTHIZ4_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PIO4 register  *******************/
+#define  FSMC_PIO4_IOSET4                    ((uint32_t)0x000000FF)        /*!<IOSET4[7:0] bits (I/O 4 setup time) */
+#define  FSMC_PIO4_IOSET4_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOSET4_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOSET4_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOSET4_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOSET4_4                  ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOSET4_5                  ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOSET4_6                  ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOSET4_7                  ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PIO4_IOWAIT4                   ((uint32_t)0x0000FF00)        /*!<IOWAIT4[7:0] bits (I/O 4 wait time) */
+#define  FSMC_PIO4_IOWAIT4_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOWAIT4_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOWAIT4_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOWAIT4_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOWAIT4_4                 ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOWAIT4_5                 ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOWAIT4_6                 ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOWAIT4_7                 ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PIO4_IOHOLD4                   ((uint32_t)0x00FF0000)        /*!<IOHOLD4[7:0] bits (I/O 4 hold time) */
+#define  FSMC_PIO4_IOHOLD4_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOHOLD4_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOHOLD4_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOHOLD4_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOHOLD4_4                 ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOHOLD4_5                 ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOHOLD4_6                 ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOHOLD4_7                 ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PIO4_IOHIZ4                    ((uint32_t)0xFF000000)        /*!<IOHIZ4[7:0] bits (I/O 4 databus HiZ time) */
+#define  FSMC_PIO4_IOHIZ4_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOHIZ4_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOHIZ4_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOHIZ4_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOHIZ4_4                  ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOHIZ4_5                  ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOHIZ4_6                  ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOHIZ4_7                  ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_ECCR2 register  ******************/
+#define  FSMC_ECCR2_ECC2                     ((uint32_t)0xFFFFFFFF)        /*!<ECC result */
+
+/******************  Bit definition for FSMC_ECCR3 register  ******************/
+#define  FSMC_ECCR3_ECC3                     ((uint32_t)0xFFFFFFFF)        /*!<ECC result */
+
+/******************************************************************************/
+/*                                                                            */
+/*                          SD host Interface                                 */
+/*                                                                            */
+/******************************************************************************/
+
+/******************  Bit definition for SDIO_POWER register  ******************/
+#define  SDIO_POWER_PWRCTRL                  ((uint8_t)0x03)               /*!<PWRCTRL[1:0] bits (Power supply control bits) */
+#define  SDIO_POWER_PWRCTRL_0                ((uint8_t)0x01)               /*!<Bit 0 */
+#define  SDIO_POWER_PWRCTRL_1                ((uint8_t)0x02)               /*!<Bit 1 */
+
+/******************  Bit definition for SDIO_CLKCR register  ******************/
+#define  SDIO_CLKCR_CLKDIV                   ((uint16_t)0x00FF)            /*!<Clock divide factor */
+#define  SDIO_CLKCR_CLKEN                    ((uint16_t)0x0100)            /*!<Clock enable bit */
+#define  SDIO_CLKCR_PWRSAV                   ((uint16_t)0x0200)            /*!<Power saving configuration bit */
+#define  SDIO_CLKCR_BYPASS                   ((uint16_t)0x0400)            /*!<Clock divider bypass enable bit */
+
+#define  SDIO_CLKCR_WIDBUS                   ((uint16_t)0x1800)            /*!<WIDBUS[1:0] bits (Wide bus mode enable bit) */
+#define  SDIO_CLKCR_WIDBUS_0                 ((uint16_t)0x0800)            /*!<Bit 0 */
+#define  SDIO_CLKCR_WIDBUS_1                 ((uint16_t)0x1000)            /*!<Bit 1 */
+
+#define  SDIO_CLKCR_NEGEDGE                  ((uint16_t)0x2000)            /*!<SDIO_CK dephasing selection bit */
+#define  SDIO_CLKCR_HWFC_EN                  ((uint16_t)0x4000)            /*!<HW Flow Control enable */
+
+/*******************  Bit definition for SDIO_ARG register  *******************/
+#define  SDIO_ARG_CMDARG                     ((uint32_t)0xFFFFFFFF)            /*!<Command argument */
+
+/*******************  Bit definition for SDIO_CMD register  *******************/
+#define  SDIO_CMD_CMDINDEX                   ((uint16_t)0x003F)            /*!<Command Index */
+
+#define  SDIO_CMD_WAITRESP                   ((uint16_t)0x00C0)            /*!<WAITRESP[1:0] bits (Wait for response bits) */
+#define  SDIO_CMD_WAITRESP_0                 ((uint16_t)0x0040)            /*!< Bit 0 */
+#define  SDIO_CMD_WAITRESP_1                 ((uint16_t)0x0080)            /*!< Bit 1 */
+
+#define  SDIO_CMD_WAITINT                    ((uint16_t)0x0100)            /*!<CPSM Waits for Interrupt Request */
+#define  SDIO_CMD_WAITPEND                   ((uint16_t)0x0200)            /*!<CPSM Waits for ends of data transfer (CmdPend internal signal) */
+#define  SDIO_CMD_CPSMEN                     ((uint16_t)0x0400)            /*!<Command path state machine (CPSM) Enable bit */
+#define  SDIO_CMD_SDIOSUSPEND                ((uint16_t)0x0800)            /*!<SD I/O suspend command */
+#define  SDIO_CMD_ENCMDCOMPL                 ((uint16_t)0x1000)            /*!<Enable CMD completion */
+#define  SDIO_CMD_NIEN                       ((uint16_t)0x2000)            /*!<Not Interrupt Enable */
+#define  SDIO_CMD_CEATACMD                   ((uint16_t)0x4000)            /*!<CE-ATA command */
+
+/*****************  Bit definition for SDIO_RESPCMD register  *****************/
+#define  SDIO_RESPCMD_RESPCMD                ((uint8_t)0x3F)               /*!<Response command index */
+
+/******************  Bit definition for SDIO_RESP0 register  ******************/
+#define  SDIO_RESP0_CARDSTATUS0              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP1 register  ******************/
+#define  SDIO_RESP1_CARDSTATUS1              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP2 register  ******************/
+#define  SDIO_RESP2_CARDSTATUS2              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP3 register  ******************/
+#define  SDIO_RESP3_CARDSTATUS3              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP4 register  ******************/
+#define  SDIO_RESP4_CARDSTATUS4              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_DTIMER register  *****************/
+#define  SDIO_DTIMER_DATATIME                ((uint32_t)0xFFFFFFFF)        /*!<Data timeout period. */
+
+/******************  Bit definition for SDIO_DLEN register  *******************/
+#define  SDIO_DLEN_DATALENGTH                ((uint32_t)0x01FFFFFF)        /*!<Data length value */
+
+/******************  Bit definition for SDIO_DCTRL register  ******************/
+#define  SDIO_DCTRL_DTEN                     ((uint16_t)0x0001)            /*!<Data transfer enabled bit */
+#define  SDIO_DCTRL_DTDIR                    ((uint16_t)0x0002)            /*!<Data transfer direction selection */
+#define  SDIO_DCTRL_DTMODE                   ((uint16_t)0x0004)            /*!<Data transfer mode selection */
+#define  SDIO_DCTRL_DMAEN                    ((uint16_t)0x0008)            /*!<DMA enabled bit */
+
+#define  SDIO_DCTRL_DBLOCKSIZE               ((uint16_t)0x00F0)            /*!<DBLOCKSIZE[3:0] bits (Data block size) */
+#define  SDIO_DCTRL_DBLOCKSIZE_0             ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  SDIO_DCTRL_DBLOCKSIZE_1             ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  SDIO_DCTRL_DBLOCKSIZE_2             ((uint16_t)0x0040)            /*!<Bit 2 */
+#define  SDIO_DCTRL_DBLOCKSIZE_3             ((uint16_t)0x0080)            /*!<Bit 3 */
+
+#define  SDIO_DCTRL_RWSTART                  ((uint16_t)0x0100)            /*!<Read wait start */
+#define  SDIO_DCTRL_RWSTOP                   ((uint16_t)0x0200)            /*!<Read wait stop */
+#define  SDIO_DCTRL_RWMOD                    ((uint16_t)0x0400)            /*!<Read wait mode */
+#define  SDIO_DCTRL_SDIOEN                   ((uint16_t)0x0800)            /*!<SD I/O enable functions */
+
+/******************  Bit definition for SDIO_DCOUNT register  *****************/
+#define  SDIO_DCOUNT_DATACOUNT               ((uint32_t)0x01FFFFFF)        /*!<Data count value */
+
+/******************  Bit definition for SDIO_STA register  ********************/
+#define  SDIO_STA_CCRCFAIL                   ((uint32_t)0x00000001)        /*!<Command response received (CRC check failed) */
+#define  SDIO_STA_DCRCFAIL                   ((uint32_t)0x00000002)        /*!<Data block sent/received (CRC check failed) */
+#define  SDIO_STA_CTIMEOUT                   ((uint32_t)0x00000004)        /*!<Command response timeout */
+#define  SDIO_STA_DTIMEOUT                   ((uint32_t)0x00000008)        /*!<Data timeout */
+#define  SDIO_STA_TXUNDERR                   ((uint32_t)0x00000010)        /*!<Transmit FIFO underrun error */
+#define  SDIO_STA_RXOVERR                    ((uint32_t)0x00000020)        /*!<Received FIFO overrun error */
+#define  SDIO_STA_CMDREND                    ((uint32_t)0x00000040)        /*!<Command response received (CRC check passed) */
+#define  SDIO_STA_CMDSENT                    ((uint32_t)0x00000080)        /*!<Command sent (no response required) */
+#define  SDIO_STA_DATAEND                    ((uint32_t)0x00000100)        /*!<Data end (data counter, SDIDCOUNT, is zero) */
+#define  SDIO_STA_STBITERR                   ((uint32_t)0x00000200)        /*!<Start bit not detected on all data signals in wide bus mode */
+#define  SDIO_STA_DBCKEND                    ((uint32_t)0x00000400)        /*!<Data block sent/received (CRC check passed) */
+#define  SDIO_STA_CMDACT                     ((uint32_t)0x00000800)        /*!<Command transfer in progress */
+#define  SDIO_STA_TXACT                      ((uint32_t)0x00001000)        /*!<Data transmit in progress */
+#define  SDIO_STA_RXACT                      ((uint32_t)0x00002000)        /*!<Data receive in progress */
+#define  SDIO_STA_TXFIFOHE                   ((uint32_t)0x00004000)        /*!<Transmit FIFO Half Empty: at least 8 words can be written into the FIFO */
+#define  SDIO_STA_RXFIFOHF                   ((uint32_t)0x00008000)        /*!<Receive FIFO Half Full: there are at least 8 words in the FIFO */
+#define  SDIO_STA_TXFIFOF                    ((uint32_t)0x00010000)        /*!<Transmit FIFO full */
+#define  SDIO_STA_RXFIFOF                    ((uint32_t)0x00020000)        /*!<Receive FIFO full */
+#define  SDIO_STA_TXFIFOE                    ((uint32_t)0x00040000)        /*!<Transmit FIFO empty */
+#define  SDIO_STA_RXFIFOE                    ((uint32_t)0x00080000)        /*!<Receive FIFO empty */
+#define  SDIO_STA_TXDAVL                     ((uint32_t)0x00100000)        /*!<Data available in transmit FIFO */
+#define  SDIO_STA_RXDAVL                     ((uint32_t)0x00200000)        /*!<Data available in receive FIFO */
+#define  SDIO_STA_SDIOIT                     ((uint32_t)0x00400000)        /*!<SDIO interrupt received */
+#define  SDIO_STA_CEATAEND                   ((uint32_t)0x00800000)        /*!<CE-ATA command completion signal received for CMD61 */
+
+/*******************  Bit definition for SDIO_ICR register  *******************/
+#define  SDIO_ICR_CCRCFAILC                  ((uint32_t)0x00000001)        /*!<CCRCFAIL flag clear bit */
+#define  SDIO_ICR_DCRCFAILC                  ((uint32_t)0x00000002)        /*!<DCRCFAIL flag clear bit */
+#define  SDIO_ICR_CTIMEOUTC                  ((uint32_t)0x00000004)        /*!<CTIMEOUT flag clear bit */
+#define  SDIO_ICR_DTIMEOUTC                  ((uint32_t)0x00000008)        /*!<DTIMEOUT flag clear bit */
+#define  SDIO_ICR_TXUNDERRC                  ((uint32_t)0x00000010)        /*!<TXUNDERR flag clear bit */
+#define  SDIO_ICR_RXOVERRC                   ((uint32_t)0x00000020)        /*!<RXOVERR flag clear bit */
+#define  SDIO_ICR_CMDRENDC                   ((uint32_t)0x00000040)        /*!<CMDREND flag clear bit */
+#define  SDIO_ICR_CMDSENTC                   ((uint32_t)0x00000080)        /*!<CMDSENT flag clear bit */
+#define  SDIO_ICR_DATAENDC                   ((uint32_t)0x00000100)        /*!<DATAEND flag clear bit */
+#define  SDIO_ICR_STBITERRC                  ((uint32_t)0x00000200)        /*!<STBITERR flag clear bit */
+#define  SDIO_ICR_DBCKENDC                   ((uint32_t)0x00000400)        /*!<DBCKEND flag clear bit */
+#define  SDIO_ICR_SDIOITC                    ((uint32_t)0x00400000)        /*!<SDIOIT flag clear bit */
+#define  SDIO_ICR_CEATAENDC                  ((uint32_t)0x00800000)        /*!<CEATAEND flag clear bit */
+
+/******************  Bit definition for SDIO_MASK register  *******************/
+#define  SDIO_MASK_CCRCFAILIE                ((uint32_t)0x00000001)        /*!<Command CRC Fail Interrupt Enable */
+#define  SDIO_MASK_DCRCFAILIE                ((uint32_t)0x00000002)        /*!<Data CRC Fail Interrupt Enable */
+#define  SDIO_MASK_CTIMEOUTIE                ((uint32_t)0x00000004)        /*!<Command TimeOut Interrupt Enable */
+#define  SDIO_MASK_DTIMEOUTIE                ((uint32_t)0x00000008)        /*!<Data TimeOut Interrupt Enable */
+#define  SDIO_MASK_TXUNDERRIE                ((uint32_t)0x00000010)        /*!<Tx FIFO UnderRun Error Interrupt Enable */
+#define  SDIO_MASK_RXOVERRIE                 ((uint32_t)0x00000020)        /*!<Rx FIFO OverRun Error Interrupt Enable */
+#define  SDIO_MASK_CMDRENDIE                 ((uint32_t)0x00000040)        /*!<Command Response Received Interrupt Enable */
+#define  SDIO_MASK_CMDSENTIE                 ((uint32_t)0x00000080)        /*!<Command Sent Interrupt Enable */
+#define  SDIO_MASK_DATAENDIE                 ((uint32_t)0x00000100)        /*!<Data End Interrupt Enable */
+#define  SDIO_MASK_STBITERRIE                ((uint32_t)0x00000200)        /*!<Start Bit Error Interrupt Enable */
+#define  SDIO_MASK_DBCKENDIE                 ((uint32_t)0x00000400)        /*!<Data Block End Interrupt Enable */
+#define  SDIO_MASK_CMDACTIE                  ((uint32_t)0x00000800)        /*!<CCommand Acting Interrupt Enable */
+#define  SDIO_MASK_TXACTIE                   ((uint32_t)0x00001000)        /*!<Data Transmit Acting Interrupt Enable */
+#define  SDIO_MASK_RXACTIE                   ((uint32_t)0x00002000)        /*!<Data receive acting interrupt enabled */
+#define  SDIO_MASK_TXFIFOHEIE                ((uint32_t)0x00004000)        /*!<Tx FIFO Half Empty interrupt Enable */
+#define  SDIO_MASK_RXFIFOHFIE                ((uint32_t)0x00008000)        /*!<Rx FIFO Half Full interrupt Enable */
+#define  SDIO_MASK_TXFIFOFIE                 ((uint32_t)0x00010000)        /*!<Tx FIFO Full interrupt Enable */
+#define  SDIO_MASK_RXFIFOFIE                 ((uint32_t)0x00020000)        /*!<Rx FIFO Full interrupt Enable */
+#define  SDIO_MASK_TXFIFOEIE                 ((uint32_t)0x00040000)        /*!<Tx FIFO Empty interrupt Enable */
+#define  SDIO_MASK_RXFIFOEIE                 ((uint32_t)0x00080000)        /*!<Rx FIFO Empty interrupt Enable */
+#define  SDIO_MASK_TXDAVLIE                  ((uint32_t)0x00100000)        /*!<Data available in Tx FIFO interrupt Enable */
+#define  SDIO_MASK_RXDAVLIE                  ((uint32_t)0x00200000)        /*!<Data available in Rx FIFO interrupt Enable */
+#define  SDIO_MASK_SDIOITIE                  ((uint32_t)0x00400000)        /*!<SDIO Mode Interrupt Received interrupt Enable */
+#define  SDIO_MASK_CEATAENDIE                ((uint32_t)0x00800000)        /*!<CE-ATA command completion signal received Interrupt Enable */
+
+/*****************  Bit definition for SDIO_FIFOCNT register  *****************/
+#define  SDIO_FIFOCNT_FIFOCOUNT              ((uint32_t)0x00FFFFFF)        /*!<Remaining number of words to be written to or read from the FIFO */
+
+/******************  Bit definition for SDIO_FIFO register  *******************/
+#define  SDIO_FIFO_FIFODATA                  ((uint32_t)0xFFFFFFFF)        /*!<Receive and transmit FIFO data */
+
+/******************************************************************************/
+/*                                                                            */
+/*                                   USB Device FS                            */
+/*                                                                            */
+/******************************************************************************/
+
+/*!<Endpoint-specific registers */
+/*******************  Bit definition for USB_EP0R register  *******************/
+#define  USB_EP0R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP0R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP0R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP0R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP0R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP0R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP0R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP0R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP0R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP0R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP0R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP0R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP0R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP0R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP0R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP0R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*******************  Bit definition for USB_EP1R register  *******************/
+#define  USB_EP1R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP1R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP1R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP1R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP1R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP1R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP1R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP1R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP1R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP1R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP1R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP1R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP1R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP1R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP1R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP1R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*******************  Bit definition for USB_EP2R register  *******************/
+#define  USB_EP2R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP2R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP2R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP2R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP2R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP2R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP2R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP2R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP2R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP2R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP2R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP2R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP2R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP2R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP2R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP2R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*******************  Bit definition for USB_EP3R register  *******************/
+#define  USB_EP3R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP3R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP3R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP3R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP3R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP3R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP3R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP3R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP3R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP3R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP3R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP3R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP3R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP3R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP3R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP3R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*******************  Bit definition for USB_EP4R register  *******************/
+#define  USB_EP4R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP4R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP4R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP4R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP4R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP4R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP4R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP4R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP4R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP4R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP4R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP4R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP4R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP4R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP4R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP4R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*******************  Bit definition for USB_EP5R register  *******************/
+#define  USB_EP5R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP5R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP5R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP5R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP5R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP5R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP5R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP5R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP5R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP5R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP5R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP5R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP5R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP5R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP5R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP5R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*******************  Bit definition for USB_EP6R register  *******************/
+#define  USB_EP6R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP6R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP6R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP6R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP6R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP6R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP6R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP6R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP6R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP6R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP6R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP6R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP6R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP6R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP6R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP6R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*******************  Bit definition for USB_EP7R register  *******************/
+#define  USB_EP7R_EA                         ((uint16_t)0x000F)            /*!<Endpoint Address */
+
+#define  USB_EP7R_STAT_TX                    ((uint16_t)0x0030)            /*!<STAT_TX[1:0] bits (Status bits, for transmission transfers) */
+#define  USB_EP7R_STAT_TX_0                  ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  USB_EP7R_STAT_TX_1                  ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  USB_EP7R_DTOG_TX                    ((uint16_t)0x0040)            /*!<Data Toggle, for transmission transfers */
+#define  USB_EP7R_CTR_TX                     ((uint16_t)0x0080)            /*!<Correct Transfer for transmission */
+#define  USB_EP7R_EP_KIND                    ((uint16_t)0x0100)            /*!<Endpoint Kind */
+
+#define  USB_EP7R_EP_TYPE                    ((uint16_t)0x0600)            /*!<EP_TYPE[1:0] bits (Endpoint type) */
+#define  USB_EP7R_EP_TYPE_0                  ((uint16_t)0x0200)            /*!<Bit 0 */
+#define  USB_EP7R_EP_TYPE_1                  ((uint16_t)0x0400)            /*!<Bit 1 */
+
+#define  USB_EP7R_SETUP                      ((uint16_t)0x0800)            /*!<Setup transaction completed */
+
+#define  USB_EP7R_STAT_RX                    ((uint16_t)0x3000)            /*!<STAT_RX[1:0] bits (Status bits, for reception transfers) */
+#define  USB_EP7R_STAT_RX_0                  ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USB_EP7R_STAT_RX_1                  ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USB_EP7R_DTOG_RX                    ((uint16_t)0x4000)            /*!<Data Toggle, for reception transfers */
+#define  USB_EP7R_CTR_RX                     ((uint16_t)0x8000)            /*!<Correct Transfer for reception */
+
+/*!<Common registers */
+/*******************  Bit definition for USB_CNTR register  *******************/
+#define  USB_CNTR_FRES                       ((uint16_t)0x0001)            /*!<Force USB Reset */
+#define  USB_CNTR_PDWN                       ((uint16_t)0x0002)            /*!<Power down */
+#define  USB_CNTR_LP_MODE                    ((uint16_t)0x0004)            /*!<Low-power mode */
+#define  USB_CNTR_FSUSP                      ((uint16_t)0x0008)            /*!<Force suspend */
+#define  USB_CNTR_RESUME                     ((uint16_t)0x0010)            /*!<Resume request */
+#define  USB_CNTR_ESOFM                      ((uint16_t)0x0100)            /*!<Expected Start Of Frame Interrupt Mask */
+#define  USB_CNTR_SOFM                       ((uint16_t)0x0200)            /*!<Start Of Frame Interrupt Mask */
+#define  USB_CNTR_RESETM                     ((uint16_t)0x0400)            /*!<RESET Interrupt Mask */
+#define  USB_CNTR_SUSPM                      ((uint16_t)0x0800)            /*!<Suspend mode Interrupt Mask */
+#define  USB_CNTR_WKUPM                      ((uint16_t)0x1000)            /*!<Wakeup Interrupt Mask */
+#define  USB_CNTR_ERRM                       ((uint16_t)0x2000)            /*!<Error Interrupt Mask */
+#define  USB_CNTR_PMAOVRM                    ((uint16_t)0x4000)            /*!<Packet Memory Area Over / Underrun Interrupt Mask */
+#define  USB_CNTR_CTRM                       ((uint16_t)0x8000)            /*!<Correct Transfer Interrupt Mask */
+
+/*******************  Bit definition for USB_ISTR register  *******************/
+#define  USB_ISTR_EP_ID                      ((uint16_t)0x000F)            /*!<Endpoint Identifier */
+#define  USB_ISTR_DIR                        ((uint16_t)0x0010)            /*!<Direction of transaction */
+#define  USB_ISTR_ESOF                       ((uint16_t)0x0100)            /*!<Expected Start Of Frame */
+#define  USB_ISTR_SOF                        ((uint16_t)0x0200)            /*!<Start Of Frame */
+#define  USB_ISTR_RESET                      ((uint16_t)0x0400)            /*!<USB RESET request */
+#define  USB_ISTR_SUSP                       ((uint16_t)0x0800)            /*!<Suspend mode request */
+#define  USB_ISTR_WKUP                       ((uint16_t)0x1000)            /*!<Wake up */
+#define  USB_ISTR_ERR                        ((uint16_t)0x2000)            /*!<Error */
+#define  USB_ISTR_PMAOVR                     ((uint16_t)0x4000)            /*!<Packet Memory Area Over / Underrun */
+#define  USB_ISTR_CTR                        ((uint16_t)0x8000)            /*!<Correct Transfer */
+
+/*******************  Bit definition for USB_FNR register  ********************/
+#define  USB_FNR_FN                          ((uint16_t)0x07FF)            /*!<Frame Number */
+#define  USB_FNR_LSOF                        ((uint16_t)0x1800)            /*!<Lost SOF */
+#define  USB_FNR_LCK                         ((uint16_t)0x2000)            /*!<Locked */
+#define  USB_FNR_RXDM                        ((uint16_t)0x4000)            /*!<Receive Data - Line Status */
+#define  USB_FNR_RXDP                        ((uint16_t)0x8000)            /*!<Receive Data + Line Status */
+
+/******************  Bit definition for USB_DADDR register  *******************/
+#define  USB_DADDR_ADD                       ((uint8_t)0x7F)               /*!<ADD[6:0] bits (Device Address) */
+#define  USB_DADDR_ADD0                      ((uint8_t)0x01)               /*!<Bit 0 */
+#define  USB_DADDR_ADD1                      ((uint8_t)0x02)               /*!<Bit 1 */
+#define  USB_DADDR_ADD2                      ((uint8_t)0x04)               /*!<Bit 2 */
+#define  USB_DADDR_ADD3                      ((uint8_t)0x08)               /*!<Bit 3 */
+#define  USB_DADDR_ADD4                      ((uint8_t)0x10)               /*!<Bit 4 */
+#define  USB_DADDR_ADD5                      ((uint8_t)0x20)               /*!<Bit 5 */
+#define  USB_DADDR_ADD6                      ((uint8_t)0x40)               /*!<Bit 6 */
+
+#define  USB_DADDR_EF                        ((uint8_t)0x80)               /*!<Enable Function */
+
+/******************  Bit definition for USB_BTABLE register  ******************/    
+#define  USB_BTABLE_BTABLE                   ((uint16_t)0xFFF8)            /*!<Buffer Table */
+
+/*!<Buffer descriptor table */
+/*****************  Bit definition for USB_ADDR0_TX register  *****************/
+#define  USB_ADDR0_TX_ADDR0_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 0 */
+
+/*****************  Bit definition for USB_ADDR1_TX register  *****************/
+#define  USB_ADDR1_TX_ADDR1_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 1 */
+
+/*****************  Bit definition for USB_ADDR2_TX register  *****************/
+#define  USB_ADDR2_TX_ADDR2_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 2 */
+
+/*****************  Bit definition for USB_ADDR3_TX register  *****************/
+#define  USB_ADDR3_TX_ADDR3_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 3 */
+
+/*****************  Bit definition for USB_ADDR4_TX register  *****************/
+#define  USB_ADDR4_TX_ADDR4_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 4 */
+
+/*****************  Bit definition for USB_ADDR5_TX register  *****************/
+#define  USB_ADDR5_TX_ADDR5_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 5 */
+
+/*****************  Bit definition for USB_ADDR6_TX register  *****************/
+#define  USB_ADDR6_TX_ADDR6_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 6 */
+
+/*****************  Bit definition for USB_ADDR7_TX register  *****************/
+#define  USB_ADDR7_TX_ADDR7_TX               ((uint16_t)0xFFFE)            /*!<Transmission Buffer Address 7 */
+
+/*----------------------------------------------------------------------------*/
+
+/*****************  Bit definition for USB_COUNT0_TX register  ****************/
+#define  USB_COUNT0_TX_COUNT0_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 0 */
+
+/*****************  Bit definition for USB_COUNT1_TX register  ****************/
+#define  USB_COUNT1_TX_COUNT1_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 1 */
+
+/*****************  Bit definition for USB_COUNT2_TX register  ****************/
+#define  USB_COUNT2_TX_COUNT2_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 2 */
+
+/*****************  Bit definition for USB_COUNT3_TX register  ****************/
+#define  USB_COUNT3_TX_COUNT3_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 3 */
+
+/*****************  Bit definition for USB_COUNT4_TX register  ****************/
+#define  USB_COUNT4_TX_COUNT4_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 4 */
+
+/*****************  Bit definition for USB_COUNT5_TX register  ****************/
+#define  USB_COUNT5_TX_COUNT5_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 5 */
+
+/*****************  Bit definition for USB_COUNT6_TX register  ****************/
+#define  USB_COUNT6_TX_COUNT6_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 6 */
+
+/*****************  Bit definition for USB_COUNT7_TX register  ****************/
+#define  USB_COUNT7_TX_COUNT7_TX             ((uint16_t)0x03FF)            /*!<Transmission Byte Count 7 */
+
+/*----------------------------------------------------------------------------*/
+
+/****************  Bit definition for USB_COUNT0_TX_0 register  ***************/
+#define  USB_COUNT0_TX_0_COUNT0_TX_0         ((uint32_t)0x000003FF)        /*!<Transmission Byte Count 0 (low) */
+
+/****************  Bit definition for USB_COUNT0_TX_1 register  ***************/
+#define  USB_COUNT0_TX_1_COUNT0_TX_1         ((uint32_t)0x03FF0000)        /*!<Transmission Byte Count 0 (high) */
+
+/****************  Bit definition for USB_COUNT1_TX_0 register  ***************/
+#define  USB_COUNT1_TX_0_COUNT1_TX_0          ((uint32_t)0x000003FF)        /*!<Transmission Byte Count 1 (low) */
+
+/****************  Bit definition for USB_COUNT1_TX_1 register  ***************/
+#define  USB_COUNT1_TX_1_COUNT1_TX_1          ((uint32_t)0x03FF0000)        /*!<Transmission Byte Count 1 (high) */
+
+/****************  Bit definition for USB_COUNT2_TX_0 register  ***************/
+#define  USB_COUNT2_TX_0_COUNT2_TX_0         ((uint32_t)0x000003FF)        /*!<Transmission Byte Count 2 (low) */
+
+/****************  Bit definition for USB_COUNT2_TX_1 register  ***************/
+#define  USB_COUNT2_TX_1_COUNT2_TX_1         ((uint32_t)0x03FF0000)        /*!<Transmission Byte Count 2 (high) */
+
+/****************  Bit definition for USB_COUNT3_TX_0 register  ***************/
+#define  USB_COUNT3_TX_0_COUNT3_TX_0         ((uint16_t)0x000003FF)        /*!<Transmission Byte Count 3 (low) */
+
+/****************  Bit definition for USB_COUNT3_TX_1 register  ***************/
+#define  USB_COUNT3_TX_1_COUNT3_TX_1         ((uint16_t)0x03FF0000)        /*!<Transmission Byte Count 3 (high) */
+
+/****************  Bit definition for USB_COUNT4_TX_0 register  ***************/
+#define  USB_COUNT4_TX_0_COUNT4_TX_0         ((uint32_t)0x000003FF)        /*!<Transmission Byte Count 4 (low) */
+
+/****************  Bit definition for USB_COUNT4_TX_1 register  ***************/
+#define  USB_COUNT4_TX_1_COUNT4_TX_1         ((uint32_t)0x03FF0000)        /*!<Transmission Byte Count 4 (high) */
+
+/****************  Bit definition for USB_COUNT5_TX_0 register  ***************/
+#define  USB_COUNT5_TX_0_COUNT5_TX_0         ((uint32_t)0x000003FF)        /*!<Transmission Byte Count 5 (low) */
+
+/****************  Bit definition for USB_COUNT5_TX_1 register  ***************/
+#define  USB_COUNT5_TX_1_COUNT5_TX_1         ((uint32_t)0x03FF0000)        /*!<Transmission Byte Count 5 (high) */
+
+/****************  Bit definition for USB_COUNT6_TX_0 register  ***************/
+#define  USB_COUNT6_TX_0_COUNT6_TX_0         ((uint32_t)0x000003FF)        /*!<Transmission Byte Count 6 (low) */
+
+/****************  Bit definition for USB_COUNT6_TX_1 register  ***************/
+#define  USB_COUNT6_TX_1_COUNT6_TX_1         ((uint32_t)0x03FF0000)        /*!<Transmission Byte Count 6 (high) */
+
+/****************  Bit definition for USB_COUNT7_TX_0 register  ***************/
+#define  USB_COUNT7_TX_0_COUNT7_TX_0         ((uint32_t)0x000003FF)        /*!<Transmission Byte Count 7 (low) */
+
+/****************  Bit definition for USB_COUNT7_TX_1 register  ***************/
+#define  USB_COUNT7_TX_1_COUNT7_TX_1         ((uint32_t)0x03FF0000)        /*!<Transmission Byte Count 7 (high) */
+
+/*----------------------------------------------------------------------------*/
+
+/*****************  Bit definition for USB_ADDR0_RX register  *****************/
+#define  USB_ADDR0_RX_ADDR0_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 0 */
+
+/*****************  Bit definition for USB_ADDR1_RX register  *****************/
+#define  USB_ADDR1_RX_ADDR1_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 1 */
+
+/*****************  Bit definition for USB_ADDR2_RX register  *****************/
+#define  USB_ADDR2_RX_ADDR2_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 2 */
+
+/*****************  Bit definition for USB_ADDR3_RX register  *****************/
+#define  USB_ADDR3_RX_ADDR3_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 3 */
+
+/*****************  Bit definition for USB_ADDR4_RX register  *****************/
+#define  USB_ADDR4_RX_ADDR4_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 4 */
+
+/*****************  Bit definition for USB_ADDR5_RX register  *****************/
+#define  USB_ADDR5_RX_ADDR5_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 5 */
+
+/*****************  Bit definition for USB_ADDR6_RX register  *****************/
+#define  USB_ADDR6_RX_ADDR6_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 6 */
+
+/*****************  Bit definition for USB_ADDR7_RX register  *****************/
+#define  USB_ADDR7_RX_ADDR7_RX               ((uint16_t)0xFFFE)            /*!<Reception Buffer Address 7 */
+
+/*----------------------------------------------------------------------------*/
+
+/*****************  Bit definition for USB_COUNT0_RX register  ****************/
+#define  USB_COUNT0_RX_COUNT0_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT0_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT0_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT0_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT0_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT0_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT0_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT0_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*****************  Bit definition for USB_COUNT1_RX register  ****************/
+#define  USB_COUNT1_RX_COUNT1_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT1_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT1_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT1_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT1_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT1_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT1_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT1_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*****************  Bit definition for USB_COUNT2_RX register  ****************/
+#define  USB_COUNT2_RX_COUNT2_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT2_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT2_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT2_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT2_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT2_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT2_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT2_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*****************  Bit definition for USB_COUNT3_RX register  ****************/
+#define  USB_COUNT3_RX_COUNT3_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT3_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT3_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT3_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT3_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT3_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT3_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT3_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*****************  Bit definition for USB_COUNT4_RX register  ****************/
+#define  USB_COUNT4_RX_COUNT4_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT4_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT4_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT4_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT4_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT4_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT4_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT4_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*****************  Bit definition for USB_COUNT5_RX register  ****************/
+#define  USB_COUNT5_RX_COUNT5_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT5_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT5_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT5_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT5_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT5_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT5_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT5_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*****************  Bit definition for USB_COUNT6_RX register  ****************/
+#define  USB_COUNT6_RX_COUNT6_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT6_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT6_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT6_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT6_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT6_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT6_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT6_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*****************  Bit definition for USB_COUNT7_RX register  ****************/
+#define  USB_COUNT7_RX_COUNT7_RX             ((uint16_t)0x03FF)            /*!<Reception Byte Count */
+
+#define  USB_COUNT7_RX_NUM_BLOCK             ((uint16_t)0x7C00)            /*!<NUM_BLOCK[4:0] bits (Number of blocks) */
+#define  USB_COUNT7_RX_NUM_BLOCK_0           ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  USB_COUNT7_RX_NUM_BLOCK_1           ((uint16_t)0x0800)            /*!<Bit 1 */
+#define  USB_COUNT7_RX_NUM_BLOCK_2           ((uint16_t)0x1000)            /*!<Bit 2 */
+#define  USB_COUNT7_RX_NUM_BLOCK_3           ((uint16_t)0x2000)            /*!<Bit 3 */
+#define  USB_COUNT7_RX_NUM_BLOCK_4           ((uint16_t)0x4000)            /*!<Bit 4 */
+
+#define  USB_COUNT7_RX_BLSIZE                ((uint16_t)0x8000)            /*!<BLock SIZE */
+
+/*----------------------------------------------------------------------------*/
+
+/****************  Bit definition for USB_COUNT0_RX_0 register  ***************/
+#define  USB_COUNT0_RX_0_COUNT0_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT0_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT0_RX_0_NUM_BLOCK_0_0       ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT0_RX_0_NUM_BLOCK_0_1       ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT0_RX_0_NUM_BLOCK_0_2       ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT0_RX_0_NUM_BLOCK_0_3       ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT0_RX_0_NUM_BLOCK_0_4       ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT0_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/****************  Bit definition for USB_COUNT0_RX_1 register  ***************/
+#define  USB_COUNT0_RX_1_COUNT0_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT0_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT0_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 1 */
+#define  USB_COUNT0_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT0_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT0_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT0_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT0_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/****************  Bit definition for USB_COUNT1_RX_0 register  ***************/
+#define  USB_COUNT1_RX_0_COUNT1_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT1_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT1_RX_0_NUM_BLOCK_0_0       ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT1_RX_0_NUM_BLOCK_0_1       ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT1_RX_0_NUM_BLOCK_0_2       ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT1_RX_0_NUM_BLOCK_0_3       ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT1_RX_0_NUM_BLOCK_0_4       ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT1_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/****************  Bit definition for USB_COUNT1_RX_1 register  ***************/
+#define  USB_COUNT1_RX_1_COUNT1_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT1_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT1_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 0 */
+#define  USB_COUNT1_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT1_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT1_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT1_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT1_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/****************  Bit definition for USB_COUNT2_RX_0 register  ***************/
+#define  USB_COUNT2_RX_0_COUNT2_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT2_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT2_RX_0_NUM_BLOCK_0_0       ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT2_RX_0_NUM_BLOCK_0_1       ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT2_RX_0_NUM_BLOCK_0_2       ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT2_RX_0_NUM_BLOCK_0_3       ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT2_RX_0_NUM_BLOCK_0_4       ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT2_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/****************  Bit definition for USB_COUNT2_RX_1 register  ***************/
+#define  USB_COUNT2_RX_1_COUNT2_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT2_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT2_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 0 */
+#define  USB_COUNT2_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT2_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT2_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT2_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT2_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/****************  Bit definition for USB_COUNT3_RX_0 register  ***************/
+#define  USB_COUNT3_RX_0_COUNT3_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT3_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT3_RX_0_NUM_BLOCK_0_0       ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT3_RX_0_NUM_BLOCK_0_1       ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT3_RX_0_NUM_BLOCK_0_2       ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT3_RX_0_NUM_BLOCK_0_3       ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT3_RX_0_NUM_BLOCK_0_4       ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT3_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/****************  Bit definition for USB_COUNT3_RX_1 register  ***************/
+#define  USB_COUNT3_RX_1_COUNT3_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT3_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT3_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 0 */
+#define  USB_COUNT3_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT3_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT3_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT3_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT3_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/****************  Bit definition for USB_COUNT4_RX_0 register  ***************/
+#define  USB_COUNT4_RX_0_COUNT4_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT4_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT4_RX_0_NUM_BLOCK_0_0      ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT4_RX_0_NUM_BLOCK_0_1      ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT4_RX_0_NUM_BLOCK_0_2      ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT4_RX_0_NUM_BLOCK_0_3      ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT4_RX_0_NUM_BLOCK_0_4      ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT4_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/****************  Bit definition for USB_COUNT4_RX_1 register  ***************/
+#define  USB_COUNT4_RX_1_COUNT4_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT4_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT4_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 0 */
+#define  USB_COUNT4_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT4_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT4_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT4_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT4_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/****************  Bit definition for USB_COUNT5_RX_0 register  ***************/
+#define  USB_COUNT5_RX_0_COUNT5_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT5_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT5_RX_0_NUM_BLOCK_0_0       ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT5_RX_0_NUM_BLOCK_0_1       ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT5_RX_0_NUM_BLOCK_0_2       ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT5_RX_0_NUM_BLOCK_0_3       ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT5_RX_0_NUM_BLOCK_0_4       ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT5_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/****************  Bit definition for USB_COUNT5_RX_1 register  ***************/
+#define  USB_COUNT5_RX_1_COUNT5_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT5_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT5_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 0 */
+#define  USB_COUNT5_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT5_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT5_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT5_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT5_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/***************  Bit definition for USB_COUNT6_RX_0  register  ***************/
+#define  USB_COUNT6_RX_0_COUNT6_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT6_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT6_RX_0_NUM_BLOCK_0_0       ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT6_RX_0_NUM_BLOCK_0_1       ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT6_RX_0_NUM_BLOCK_0_2       ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT6_RX_0_NUM_BLOCK_0_3       ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT6_RX_0_NUM_BLOCK_0_4       ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT6_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/****************  Bit definition for USB_COUNT6_RX_1 register  ***************/
+#define  USB_COUNT6_RX_1_COUNT6_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT6_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT6_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 0 */
+#define  USB_COUNT6_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT6_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT6_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT6_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT6_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/***************  Bit definition for USB_COUNT7_RX_0 register  ****************/
+#define  USB_COUNT7_RX_0_COUNT7_RX_0         ((uint32_t)0x000003FF)        /*!<Reception Byte Count (low) */
+
+#define  USB_COUNT7_RX_0_NUM_BLOCK_0         ((uint32_t)0x00007C00)        /*!<NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */
+#define  USB_COUNT7_RX_0_NUM_BLOCK_0_0       ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  USB_COUNT7_RX_0_NUM_BLOCK_0_1       ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  USB_COUNT7_RX_0_NUM_BLOCK_0_2       ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  USB_COUNT7_RX_0_NUM_BLOCK_0_3       ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  USB_COUNT7_RX_0_NUM_BLOCK_0_4       ((uint32_t)0x00004000)        /*!<Bit 4 */
+
+#define  USB_COUNT7_RX_0_BLSIZE_0            ((uint32_t)0x00008000)        /*!<BLock SIZE (low) */
+
+/***************  Bit definition for USB_COUNT7_RX_1 register  ****************/
+#define  USB_COUNT7_RX_1_COUNT7_RX_1         ((uint32_t)0x03FF0000)        /*!<Reception Byte Count (high) */
+
+#define  USB_COUNT7_RX_1_NUM_BLOCK_1         ((uint32_t)0x7C000000)        /*!<NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */
+#define  USB_COUNT7_RX_1_NUM_BLOCK_1_0       ((uint32_t)0x04000000)        /*!<Bit 0 */
+#define  USB_COUNT7_RX_1_NUM_BLOCK_1_1       ((uint32_t)0x08000000)        /*!<Bit 1 */
+#define  USB_COUNT7_RX_1_NUM_BLOCK_1_2       ((uint32_t)0x10000000)        /*!<Bit 2 */
+#define  USB_COUNT7_RX_1_NUM_BLOCK_1_3       ((uint32_t)0x20000000)        /*!<Bit 3 */
+#define  USB_COUNT7_RX_1_NUM_BLOCK_1_4       ((uint32_t)0x40000000)        /*!<Bit 4 */
+
+#define  USB_COUNT7_RX_1_BLSIZE_1            ((uint32_t)0x80000000)        /*!<BLock SIZE (high) */
+
+/******************************************************************************/
+/*                                                                            */
+/*                         Controller Area Network                            */
+/*                                                                            */
+/******************************************************************************/
+
+/*!<CAN control and status registers */
+/*******************  Bit definition for CAN_MCR register  ********************/
+#define  CAN_MCR_INRQ                        ((uint16_t)0x0001)            /*!<Initialization Request */
+#define  CAN_MCR_SLEEP                       ((uint16_t)0x0002)            /*!<Sleep Mode Request */
+#define  CAN_MCR_TXFP                        ((uint16_t)0x0004)            /*!<Transmit FIFO Priority */
+#define  CAN_MCR_RFLM                        ((uint16_t)0x0008)            /*!<Receive FIFO Locked Mode */
+#define  CAN_MCR_NART                        ((uint16_t)0x0010)            /*!<No Automatic Retransmission */
+#define  CAN_MCR_AWUM                        ((uint16_t)0x0020)            /*!<Automatic Wakeup Mode */
+#define  CAN_MCR_ABOM                        ((uint16_t)0x0040)            /*!<Automatic Bus-Off Management */
+#define  CAN_MCR_TTCM                        ((uint16_t)0x0080)            /*!<Time Triggered Communication Mode */
+#define  CAN_MCR_RESET                       ((uint16_t)0x8000)            /*!<bxCAN software master reset */
+
+/*******************  Bit definition for CAN_MSR register  ********************/
+#define  CAN_MSR_INAK                        ((uint16_t)0x0001)            /*!<Initialization Acknowledge */
+#define  CAN_MSR_SLAK                        ((uint16_t)0x0002)            /*!<Sleep Acknowledge */
+#define  CAN_MSR_ERRI                        ((uint16_t)0x0004)            /*!<Error Interrupt */
+#define  CAN_MSR_WKUI                        ((uint16_t)0x0008)            /*!<Wakeup Interrupt */
+#define  CAN_MSR_SLAKI                       ((uint16_t)0x0010)            /*!<Sleep Acknowledge Interrupt */
+#define  CAN_MSR_TXM                         ((uint16_t)0x0100)            /*!<Transmit Mode */
+#define  CAN_MSR_RXM                         ((uint16_t)0x0200)            /*!<Receive Mode */
+#define  CAN_MSR_SAMP                        ((uint16_t)0x0400)            /*!<Last Sample Point */
+#define  CAN_MSR_RX                          ((uint16_t)0x0800)            /*!<CAN Rx Signal */
+
+/*******************  Bit definition for CAN_TSR register  ********************/
+#define  CAN_TSR_RQCP0                       ((uint32_t)0x00000001)        /*!<Request Completed Mailbox0 */
+#define  CAN_TSR_TXOK0                       ((uint32_t)0x00000002)        /*!<Transmission OK of Mailbox0 */
+#define  CAN_TSR_ALST0                       ((uint32_t)0x00000004)        /*!<Arbitration Lost for Mailbox0 */
+#define  CAN_TSR_TERR0                       ((uint32_t)0x00000008)        /*!<Transmission Error of Mailbox0 */
+#define  CAN_TSR_ABRQ0                       ((uint32_t)0x00000080)        /*!<Abort Request for Mailbox0 */
+#define  CAN_TSR_RQCP1                       ((uint32_t)0x00000100)        /*!<Request Completed Mailbox1 */
+#define  CAN_TSR_TXOK1                       ((uint32_t)0x00000200)        /*!<Transmission OK of Mailbox1 */
+#define  CAN_TSR_ALST1                       ((uint32_t)0x00000400)        /*!<Arbitration Lost for Mailbox1 */
+#define  CAN_TSR_TERR1                       ((uint32_t)0x00000800)        /*!<Transmission Error of Mailbox1 */
+#define  CAN_TSR_ABRQ1                       ((uint32_t)0x00008000)        /*!<Abort Request for Mailbox 1 */
+#define  CAN_TSR_RQCP2                       ((uint32_t)0x00010000)        /*!<Request Completed Mailbox2 */
+#define  CAN_TSR_TXOK2                       ((uint32_t)0x00020000)        /*!<Transmission OK of Mailbox 2 */
+#define  CAN_TSR_ALST2                       ((uint32_t)0x00040000)        /*!<Arbitration Lost for mailbox 2 */
+#define  CAN_TSR_TERR2                       ((uint32_t)0x00080000)        /*!<Transmission Error of Mailbox 2 */
+#define  CAN_TSR_ABRQ2                       ((uint32_t)0x00800000)        /*!<Abort Request for Mailbox 2 */
+#define  CAN_TSR_CODE                        ((uint32_t)0x03000000)        /*!<Mailbox Code */
+
+#define  CAN_TSR_TME                         ((uint32_t)0x1C000000)        /*!<TME[2:0] bits */
+#define  CAN_TSR_TME0                        ((uint32_t)0x04000000)        /*!<Transmit Mailbox 0 Empty */
+#define  CAN_TSR_TME1                        ((uint32_t)0x08000000)        /*!<Transmit Mailbox 1 Empty */
+#define  CAN_TSR_TME2                        ((uint32_t)0x10000000)        /*!<Transmit Mailbox 2 Empty */
+
+#define  CAN_TSR_LOW                         ((uint32_t)0xE0000000)        /*!<LOW[2:0] bits */
+#define  CAN_TSR_LOW0                        ((uint32_t)0x20000000)        /*!<Lowest Priority Flag for Mailbox 0 */
+#define  CAN_TSR_LOW1                        ((uint32_t)0x40000000)        /*!<Lowest Priority Flag for Mailbox 1 */
+#define  CAN_TSR_LOW2                        ((uint32_t)0x80000000)        /*!<Lowest Priority Flag for Mailbox 2 */
+
+/*******************  Bit definition for CAN_RF0R register  *******************/
+#define  CAN_RF0R_FMP0                       ((uint8_t)0x03)               /*!<FIFO 0 Message Pending */
+#define  CAN_RF0R_FULL0                      ((uint8_t)0x08)               /*!<FIFO 0 Full */
+#define  CAN_RF0R_FOVR0                      ((uint8_t)0x10)               /*!<FIFO 0 Overrun */
+#define  CAN_RF0R_RFOM0                      ((uint8_t)0x20)               /*!<Release FIFO 0 Output Mailbox */
+
+/*******************  Bit definition for CAN_RF1R register  *******************/
+#define  CAN_RF1R_FMP1                       ((uint8_t)0x03)               /*!<FIFO 1 Message Pending */
+#define  CAN_RF1R_FULL1                      ((uint8_t)0x08)               /*!<FIFO 1 Full */
+#define  CAN_RF1R_FOVR1                      ((uint8_t)0x10)               /*!<FIFO 1 Overrun */
+#define  CAN_RF1R_RFOM1                      ((uint8_t)0x20)               /*!<Release FIFO 1 Output Mailbox */
+
+/********************  Bit definition for CAN_IER register  *******************/
+#define  CAN_IER_TMEIE                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Empty Interrupt Enable */
+#define  CAN_IER_FMPIE0                      ((uint32_t)0x00000002)        /*!<FIFO Message Pending Interrupt Enable */
+#define  CAN_IER_FFIE0                       ((uint32_t)0x00000004)        /*!<FIFO Full Interrupt Enable */
+#define  CAN_IER_FOVIE0                      ((uint32_t)0x00000008)        /*!<FIFO Overrun Interrupt Enable */
+#define  CAN_IER_FMPIE1                      ((uint32_t)0x00000010)        /*!<FIFO Message Pending Interrupt Enable */
+#define  CAN_IER_FFIE1                       ((uint32_t)0x00000020)        /*!<FIFO Full Interrupt Enable */
+#define  CAN_IER_FOVIE1                      ((uint32_t)0x00000040)        /*!<FIFO Overrun Interrupt Enable */
+#define  CAN_IER_EWGIE                       ((uint32_t)0x00000100)        /*!<Error Warning Interrupt Enable */
+#define  CAN_IER_EPVIE                       ((uint32_t)0x00000200)        /*!<Error Passive Interrupt Enable */
+#define  CAN_IER_BOFIE                       ((uint32_t)0x00000400)        /*!<Bus-Off Interrupt Enable */
+#define  CAN_IER_LECIE                       ((uint32_t)0x00000800)        /*!<Last Error Code Interrupt Enable */
+#define  CAN_IER_ERRIE                       ((uint32_t)0x00008000)        /*!<Error Interrupt Enable */
+#define  CAN_IER_WKUIE                       ((uint32_t)0x00010000)        /*!<Wakeup Interrupt Enable */
+#define  CAN_IER_SLKIE                       ((uint32_t)0x00020000)        /*!<Sleep Interrupt Enable */
+
+/********************  Bit definition for CAN_ESR register  *******************/
+#define  CAN_ESR_EWGF                        ((uint32_t)0x00000001)        /*!<Error Warning Flag */
+#define  CAN_ESR_EPVF                        ((uint32_t)0x00000002)        /*!<Error Passive Flag */
+#define  CAN_ESR_BOFF                        ((uint32_t)0x00000004)        /*!<Bus-Off Flag */
+
+#define  CAN_ESR_LEC                         ((uint32_t)0x00000070)        /*!<LEC[2:0] bits (Last Error Code) */
+#define  CAN_ESR_LEC_0                       ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  CAN_ESR_LEC_1                       ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  CAN_ESR_LEC_2                       ((uint32_t)0x00000040)        /*!<Bit 2 */
+
+#define  CAN_ESR_TEC                         ((uint32_t)0x00FF0000)        /*!<Least significant byte of the 9-bit Transmit Error Counter */
+#define  CAN_ESR_REC                         ((uint32_t)0xFF000000)        /*!<Receive Error Counter */
+
+/*******************  Bit definition for CAN_BTR register  ********************/
+#define  CAN_BTR_BRP                         ((uint32_t)0x000003FF)        /*!<Baud Rate Prescaler */
+#define  CAN_BTR_TS1                         ((uint32_t)0x000F0000)        /*!<Time Segment 1 */
+#define  CAN_BTR_TS2                         ((uint32_t)0x00700000)        /*!<Time Segment 2 */
+#define  CAN_BTR_SJW                         ((uint32_t)0x03000000)        /*!<Resynchronization Jump Width */
+#define  CAN_BTR_LBKM                        ((uint32_t)0x40000000)        /*!<Loop Back Mode (Debug) */
+#define  CAN_BTR_SILM                        ((uint32_t)0x80000000)        /*!<Silent Mode */
+
+/*!<Mailbox registers */
+/******************  Bit definition for CAN_TI0R register  ********************/
+#define  CAN_TI0R_TXRQ                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Request */
+#define  CAN_TI0R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_TI0R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_TI0R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended Identifier */
+#define  CAN_TI0R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/******************  Bit definition for CAN_TDT0R register  *******************/
+#define  CAN_TDT0R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_TDT0R_TGT                       ((uint32_t)0x00000100)        /*!<Transmit Global Time */
+#define  CAN_TDT0R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/******************  Bit definition for CAN_TDL0R register  *******************/
+#define  CAN_TDL0R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_TDL0R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_TDL0R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_TDL0R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/******************  Bit definition for CAN_TDH0R register  *******************/
+#define  CAN_TDH0R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_TDH0R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_TDH0R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_TDH0R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_TI1R register  *******************/
+#define  CAN_TI1R_TXRQ                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Request */
+#define  CAN_TI1R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_TI1R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_TI1R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended Identifier */
+#define  CAN_TI1R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_TDT1R register  ******************/
+#define  CAN_TDT1R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_TDT1R_TGT                       ((uint32_t)0x00000100)        /*!<Transmit Global Time */
+#define  CAN_TDT1R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_TDL1R register  ******************/
+#define  CAN_TDL1R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_TDL1R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_TDL1R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_TDL1R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_TDH1R register  ******************/
+#define  CAN_TDH1R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_TDH1R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_TDH1R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_TDH1R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_TI2R register  *******************/
+#define  CAN_TI2R_TXRQ                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Request */
+#define  CAN_TI2R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_TI2R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_TI2R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended identifier */
+#define  CAN_TI2R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_TDT2R register  ******************/  
+#define  CAN_TDT2R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_TDT2R_TGT                       ((uint32_t)0x00000100)        /*!<Transmit Global Time */
+#define  CAN_TDT2R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_TDL2R register  ******************/
+#define  CAN_TDL2R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_TDL2R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_TDL2R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_TDL2R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_TDH2R register  ******************/
+#define  CAN_TDH2R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_TDH2R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_TDH2R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_TDH2R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_RI0R register  *******************/
+#define  CAN_RI0R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_RI0R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_RI0R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended Identifier */
+#define  CAN_RI0R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_RDT0R register  ******************/
+#define  CAN_RDT0R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_RDT0R_FMI                       ((uint32_t)0x0000FF00)        /*!<Filter Match Index */
+#define  CAN_RDT0R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_RDL0R register  ******************/
+#define  CAN_RDL0R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_RDL0R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_RDL0R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_RDL0R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_RDH0R register  ******************/
+#define  CAN_RDH0R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_RDH0R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_RDH0R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_RDH0R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_RI1R register  *******************/
+#define  CAN_RI1R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_RI1R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_RI1R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended identifier */
+#define  CAN_RI1R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_RDT1R register  ******************/
+#define  CAN_RDT1R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_RDT1R_FMI                       ((uint32_t)0x0000FF00)        /*!<Filter Match Index */
+#define  CAN_RDT1R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_RDL1R register  ******************/
+#define  CAN_RDL1R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_RDL1R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_RDL1R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_RDL1R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_RDH1R register  ******************/
+#define  CAN_RDH1R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_RDH1R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_RDH1R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_RDH1R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*!<CAN filter registers */
+/*******************  Bit definition for CAN_FMR register  ********************/
+#define  CAN_FMR_FINIT                       ((uint8_t)0x01)               /*!<Filter Init Mode */
+
+/*******************  Bit definition for CAN_FM1R register  *******************/
+#define  CAN_FM1R_FBM                        ((uint16_t)0x3FFF)            /*!<Filter Mode */
+#define  CAN_FM1R_FBM0                       ((uint16_t)0x0001)            /*!<Filter Init Mode bit 0 */
+#define  CAN_FM1R_FBM1                       ((uint16_t)0x0002)            /*!<Filter Init Mode bit 1 */
+#define  CAN_FM1R_FBM2                       ((uint16_t)0x0004)            /*!<Filter Init Mode bit 2 */
+#define  CAN_FM1R_FBM3                       ((uint16_t)0x0008)            /*!<Filter Init Mode bit 3 */
+#define  CAN_FM1R_FBM4                       ((uint16_t)0x0010)            /*!<Filter Init Mode bit 4 */
+#define  CAN_FM1R_FBM5                       ((uint16_t)0x0020)            /*!<Filter Init Mode bit 5 */
+#define  CAN_FM1R_FBM6                       ((uint16_t)0x0040)            /*!<Filter Init Mode bit 6 */
+#define  CAN_FM1R_FBM7                       ((uint16_t)0x0080)            /*!<Filter Init Mode bit 7 */
+#define  CAN_FM1R_FBM8                       ((uint16_t)0x0100)            /*!<Filter Init Mode bit 8 */
+#define  CAN_FM1R_FBM9                       ((uint16_t)0x0200)            /*!<Filter Init Mode bit 9 */
+#define  CAN_FM1R_FBM10                      ((uint16_t)0x0400)            /*!<Filter Init Mode bit 10 */
+#define  CAN_FM1R_FBM11                      ((uint16_t)0x0800)            /*!<Filter Init Mode bit 11 */
+#define  CAN_FM1R_FBM12                      ((uint16_t)0x1000)            /*!<Filter Init Mode bit 12 */
+#define  CAN_FM1R_FBM13                      ((uint16_t)0x2000)            /*!<Filter Init Mode bit 13 */
+
+/*******************  Bit definition for CAN_FS1R register  *******************/
+#define  CAN_FS1R_FSC                        ((uint16_t)0x3FFF)            /*!<Filter Scale Configuration */
+#define  CAN_FS1R_FSC0                       ((uint16_t)0x0001)            /*!<Filter Scale Configuration bit 0 */
+#define  CAN_FS1R_FSC1                       ((uint16_t)0x0002)            /*!<Filter Scale Configuration bit 1 */
+#define  CAN_FS1R_FSC2                       ((uint16_t)0x0004)            /*!<Filter Scale Configuration bit 2 */
+#define  CAN_FS1R_FSC3                       ((uint16_t)0x0008)            /*!<Filter Scale Configuration bit 3 */
+#define  CAN_FS1R_FSC4                       ((uint16_t)0x0010)            /*!<Filter Scale Configuration bit 4 */
+#define  CAN_FS1R_FSC5                       ((uint16_t)0x0020)            /*!<Filter Scale Configuration bit 5 */
+#define  CAN_FS1R_FSC6                       ((uint16_t)0x0040)            /*!<Filter Scale Configuration bit 6 */
+#define  CAN_FS1R_FSC7                       ((uint16_t)0x0080)            /*!<Filter Scale Configuration bit 7 */
+#define  CAN_FS1R_FSC8                       ((uint16_t)0x0100)            /*!<Filter Scale Configuration bit 8 */
+#define  CAN_FS1R_FSC9                       ((uint16_t)0x0200)            /*!<Filter Scale Configuration bit 9 */
+#define  CAN_FS1R_FSC10                      ((uint16_t)0x0400)            /*!<Filter Scale Configuration bit 10 */
+#define  CAN_FS1R_FSC11                      ((uint16_t)0x0800)            /*!<Filter Scale Configuration bit 11 */
+#define  CAN_FS1R_FSC12                      ((uint16_t)0x1000)            /*!<Filter Scale Configuration bit 12 */
+#define  CAN_FS1R_FSC13                      ((uint16_t)0x2000)            /*!<Filter Scale Configuration bit 13 */
+
+/******************  Bit definition for CAN_FFA1R register  *******************/
+#define  CAN_FFA1R_FFA                       ((uint16_t)0x3FFF)            /*!<Filter FIFO Assignment */
+#define  CAN_FFA1R_FFA0                      ((uint16_t)0x0001)            /*!<Filter FIFO Assignment for Filter 0 */
+#define  CAN_FFA1R_FFA1                      ((uint16_t)0x0002)            /*!<Filter FIFO Assignment for Filter 1 */
+#define  CAN_FFA1R_FFA2                      ((uint16_t)0x0004)            /*!<Filter FIFO Assignment for Filter 2 */
+#define  CAN_FFA1R_FFA3                      ((uint16_t)0x0008)            /*!<Filter FIFO Assignment for Filter 3 */
+#define  CAN_FFA1R_FFA4                      ((uint16_t)0x0010)            /*!<Filter FIFO Assignment for Filter 4 */
+#define  CAN_FFA1R_FFA5                      ((uint16_t)0x0020)            /*!<Filter FIFO Assignment for Filter 5 */
+#define  CAN_FFA1R_FFA6                      ((uint16_t)0x0040)            /*!<Filter FIFO Assignment for Filter 6 */
+#define  CAN_FFA1R_FFA7                      ((uint16_t)0x0080)            /*!<Filter FIFO Assignment for Filter 7 */
+#define  CAN_FFA1R_FFA8                      ((uint16_t)0x0100)            /*!<Filter FIFO Assignment for Filter 8 */
+#define  CAN_FFA1R_FFA9                      ((uint16_t)0x0200)            /*!<Filter FIFO Assignment for Filter 9 */
+#define  CAN_FFA1R_FFA10                     ((uint16_t)0x0400)            /*!<Filter FIFO Assignment for Filter 10 */
+#define  CAN_FFA1R_FFA11                     ((uint16_t)0x0800)            /*!<Filter FIFO Assignment for Filter 11 */
+#define  CAN_FFA1R_FFA12                     ((uint16_t)0x1000)            /*!<Filter FIFO Assignment for Filter 12 */
+#define  CAN_FFA1R_FFA13                     ((uint16_t)0x2000)            /*!<Filter FIFO Assignment for Filter 13 */
+
+/*******************  Bit definition for CAN_FA1R register  *******************/
+#define  CAN_FA1R_FACT                       ((uint16_t)0x3FFF)            /*!<Filter Active */
+#define  CAN_FA1R_FACT0                      ((uint16_t)0x0001)            /*!<Filter 0 Active */
+#define  CAN_FA1R_FACT1                      ((uint16_t)0x0002)            /*!<Filter 1 Active */
+#define  CAN_FA1R_FACT2                      ((uint16_t)0x0004)            /*!<Filter 2 Active */
+#define  CAN_FA1R_FACT3                      ((uint16_t)0x0008)            /*!<Filter 3 Active */
+#define  CAN_FA1R_FACT4                      ((uint16_t)0x0010)            /*!<Filter 4 Active */
+#define  CAN_FA1R_FACT5                      ((uint16_t)0x0020)            /*!<Filter 5 Active */
+#define  CAN_FA1R_FACT6                      ((uint16_t)0x0040)            /*!<Filter 6 Active */
+#define  CAN_FA1R_FACT7                      ((uint16_t)0x0080)            /*!<Filter 7 Active */
+#define  CAN_FA1R_FACT8                      ((uint16_t)0x0100)            /*!<Filter 8 Active */
+#define  CAN_FA1R_FACT9                      ((uint16_t)0x0200)            /*!<Filter 9 Active */
+#define  CAN_FA1R_FACT10                     ((uint16_t)0x0400)            /*!<Filter 10 Active */
+#define  CAN_FA1R_FACT11                     ((uint16_t)0x0800)            /*!<Filter 11 Active */
+#define  CAN_FA1R_FACT12                     ((uint16_t)0x1000)            /*!<Filter 12 Active */
+#define  CAN_FA1R_FACT13                     ((uint16_t)0x2000)            /*!<Filter 13 Active */
+
+/*******************  Bit definition for CAN_F0R1 register  *******************/
+#define  CAN_F0R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F0R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F0R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F0R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F0R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F0R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F0R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F0R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F0R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F0R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F0R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F0R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F0R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F0R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F0R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F0R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F0R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F0R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F0R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F0R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F0R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F0R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F0R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F0R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F0R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F0R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F0R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F0R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F0R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F0R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F0R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F0R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F1R1 register  *******************/
+#define  CAN_F1R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F1R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F1R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F1R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F1R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F1R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F1R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F1R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F1R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F1R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F1R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F1R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F1R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F1R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F1R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F1R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F1R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F1R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F1R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F1R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F1R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F1R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F1R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F1R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F1R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F1R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F1R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F1R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F1R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F1R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F1R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F1R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F2R1 register  *******************/
+#define  CAN_F2R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F2R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F2R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F2R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F2R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F2R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F2R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F2R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F2R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F2R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F2R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F2R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F2R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F2R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F2R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F2R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F2R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F2R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F2R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F2R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F2R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F2R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F2R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F2R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F2R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F2R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F2R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F2R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F2R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F2R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F2R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F2R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F3R1 register  *******************/
+#define  CAN_F3R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F3R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F3R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F3R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F3R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F3R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F3R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F3R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F3R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F3R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F3R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F3R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F3R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F3R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F3R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F3R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F3R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F3R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F3R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F3R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F3R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F3R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F3R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F3R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F3R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F3R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F3R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F3R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F3R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F3R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F3R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F3R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F4R1 register  *******************/
+#define  CAN_F4R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F4R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F4R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F4R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F4R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F4R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F4R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F4R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F4R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F4R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F4R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F4R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F4R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F4R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F4R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F4R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F4R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F4R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F4R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F4R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F4R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F4R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F4R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F4R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F4R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F4R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F4R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F4R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F4R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F4R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F4R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F4R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F5R1 register  *******************/
+#define  CAN_F5R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F5R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F5R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F5R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F5R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F5R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F5R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F5R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F5R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F5R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F5R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F5R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F5R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F5R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F5R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F5R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F5R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F5R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F5R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F5R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F5R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F5R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F5R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F5R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F5R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F5R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F5R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F5R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F5R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F5R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F5R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F5R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F6R1 register  *******************/
+#define  CAN_F6R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F6R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F6R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F6R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F6R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F6R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F6R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F6R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F6R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F6R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F6R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F6R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F6R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F6R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F6R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F6R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F6R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F6R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F6R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F6R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F6R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F6R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F6R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F6R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F6R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F6R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F6R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F6R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F6R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F6R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F6R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F6R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F7R1 register  *******************/
+#define  CAN_F7R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F7R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F7R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F7R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F7R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F7R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F7R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F7R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F7R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F7R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F7R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F7R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F7R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F7R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F7R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F7R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F7R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F7R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F7R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F7R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F7R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F7R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F7R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F7R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F7R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F7R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F7R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F7R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F7R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F7R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F7R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F7R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F8R1 register  *******************/
+#define  CAN_F8R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F8R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F8R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F8R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F8R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F8R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F8R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F8R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F8R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F8R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F8R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F8R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F8R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F8R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F8R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F8R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F8R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F8R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F8R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F8R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F8R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F8R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F8R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F8R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F8R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F8R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F8R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F8R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F8R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F8R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F8R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F8R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F9R1 register  *******************/
+#define  CAN_F9R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F9R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F9R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F9R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F9R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F9R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F9R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F9R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F9R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F9R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F9R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F9R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F9R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F9R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F9R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F9R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F9R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F9R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F9R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F9R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F9R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F9R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F9R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F9R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F9R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F9R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F9R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F9R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F9R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F9R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F9R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F9R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F10R1 register  ******************/
+#define  CAN_F10R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F10R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F10R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F10R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F10R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F10R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F10R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F10R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F10R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F10R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F10R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F10R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F10R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F10R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F10R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F10R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F10R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F10R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F10R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F10R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F10R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F10R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F10R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F10R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F10R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F10R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F10R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F10R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F10R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F10R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F10R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F10R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F11R1 register  ******************/
+#define  CAN_F11R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F11R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F11R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F11R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F11R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F11R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F11R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F11R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F11R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F11R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F11R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F11R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F11R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F11R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F11R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F11R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F11R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F11R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F11R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F11R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F11R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F11R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F11R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F11R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F11R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F11R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F11R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F11R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F11R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F11R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F11R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F11R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F12R1 register  ******************/
+#define  CAN_F12R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F12R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F12R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F12R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F12R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F12R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F12R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F12R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F12R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F12R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F12R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F12R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F12R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F12R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F12R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F12R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F12R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F12R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F12R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F12R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F12R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F12R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F12R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F12R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F12R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F12R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F12R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F12R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F12R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F12R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F12R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F12R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F13R1 register  ******************/
+#define  CAN_F13R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F13R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F13R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F13R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F13R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F13R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F13R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F13R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F13R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F13R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F13R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F13R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F13R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F13R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F13R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F13R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F13R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F13R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F13R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F13R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F13R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F13R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F13R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F13R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F13R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F13R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F13R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F13R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F13R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F13R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F13R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F13R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F0R2 register  *******************/
+#define  CAN_F0R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F0R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F0R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F0R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F0R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F0R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F0R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F0R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F0R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F0R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F0R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F0R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F0R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F0R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F0R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F0R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F0R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F0R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F0R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F0R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F0R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F0R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F0R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F0R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F0R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F0R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F0R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F0R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F0R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F0R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F0R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F0R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F1R2 register  *******************/
+#define  CAN_F1R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F1R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F1R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F1R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F1R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F1R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F1R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F1R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F1R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F1R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F1R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F1R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F1R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F1R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F1R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F1R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F1R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F1R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F1R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F1R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F1R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F1R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F1R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F1R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F1R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F1R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F1R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F1R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F1R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F1R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F1R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F1R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F2R2 register  *******************/
+#define  CAN_F2R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F2R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F2R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F2R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F2R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F2R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F2R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F2R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F2R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F2R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F2R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F2R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F2R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F2R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F2R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F2R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F2R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F2R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F2R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F2R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F2R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F2R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F2R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F2R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F2R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F2R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F2R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F2R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F2R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F2R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F2R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F2R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F3R2 register  *******************/
+#define  CAN_F3R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F3R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F3R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F3R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F3R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F3R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F3R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F3R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F3R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F3R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F3R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F3R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F3R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F3R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F3R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F3R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F3R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F3R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F3R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F3R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F3R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F3R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F3R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F3R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F3R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F3R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F3R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F3R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F3R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F3R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F3R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F3R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F4R2 register  *******************/
+#define  CAN_F4R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F4R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F4R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F4R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F4R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F4R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F4R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F4R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F4R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F4R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F4R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F4R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F4R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F4R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F4R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F4R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F4R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F4R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F4R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F4R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F4R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F4R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F4R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F4R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F4R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F4R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F4R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F4R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F4R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F4R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F4R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F4R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F5R2 register  *******************/
+#define  CAN_F5R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F5R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F5R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F5R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F5R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F5R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F5R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F5R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F5R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F5R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F5R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F5R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F5R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F5R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F5R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F5R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F5R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F5R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F5R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F5R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F5R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F5R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F5R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F5R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F5R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F5R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F5R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F5R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F5R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F5R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F5R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F5R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F6R2 register  *******************/
+#define  CAN_F6R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F6R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F6R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F6R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F6R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F6R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F6R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F6R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F6R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F6R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F6R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F6R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F6R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F6R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F6R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F6R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F6R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F6R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F6R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F6R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F6R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F6R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F6R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F6R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F6R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F6R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F6R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F6R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F6R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F6R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F6R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F6R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F7R2 register  *******************/
+#define  CAN_F7R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F7R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F7R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F7R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F7R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F7R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F7R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F7R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F7R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F7R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F7R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F7R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F7R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F7R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F7R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F7R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F7R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F7R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F7R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F7R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F7R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F7R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F7R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F7R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F7R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F7R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F7R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F7R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F7R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F7R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F7R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F7R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F8R2 register  *******************/
+#define  CAN_F8R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F8R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F8R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F8R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F8R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F8R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F8R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F8R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F8R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F8R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F8R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F8R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F8R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F8R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F8R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F8R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F8R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F8R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F8R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F8R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F8R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F8R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F8R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F8R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F8R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F8R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F8R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F8R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F8R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F8R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F8R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F8R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F9R2 register  *******************/
+#define  CAN_F9R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F9R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F9R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F9R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F9R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F9R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F9R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F9R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F9R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F9R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F9R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F9R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F9R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F9R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F9R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F9R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F9R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F9R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F9R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F9R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F9R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F9R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F9R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F9R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F9R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F9R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F9R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F9R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F9R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F9R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F9R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F9R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F10R2 register  ******************/
+#define  CAN_F10R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F10R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F10R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F10R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F10R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F10R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F10R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F10R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F10R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F10R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F10R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F10R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F10R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F10R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F10R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F10R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F10R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F10R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F10R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F10R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F10R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F10R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F10R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F10R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F10R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F10R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F10R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F10R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F10R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F10R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F10R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F10R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F11R2 register  ******************/
+#define  CAN_F11R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F11R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F11R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F11R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F11R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F11R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F11R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F11R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F11R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F11R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F11R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F11R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F11R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F11R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F11R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F11R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F11R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F11R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F11R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F11R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F11R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F11R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F11R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F11R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F11R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F11R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F11R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F11R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F11R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F11R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F11R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F11R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F12R2 register  ******************/
+#define  CAN_F12R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F12R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F12R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F12R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F12R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F12R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F12R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F12R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F12R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F12R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F12R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F12R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F12R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F12R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F12R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F12R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F12R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F12R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F12R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F12R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F12R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F12R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F12R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F12R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F12R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F12R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F12R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F12R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F12R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F12R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F12R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F12R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F13R2 register  ******************/
+#define  CAN_F13R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F13R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F13R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F13R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F13R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F13R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F13R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F13R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F13R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F13R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F13R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F13R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F13R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F13R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F13R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F13R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F13R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F13R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F13R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F13R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F13R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F13R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F13R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F13R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F13R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F13R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F13R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F13R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F13R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F13R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F13R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F13R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/******************************************************************************/
+/*                                                                            */
+/*                        Serial Peripheral Interface                         */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for SPI_CR1 register  ********************/
+#define  SPI_CR1_CPHA                        ((uint16_t)0x0001)            /*!<Clock Phase */
+#define  SPI_CR1_CPOL                        ((uint16_t)0x0002)            /*!<Clock Polarity */
+#define  SPI_CR1_MSTR                        ((uint16_t)0x0004)            /*!<Master Selection */
+
+#define  SPI_CR1_BR                          ((uint16_t)0x0038)            /*!<BR[2:0] bits (Baud Rate Control) */
+#define  SPI_CR1_BR_0                        ((uint16_t)0x0008)            /*!<Bit 0 */
+#define  SPI_CR1_BR_1                        ((uint16_t)0x0010)            /*!<Bit 1 */
+#define  SPI_CR1_BR_2                        ((uint16_t)0x0020)            /*!<Bit 2 */
+
+#define  SPI_CR1_SPE                         ((uint16_t)0x0040)            /*!<SPI Enable */
+#define  SPI_CR1_LSBFIRST                    ((uint16_t)0x0080)            /*!<Frame Format */
+#define  SPI_CR1_SSI                         ((uint16_t)0x0100)            /*!<Internal slave select */
+#define  SPI_CR1_SSM                         ((uint16_t)0x0200)            /*!<Software slave management */
+#define  SPI_CR1_RXONLY                      ((uint16_t)0x0400)            /*!<Receive only */
+#define  SPI_CR1_DFF                         ((uint16_t)0x0800)            /*!<Data Frame Format */
+#define  SPI_CR1_CRCNEXT                     ((uint16_t)0x1000)            /*!<Transmit CRC next */
+#define  SPI_CR1_CRCEN                       ((uint16_t)0x2000)            /*!<Hardware CRC calculation enable */
+#define  SPI_CR1_BIDIOE                      ((uint16_t)0x4000)            /*!<Output enable in bidirectional mode */
+#define  SPI_CR1_BIDIMODE                    ((uint16_t)0x8000)            /*!<Bidirectional data mode enable */
+
+/*******************  Bit definition for SPI_CR2 register  ********************/
+#define  SPI_CR2_RXDMAEN                     ((uint8_t)0x01)               /*!<Rx Buffer DMA Enable */
+#define  SPI_CR2_TXDMAEN                     ((uint8_t)0x02)               /*!<Tx Buffer DMA Enable */
+#define  SPI_CR2_SSOE                        ((uint8_t)0x04)               /*!<SS Output Enable */
+#define  SPI_CR2_ERRIE                       ((uint8_t)0x20)               /*!<Error Interrupt Enable */
+#define  SPI_CR2_RXNEIE                      ((uint8_t)0x40)               /*!<RX buffer Not Empty Interrupt Enable */
+#define  SPI_CR2_TXEIE                       ((uint8_t)0x80)               /*!<Tx buffer Empty Interrupt Enable */
+
+/********************  Bit definition for SPI_SR register  ********************/
+#define  SPI_SR_RXNE                         ((uint8_t)0x01)               /*!<Receive buffer Not Empty */
+#define  SPI_SR_TXE                          ((uint8_t)0x02)               /*!<Transmit buffer Empty */
+#define  SPI_SR_CHSIDE                       ((uint8_t)0x04)               /*!<Channel side */
+#define  SPI_SR_UDR                          ((uint8_t)0x08)               /*!<Underrun flag */
+#define  SPI_SR_CRCERR                       ((uint8_t)0x10)               /*!<CRC Error flag */
+#define  SPI_SR_MODF                         ((uint8_t)0x20)               /*!<Mode fault */
+#define  SPI_SR_OVR                          ((uint8_t)0x40)               /*!<Overrun flag */
+#define  SPI_SR_BSY                          ((uint8_t)0x80)               /*!<Busy flag */
+
+/********************  Bit definition for SPI_DR register  ********************/
+#define  SPI_DR_DR                           ((uint16_t)0xFFFF)            /*!<Data Register */
+
+/*******************  Bit definition for SPI_CRCPR register  ******************/
+#define  SPI_CRCPR_CRCPOLY                   ((uint16_t)0xFFFF)            /*!<CRC polynomial register */
+
+/******************  Bit definition for SPI_RXCRCR register  ******************/
+#define  SPI_RXCRCR_RXCRC                    ((uint16_t)0xFFFF)            /*!<Rx CRC Register */
+
+/******************  Bit definition for SPI_TXCRCR register  ******************/
+#define  SPI_TXCRCR_TXCRC                    ((uint16_t)0xFFFF)            /*!<Tx CRC Register */
+
+/******************  Bit definition for SPI_I2SCFGR register  *****************/
+#define  SPI_I2SCFGR_CHLEN                   ((uint16_t)0x0001)            /*!<Channel length (number of bits per audio channel) */
+
+#define  SPI_I2SCFGR_DATLEN                  ((uint16_t)0x0006)            /*!<DATLEN[1:0] bits (Data length to be transferred) */
+#define  SPI_I2SCFGR_DATLEN_0                ((uint16_t)0x0002)            /*!<Bit 0 */
+#define  SPI_I2SCFGR_DATLEN_1                ((uint16_t)0x0004)            /*!<Bit 1 */
+
+#define  SPI_I2SCFGR_CKPOL                   ((uint16_t)0x0008)            /*!<steady state clock polarity */
+
+#define  SPI_I2SCFGR_I2SSTD                  ((uint16_t)0x0030)            /*!<I2SSTD[1:0] bits (I2S standard selection) */
+#define  SPI_I2SCFGR_I2SSTD_0                ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  SPI_I2SCFGR_I2SSTD_1                ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  SPI_I2SCFGR_PCMSYNC                 ((uint16_t)0x0080)            /*!<PCM frame synchronization */
+
+#define  SPI_I2SCFGR_I2SCFG                  ((uint16_t)0x0300)            /*!<I2SCFG[1:0] bits (I2S configuration mode) */
+#define  SPI_I2SCFGR_I2SCFG_0                ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  SPI_I2SCFGR_I2SCFG_1                ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  SPI_I2SCFGR_I2SE                    ((uint16_t)0x0400)            /*!<I2S Enable */
+#define  SPI_I2SCFGR_I2SMOD                  ((uint16_t)0x0800)            /*!<I2S mode selection */
+
+/******************  Bit definition for SPI_I2SPR register  *******************/
+#define  SPI_I2SPR_I2SDIV                    ((uint16_t)0x00FF)            /*!<I2S Linear prescaler */
+#define  SPI_I2SPR_ODD                       ((uint16_t)0x0100)            /*!<Odd factor for the prescaler */
+#define  SPI_I2SPR_MCKOE                     ((uint16_t)0x0200)            /*!<Master Clock Output Enable */
+
+/******************************************************************************/
+/*                                                                            */
+/*                      Inter-integrated Circuit Interface                    */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for I2C_CR1 register  ********************/
+#define  I2C_CR1_PE                          ((uint16_t)0x0001)            /*!<Peripheral Enable */
+#define  I2C_CR1_SMBUS                       ((uint16_t)0x0002)            /*!<SMBus Mode */
+#define  I2C_CR1_SMBTYPE                     ((uint16_t)0x0008)            /*!<SMBus Type */
+#define  I2C_CR1_ENARP                       ((uint16_t)0x0010)            /*!<ARP Enable */
+#define  I2C_CR1_ENPEC                       ((uint16_t)0x0020)            /*!<PEC Enable */
+#define  I2C_CR1_ENGC                        ((uint16_t)0x0040)            /*!<General Call Enable */
+#define  I2C_CR1_NOSTRETCH                   ((uint16_t)0x0080)            /*!<Clock Stretching Disable (Slave mode) */
+#define  I2C_CR1_START                       ((uint16_t)0x0100)            /*!<Start Generation */
+#define  I2C_CR1_STOP                        ((uint16_t)0x0200)            /*!<Stop Generation */
+#define  I2C_CR1_ACK                         ((uint16_t)0x0400)            /*!<Acknowledge Enable */
+#define  I2C_CR1_POS                         ((uint16_t)0x0800)            /*!<Acknowledge/PEC Position (for data reception) */
+#define  I2C_CR1_PEC                         ((uint16_t)0x1000)            /*!<Packet Error Checking */
+#define  I2C_CR1_ALERT                       ((uint16_t)0x2000)            /*!<SMBus Alert */
+#define  I2C_CR1_SWRST                       ((uint16_t)0x8000)            /*!<Software Reset */
+
+/*******************  Bit definition for I2C_CR2 register  ********************/
+#define  I2C_CR2_FREQ                        ((uint16_t)0x003F)            /*!<FREQ[5:0] bits (Peripheral Clock Frequency) */
+#define  I2C_CR2_FREQ_0                      ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  I2C_CR2_FREQ_1                      ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  I2C_CR2_FREQ_2                      ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  I2C_CR2_FREQ_3                      ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  I2C_CR2_FREQ_4                      ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  I2C_CR2_FREQ_5                      ((uint16_t)0x0020)            /*!<Bit 5 */
+
+#define  I2C_CR2_ITERREN                     ((uint16_t)0x0100)            /*!<Error Interrupt Enable */
+#define  I2C_CR2_ITEVTEN                     ((uint16_t)0x0200)            /*!<Event Interrupt Enable */
+#define  I2C_CR2_ITBUFEN                     ((uint16_t)0x0400)            /*!<Buffer Interrupt Enable */
+#define  I2C_CR2_DMAEN                       ((uint16_t)0x0800)            /*!<DMA Requests Enable */
+#define  I2C_CR2_LAST                        ((uint16_t)0x1000)            /*!<DMA Last Transfer */
+
+/*******************  Bit definition for I2C_OAR1 register  *******************/
+#define  I2C_OAR1_ADD1_7                     ((uint16_t)0x00FE)            /*!<Interface Address */
+#define  I2C_OAR1_ADD8_9                     ((uint16_t)0x0300)            /*!<Interface Address */
+
+#define  I2C_OAR1_ADD0                       ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  I2C_OAR1_ADD1                       ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  I2C_OAR1_ADD2                       ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  I2C_OAR1_ADD3                       ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  I2C_OAR1_ADD4                       ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  I2C_OAR1_ADD5                       ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  I2C_OAR1_ADD6                       ((uint16_t)0x0040)            /*!<Bit 6 */
+#define  I2C_OAR1_ADD7                       ((uint16_t)0x0080)            /*!<Bit 7 */
+#define  I2C_OAR1_ADD8                       ((uint16_t)0x0100)            /*!<Bit 8 */
+#define  I2C_OAR1_ADD9                       ((uint16_t)0x0200)            /*!<Bit 9 */
+
+#define  I2C_OAR1_ADDMODE                    ((uint16_t)0x8000)            /*!<Addressing Mode (Slave mode) */
+
+/*******************  Bit definition for I2C_OAR2 register  *******************/
+#define  I2C_OAR2_ENDUAL                     ((uint8_t)0x01)               /*!<Dual addressing mode enable */
+#define  I2C_OAR2_ADD2                       ((uint8_t)0xFE)               /*!<Interface address */
+
+/********************  Bit definition for I2C_DR register  ********************/
+#define  I2C_DR_DR                           ((uint8_t)0xFF)               /*!<8-bit Data Register */
+
+/*******************  Bit definition for I2C_SR1 register  ********************/
+#define  I2C_SR1_SB                          ((uint16_t)0x0001)            /*!<Start Bit (Master mode) */
+#define  I2C_SR1_ADDR                        ((uint16_t)0x0002)            /*!<Address sent (master mode)/matched (slave mode) */
+#define  I2C_SR1_BTF                         ((uint16_t)0x0004)            /*!<Byte Transfer Finished */
+#define  I2C_SR1_ADD10                       ((uint16_t)0x0008)            /*!<10-bit header sent (Master mode) */
+#define  I2C_SR1_STOPF                       ((uint16_t)0x0010)            /*!<Stop detection (Slave mode) */
+#define  I2C_SR1_RXNE                        ((uint16_t)0x0040)            /*!<Data Register not Empty (receivers) */
+#define  I2C_SR1_TXE                         ((uint16_t)0x0080)            /*!<Data Register Empty (transmitters) */
+#define  I2C_SR1_BERR                        ((uint16_t)0x0100)            /*!<Bus Error */
+#define  I2C_SR1_ARLO                        ((uint16_t)0x0200)            /*!<Arbitration Lost (master mode) */
+#define  I2C_SR1_AF                          ((uint16_t)0x0400)            /*!<Acknowledge Failure */
+#define  I2C_SR1_OVR                         ((uint16_t)0x0800)            /*!<Overrun/Underrun */
+#define  I2C_SR1_PECERR                      ((uint16_t)0x1000)            /*!<PEC Error in reception */
+#define  I2C_SR1_TIMEOUT                     ((uint16_t)0x4000)            /*!<Timeout or Tlow Error */
+#define  I2C_SR1_SMBALERT                    ((uint16_t)0x8000)            /*!<SMBus Alert */
+
+/*******************  Bit definition for I2C_SR2 register  ********************/
+#define  I2C_SR2_MSL                         ((uint16_t)0x0001)            /*!<Master/Slave */
+#define  I2C_SR2_BUSY                        ((uint16_t)0x0002)            /*!<Bus Busy */
+#define  I2C_SR2_TRA                         ((uint16_t)0x0004)            /*!<Transmitter/Receiver */
+#define  I2C_SR2_GENCALL                     ((uint16_t)0x0010)            /*!<General Call Address (Slave mode) */
+#define  I2C_SR2_SMBDEFAULT                  ((uint16_t)0x0020)            /*!<SMBus Device Default Address (Slave mode) */
+#define  I2C_SR2_SMBHOST                     ((uint16_t)0x0040)            /*!<SMBus Host Header (Slave mode) */
+#define  I2C_SR2_DUALF                       ((uint16_t)0x0080)            /*!<Dual Flag (Slave mode) */
+#define  I2C_SR2_PEC                         ((uint16_t)0xFF00)            /*!<Packet Error Checking Register */
+
+/*******************  Bit definition for I2C_CCR register  ********************/
+#define  I2C_CCR_CCR                         ((uint16_t)0x0FFF)            /*!<Clock Control Register in Fast/Standard mode (Master mode) */
+#define  I2C_CCR_DUTY                        ((uint16_t)0x4000)            /*!<Fast Mode Duty Cycle */
+#define  I2C_CCR_FS                          ((uint16_t)0x8000)            /*!<I2C Master Mode Selection */
+
+/******************  Bit definition for I2C_TRISE register  *******************/
+#define  I2C_TRISE_TRISE                     ((uint8_t)0x3F)               /*!<Maximum Rise Time in Fast/Standard mode (Master mode) */
+
+/******************************************************************************/
+/*                                                                            */
+/*         Universal Synchronous Asynchronous Receiver Transmitter            */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for USART_SR register  *******************/
+#define  USART_SR_PE                         ((uint16_t)0x0001)            /*!<Parity Error */
+#define  USART_SR_FE                         ((uint16_t)0x0002)            /*!<Framing Error */
+#define  USART_SR_NE                         ((uint16_t)0x0004)            /*!<Noise Error Flag */
+#define  USART_SR_ORE                        ((uint16_t)0x0008)            /*!<OverRun Error */
+#define  USART_SR_IDLE                       ((uint16_t)0x0010)            /*!<IDLE line detected */
+#define  USART_SR_RXNE                       ((uint16_t)0x0020)            /*!<Read Data Register Not Empty */
+#define  USART_SR_TC                         ((uint16_t)0x0040)            /*!<Transmission Complete */
+#define  USART_SR_TXE                        ((uint16_t)0x0080)            /*!<Transmit Data Register Empty */
+#define  USART_SR_LBD                        ((uint16_t)0x0100)            /*!<LIN Break Detection Flag */
+#define  USART_SR_CTS                        ((uint16_t)0x0200)            /*!<CTS Flag */
+
+/*******************  Bit definition for USART_DR register  *******************/
+#define  USART_DR_DR                         ((uint16_t)0x01FF)            /*!<Data value */
+
+/******************  Bit definition for USART_BRR register  *******************/
+#define  USART_BRR_DIV_Fraction              ((uint16_t)0x000F)            /*!<Fraction of USARTDIV */
+#define  USART_BRR_DIV_Mantissa              ((uint16_t)0xFFF0)            /*!<Mantissa of USARTDIV */
+
+/******************  Bit definition for USART_CR1 register  *******************/
+#define  USART_CR1_SBK                       ((uint16_t)0x0001)            /*!<Send Break */
+#define  USART_CR1_RWU                       ((uint16_t)0x0002)            /*!<Receiver wakeup */
+#define  USART_CR1_RE                        ((uint16_t)0x0004)            /*!<Receiver Enable */
+#define  USART_CR1_TE                        ((uint16_t)0x0008)            /*!<Transmitter Enable */
+#define  USART_CR1_IDLEIE                    ((uint16_t)0x0010)            /*!<IDLE Interrupt Enable */
+#define  USART_CR1_RXNEIE                    ((uint16_t)0x0020)            /*!<RXNE Interrupt Enable */
+#define  USART_CR1_TCIE                      ((uint16_t)0x0040)            /*!<Transmission Complete Interrupt Enable */
+#define  USART_CR1_TXEIE                     ((uint16_t)0x0080)            /*!<PE Interrupt Enable */
+#define  USART_CR1_PEIE                      ((uint16_t)0x0100)            /*!<PE Interrupt Enable */
+#define  USART_CR1_PS                        ((uint16_t)0x0200)            /*!<Parity Selection */
+#define  USART_CR1_PCE                       ((uint16_t)0x0400)            /*!<Parity Control Enable */
+#define  USART_CR1_WAKE                      ((uint16_t)0x0800)            /*!<Wakeup method */
+#define  USART_CR1_M                         ((uint16_t)0x1000)            /*!<Word length */
+#define  USART_CR1_UE                        ((uint16_t)0x2000)            /*!<USART Enable */
+
+/******************  Bit definition for USART_CR2 register  *******************/
+#define  USART_CR2_ADD                       ((uint16_t)0x000F)            /*!<Address of the USART node */
+#define  USART_CR2_LBDL                      ((uint16_t)0x0020)            /*!<LIN Break Detection Length */
+#define  USART_CR2_LBDIE                     ((uint16_t)0x0040)            /*!<LIN Break Detection Interrupt Enable */
+#define  USART_CR2_LBCL                      ((uint16_t)0x0100)            /*!<Last Bit Clock pulse */
+#define  USART_CR2_CPHA                      ((uint16_t)0x0200)            /*!<Clock Phase */
+#define  USART_CR2_CPOL                      ((uint16_t)0x0400)            /*!<Clock Polarity */
+#define  USART_CR2_CLKEN                     ((uint16_t)0x0800)            /*!<Clock Enable */
+
+#define  USART_CR2_STOP                      ((uint16_t)0x3000)            /*!<STOP[1:0] bits (STOP bits) */
+#define  USART_CR2_STOP_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USART_CR2_STOP_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USART_CR2_LINEN                     ((uint16_t)0x4000)            /*!<LIN mode enable */
+
+/******************  Bit definition for USART_CR3 register  *******************/
+#define  USART_CR3_EIE                       ((uint16_t)0x0001)            /*!<Error Interrupt Enable */
+#define  USART_CR3_IREN                      ((uint16_t)0x0002)            /*!<IrDA mode Enable */
+#define  USART_CR3_IRLP                      ((uint16_t)0x0004)            /*!<IrDA Low-Power */
+#define  USART_CR3_HDSEL                     ((uint16_t)0x0008)            /*!<Half-Duplex Selection */
+#define  USART_CR3_NACK                      ((uint16_t)0x0010)            /*!<Smartcard NACK enable */
+#define  USART_CR3_SCEN                      ((uint16_t)0x0020)            /*!<Smartcard mode enable */
+#define  USART_CR3_DMAR                      ((uint16_t)0x0040)            /*!<DMA Enable Receiver */
+#define  USART_CR3_DMAT                      ((uint16_t)0x0080)            /*!<DMA Enable Transmitter */
+#define  USART_CR3_RTSE                      ((uint16_t)0x0100)            /*!<RTS Enable */
+#define  USART_CR3_CTSE                      ((uint16_t)0x0200)            /*!<CTS Enable */
+#define  USART_CR3_CTSIE                     ((uint16_t)0x0400)            /*!<CTS Interrupt Enable */
+
+/******************  Bit definition for USART_GTPR register  ******************/
+#define  USART_GTPR_PSC                      ((uint16_t)0x00FF)            /*!<PSC[7:0] bits (Prescaler value) */
+#define  USART_GTPR_PSC_0                    ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  USART_GTPR_PSC_1                    ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  USART_GTPR_PSC_2                    ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  USART_GTPR_PSC_3                    ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  USART_GTPR_PSC_4                    ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  USART_GTPR_PSC_5                    ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  USART_GTPR_PSC_6                    ((uint16_t)0x0040)            /*!<Bit 6 */
+#define  USART_GTPR_PSC_7                    ((uint16_t)0x0080)            /*!<Bit 7 */
+
+#define  USART_GTPR_GT                       ((uint16_t)0xFF00)            /*!<Guard time value */
+
+/******************************************************************************/
+/*                                                                            */
+/*                                 Debug MCU                                  */
+/*                                                                            */
+/******************************************************************************/
+
+/****************  Bit definition for DBGMCU_IDCODE register  *****************/
+#define  DBGMCU_IDCODE_DEV_ID                ((uint32_t)0x00000FFF)        /*!<Device Identifier */
+
+#define  DBGMCU_IDCODE_REV_ID                ((uint32_t)0xFFFF0000)        /*!<REV_ID[15:0] bits (Revision Identifier) */
+#define  DBGMCU_IDCODE_REV_ID_0              ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  DBGMCU_IDCODE_REV_ID_1              ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  DBGMCU_IDCODE_REV_ID_2              ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  DBGMCU_IDCODE_REV_ID_3              ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  DBGMCU_IDCODE_REV_ID_4              ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  DBGMCU_IDCODE_REV_ID_5              ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  DBGMCU_IDCODE_REV_ID_6              ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  DBGMCU_IDCODE_REV_ID_7              ((uint32_t)0x00800000)        /*!<Bit 7 */
+#define  DBGMCU_IDCODE_REV_ID_8              ((uint32_t)0x01000000)        /*!<Bit 8 */
+#define  DBGMCU_IDCODE_REV_ID_9              ((uint32_t)0x02000000)        /*!<Bit 9 */
+#define  DBGMCU_IDCODE_REV_ID_10             ((uint32_t)0x04000000)        /*!<Bit 10 */
+#define  DBGMCU_IDCODE_REV_ID_11             ((uint32_t)0x08000000)        /*!<Bit 11 */
+#define  DBGMCU_IDCODE_REV_ID_12             ((uint32_t)0x10000000)        /*!<Bit 12 */
+#define  DBGMCU_IDCODE_REV_ID_13             ((uint32_t)0x20000000)        /*!<Bit 13 */
+#define  DBGMCU_IDCODE_REV_ID_14             ((uint32_t)0x40000000)        /*!<Bit 14 */
+#define  DBGMCU_IDCODE_REV_ID_15             ((uint32_t)0x80000000)        /*!<Bit 15 */
+
+/******************  Bit definition for DBGMCU_CR register  *******************/
+#define  DBGMCU_CR_DBG_SLEEP                 ((uint32_t)0x00000001)        /*!<Debug Sleep Mode */
+#define  DBGMCU_CR_DBG_STOP                  ((uint32_t)0x00000002)        /*!<Debug Stop Mode */
+#define  DBGMCU_CR_DBG_STANDBY               ((uint32_t)0x00000004)        /*!<Debug Standby mode */
+#define  DBGMCU_CR_TRACE_IOEN                ((uint32_t)0x00000020)        /*!<Trace Pin Assignment Control */
+
+#define  DBGMCU_CR_TRACE_MODE                ((uint32_t)0x000000C0)        /*!<TRACE_MODE[1:0] bits (Trace Pin Assignment Control) */
+#define  DBGMCU_CR_TRACE_MODE_0              ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  DBGMCU_CR_TRACE_MODE_1              ((uint32_t)0x00000080)        /*!<Bit 1 */
+
+#define  DBGMCU_CR_DBG_IWDG_STOP             ((uint32_t)0x00000100)        /*!<Debug Independent Watchdog stopped when Core is halted */
+#define  DBGMCU_CR_DBG_WWDG_STOP             ((uint32_t)0x00000200)        /*!<Debug Window Watchdog stopped when Core is halted */
+#define  DBGMCU_CR_DBG_TIM1_STOP             ((uint32_t)0x00000400)        /*!<TIM1 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_TIM2_STOP             ((uint32_t)0x00000800)        /*!<TIM2 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_TIM3_STOP             ((uint32_t)0x00001000)        /*!<TIM3 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_TIM4_STOP             ((uint32_t)0x00002000)        /*!<TIM4 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_CAN1_STOP             ((uint32_t)0x00004000)        /*!<Debug CAN1 stopped when Core is halted */
+#define  DBGMCU_CR_DBG_I2C1_SMBUS_TIMEOUT    ((uint32_t)0x00008000)        /*!<SMBUS timeout mode stopped when Core is halted */
+#define  DBGMCU_CR_DBG_I2C2_SMBUS_TIMEOUT    ((uint32_t)0x00010000)        /*!<SMBUS timeout mode stopped when Core is halted */
+#define  DBGMCU_CR_DBG_TIM8_STOP             ((uint32_t)0x00020000)        /*!<TIM8 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_TIM5_STOP             ((uint32_t)0x00040000)        /*!<TIM5 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_TIM6_STOP             ((uint32_t)0x00080000)        /*!<TIM6 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_TIM7_STOP             ((uint32_t)0x00100000)        /*!<TIM7 counter stopped when core is halted */
+#define  DBGMCU_CR_DBG_CAN2_STOP             ((uint32_t)0x00200000)        /*!<Debug CAN2 stopped when Core is halted */
+
+/******************************************************************************/
+/*                                                                            */
+/*                      FLASH and Option Bytes Registers                      */
+/*                                                                            */
+/******************************************************************************/
+
+/*******************  Bit definition for FLASH_ACR register  ******************/
+#define  FLASH_ACR_LATENCY                   ((uint8_t)0x03)               /*!<LATENCY[2:0] bits (Latency) */
+#define  FLASH_ACR_LATENCY_0                 ((uint8_t)0x00)               /*!<Bit 0 */
+#define  FLASH_ACR_LATENCY_1                 ((uint8_t)0x01)               /*!<Bit 0 */
+#define  FLASH_ACR_LATENCY_2                 ((uint8_t)0x02)               /*!<Bit 1 */
+
+#define  FLASH_ACR_HLFCYA                    ((uint8_t)0x08)               /*!<Flash Half Cycle Access Enable */
+#define  FLASH_ACR_PRFTBE                    ((uint8_t)0x10)               /*!<Prefetch Buffer Enable */
+#define  FLASH_ACR_PRFTBS                    ((uint8_t)0x20)               /*!<Prefetch Buffer Status */
+
+/******************  Bit definition for FLASH_KEYR register  ******************/
+#define  FLASH_KEYR_FKEYR                    ((uint32_t)0xFFFFFFFF)        /*!<FPEC Key */
+
+/*****************  Bit definition for FLASH_OPTKEYR register  ****************/
+#define  FLASH_OPTKEYR_OPTKEYR               ((uint32_t)0xFFFFFFFF)        /*!<Option Byte Key */
+
+/******************  Bit definition for FLASH_SR register  *******************/
+#define  FLASH_SR_BSY                        ((uint8_t)0x01)               /*!<Busy */
+#define  FLASH_SR_PGERR                      ((uint8_t)0x04)               /*!<Programming Error */
+#define  FLASH_SR_WRPRTERR                   ((uint8_t)0x10)               /*!<Write Protection Error */
+#define  FLASH_SR_EOP                        ((uint8_t)0x20)               /*!<End of operation */
+
+/*******************  Bit definition for FLASH_CR register  *******************/
+#define  FLASH_CR_PG                         ((uint16_t)0x0001)            /*!<Programming */
+#define  FLASH_CR_PER                        ((uint16_t)0x0002)            /*!<Page Erase */
+#define  FLASH_CR_MER                        ((uint16_t)0x0004)            /*!<Mass Erase */
+#define  FLASH_CR_OPTPG                      ((uint16_t)0x0010)            /*!<Option Byte Programming */
+#define  FLASH_CR_OPTER                      ((uint16_t)0x0020)            /*!<Option Byte Erase */
+#define  FLASH_CR_STRT                       ((uint16_t)0x0040)            /*!<Start */
+#define  FLASH_CR_LOCK                       ((uint16_t)0x0080)            /*!<Lock */
+#define  FLASH_CR_OPTWRE                     ((uint16_t)0x0200)            /*!<Option Bytes Write Enable */
+#define  FLASH_CR_ERRIE                      ((uint16_t)0x0400)            /*!<Error Interrupt Enable */
+#define  FLASH_CR_EOPIE                      ((uint16_t)0x1000)            /*!<End of operation interrupt enable */
+
+/*******************  Bit definition for FLASH_AR register  *******************/
+#define  FLASH_AR_FAR                        ((uint32_t)0xFFFFFFFF)        /*!<Flash Address */
+
+/******************  Bit definition for FLASH_OBR register  *******************/
+#define  FLASH_OBR_OPTERR                    ((uint16_t)0x0001)            /*!<Option Byte Error */
+#define  FLASH_OBR_RDPRT                     ((uint16_t)0x0002)            /*!<Read protection */
+
+#define  FLASH_OBR_USER                      ((uint16_t)0x03FC)            /*!<User Option Bytes */
+#define  FLASH_OBR_WDG_SW                    ((uint16_t)0x0004)            /*!<WDG_SW */
+#define  FLASH_OBR_nRST_STOP                 ((uint16_t)0x0008)            /*!<nRST_STOP */
+#define  FLASH_OBR_nRST_STDBY                ((uint16_t)0x0010)            /*!<nRST_STDBY */
+#define  FLASH_OBR_Notused                   ((uint16_t)0x03E0)            /*!<Not used */
+
+/******************  Bit definition for FLASH_WRPR register  ******************/
+#define  FLASH_WRPR_WRP                        ((uint32_t)0xFFFFFFFF)        /*!<Write Protect */
+
+/*----------------------------------------------------------------------------*/
+
+/******************  Bit definition for FLASH_RDP register  *******************/
+#define  FLASH_RDP_RDP                       ((uint32_t)0x000000FF)        /*!<Read protection option byte */
+#define  FLASH_RDP_nRDP                      ((uint32_t)0x0000FF00)        /*!<Read protection complemented option byte */
+
+/******************  Bit definition for FLASH_USER register  ******************/
+#define  FLASH_USER_USER                     ((uint32_t)0x00FF0000)        /*!<User option byte */
+#define  FLASH_USER_nUSER                    ((uint32_t)0xFF000000)        /*!<User complemented option byte */
+
+/******************  Bit definition for FLASH_Data0 register  *****************/
+#define  FLASH_Data0_Data0                   ((uint32_t)0x000000FF)        /*!<User data storage option byte */
+#define  FLASH_Data0_nData0                  ((uint32_t)0x0000FF00)        /*!<User data storage complemented option byte */
+
+/******************  Bit definition for FLASH_Data1 register  *****************/
+#define  FLASH_Data1_Data1                   ((uint32_t)0x00FF0000)        /*!<User data storage option byte */
+#define  FLASH_Data1_nData1                  ((uint32_t)0xFF000000)        /*!<User data storage complemented option byte */
+
+/******************  Bit definition for FLASH_WRP0 register  ******************/
+#define  FLASH_WRP0_WRP0                     ((uint32_t)0x000000FF)        /*!<Flash memory write protection option bytes */
+#define  FLASH_WRP0_nWRP0                    ((uint32_t)0x0000FF00)        /*!<Flash memory write protection complemented option bytes */
+
+/******************  Bit definition for FLASH_WRP1 register  ******************/
+#define  FLASH_WRP1_WRP1                     ((uint32_t)0x00FF0000)        /*!<Flash memory write protection option bytes */
+#define  FLASH_WRP1_nWRP1                    ((uint32_t)0xFF000000)        /*!<Flash memory write protection complemented option bytes */
+
+/******************  Bit definition for FLASH_WRP2 register  ******************/
+#define  FLASH_WRP2_WRP2                     ((uint32_t)0x000000FF)        /*!<Flash memory write protection option bytes */
+#define  FLASH_WRP2_nWRP2                    ((uint32_t)0x0000FF00)        /*!<Flash memory write protection complemented option bytes */
+
+/******************  Bit definition for FLASH_WRP3 register  ******************/
+#define  FLASH_WRP3_WRP3                     ((uint32_t)0x00FF0000)        /*!<Flash memory write protection option bytes */
+#define  FLASH_WRP3_nWRP3                    ((uint32_t)0xFF000000)        /*!<Flash memory write protection complemented option bytes */
+
+#ifdef STM32F10X_CL
+/******************************************************************************/
+/*                Ethernet MAC Registers bits definitions                     */
+/******************************************************************************/
+/* Bit definition for Ethernet MAC Control Register register */
+#define ETH_MACCR_WD      ((uint32_t)0x00800000)  /* Watchdog disable */
+#define ETH_MACCR_JD      ((uint32_t)0x00400000)  /* Jabber disable */
+#define ETH_MACCR_IFG     ((uint32_t)0x000E0000)  /* Inter-frame gap */
+  #define ETH_MACCR_IFG_96Bit     ((uint32_t)0x00000000)  /* Minimum IFG between frames during transmission is 96Bit */
+  #define ETH_MACCR_IFG_88Bit     ((uint32_t)0x00020000)  /* Minimum IFG between frames during transmission is 88Bit */
+  #define ETH_MACCR_IFG_80Bit     ((uint32_t)0x00040000)  /* Minimum IFG between frames during transmission is 80Bit */
+  #define ETH_MACCR_IFG_72Bit     ((uint32_t)0x00060000)  /* Minimum IFG between frames during transmission is 72Bit */
+  #define ETH_MACCR_IFG_64Bit     ((uint32_t)0x00080000)  /* Minimum IFG between frames during transmission is 64Bit */        
+  #define ETH_MACCR_IFG_56Bit     ((uint32_t)0x000A0000)  /* Minimum IFG between frames during transmission is 56Bit */
+  #define ETH_MACCR_IFG_48Bit     ((uint32_t)0x000C0000)  /* Minimum IFG between frames during transmission is 48Bit */
+  #define ETH_MACCR_IFG_40Bit     ((uint32_t)0x000E0000)  /* Minimum IFG between frames during transmission is 40Bit */              
+#define ETH_MACCR_CSD     ((uint32_t)0x00010000)  /* Carrier sense disable (during transmission) */
+#define ETH_MACCR_FES     ((uint32_t)0x00004000)  /* Fast ethernet speed */
+#define ETH_MACCR_ROD     ((uint32_t)0x00002000)  /* Receive own disable */
+#define ETH_MACCR_LM      ((uint32_t)0x00001000)  /* loopback mode */
+#define ETH_MACCR_DM      ((uint32_t)0x00000800)  /* Duplex mode */
+#define ETH_MACCR_IPCO    ((uint32_t)0x00000400)  /* IP Checksum offload */
+#define ETH_MACCR_RD      ((uint32_t)0x00000200)  /* Retry disable */
+#define ETH_MACCR_APCS    ((uint32_t)0x00000080)  /* Automatic Pad/CRC stripping */
+#define ETH_MACCR_BL      ((uint32_t)0x00000060)  /* Back-off limit: random integer number (r) of slot time delays before rescheduling
+                                                       a transmission attempt during retries after a collision: 0 =< r <2^k */
+  #define ETH_MACCR_BL_10    ((uint32_t)0x00000000)  /* k = min (n, 10) */
+  #define ETH_MACCR_BL_8     ((uint32_t)0x00000020)  /* k = min (n, 8) */
+  #define ETH_MACCR_BL_4     ((uint32_t)0x00000040)  /* k = min (n, 4) */
+  #define ETH_MACCR_BL_1     ((uint32_t)0x00000060)  /* k = min (n, 1) */ 
+#define ETH_MACCR_DC      ((uint32_t)0x00000010)  /* Defferal check */
+#define ETH_MACCR_TE      ((uint32_t)0x00000008)  /* Transmitter enable */
+#define ETH_MACCR_RE      ((uint32_t)0x00000004)  /* Receiver enable */
+
+/* Bit definition for Ethernet MAC Frame Filter Register */
+#define ETH_MACFFR_RA     ((uint32_t)0x80000000)  /* Receive all */ 
+#define ETH_MACFFR_HPF    ((uint32_t)0x00000400)  /* Hash or perfect filter */ 
+#define ETH_MACFFR_SAF    ((uint32_t)0x00000200)  /* Source address filter enable */ 
+#define ETH_MACFFR_SAIF   ((uint32_t)0x00000100)  /* SA inverse filtering */ 
+#define ETH_MACFFR_PCF    ((uint32_t)0x000000C0)  /* Pass control frames: 3 cases */
+  #define ETH_MACFFR_PCF_BlockAll                ((uint32_t)0x00000040)  /* MAC filters all control frames from reaching the application */
+  #define ETH_MACFFR_PCF_ForwardAll              ((uint32_t)0x00000080)  /* MAC forwards all control frames to application even if they fail the Address Filter */
+  #define ETH_MACFFR_PCF_ForwardPassedAddrFilter ((uint32_t)0x000000C0)  /* MAC forwards control frames that pass the Address Filter. */ 
+#define ETH_MACFFR_BFD    ((uint32_t)0x00000020)  /* Broadcast frame disable */ 
+#define ETH_MACFFR_PAM 	  ((uint32_t)0x00000010)  /* Pass all mutlicast */ 
+#define ETH_MACFFR_DAIF   ((uint32_t)0x00000008)  /* DA Inverse filtering */ 
+#define ETH_MACFFR_HM     ((uint32_t)0x00000004)  /* Hash multicast */ 
+#define ETH_MACFFR_HU     ((uint32_t)0x00000002)  /* Hash unicast */
+#define ETH_MACFFR_PM     ((uint32_t)0x00000001)  /* Promiscuous mode */
+
+/* Bit definition for Ethernet MAC Hash Table High Register */
+#define ETH_MACHTHR_HTH   ((uint32_t)0xFFFFFFFF)  /* Hash table high */
+
+/* Bit definition for Ethernet MAC Hash Table Low Register */
+#define ETH_MACHTLR_HTL   ((uint32_t)0xFFFFFFFF)  /* Hash table low */
+
+/* Bit definition for Ethernet MAC MII Address Register */
+#define ETH_MACMIIAR_PA   ((uint32_t)0x0000F800)  /* Physical layer address */ 
+#define ETH_MACMIIAR_MR   ((uint32_t)0x000007C0)  /* MII register in the selected PHY */ 
+#define ETH_MACMIIAR_CR   ((uint32_t)0x0000001C)  /* CR clock range: 6 cases */ 
+  #define ETH_MACMIIAR_CR_Div42   ((uint32_t)0x00000000)  /* HCLK:60-72 MHz; MDC clock= HCLK/42 */
+  #define ETH_MACMIIAR_CR_Div16   ((uint32_t)0x00000008)  /* HCLK:20-35 MHz; MDC clock= HCLK/16 */
+  #define ETH_MACMIIAR_CR_Div26   ((uint32_t)0x0000000C)  /* HCLK:35-60 MHz; MDC clock= HCLK/26 */
+#define ETH_MACMIIAR_MW   ((uint32_t)0x00000002)  /* MII write */ 
+#define ETH_MACMIIAR_MB   ((uint32_t)0x00000001)  /* MII busy */ 
+  
+/* Bit definition for Ethernet MAC MII Data Register */
+#define ETH_MACMIIDR_MD   ((uint32_t)0x0000FFFF)  /* MII data: read/write data from/to PHY */
+
+/* Bit definition for Ethernet MAC Flow Control Register */
+#define ETH_MACFCR_PT     ((uint32_t)0xFFFF0000)  /* Pause time */
+#define ETH_MACFCR_ZQPD   ((uint32_t)0x00000080)  /* Zero-quanta pause disable */
+#define ETH_MACFCR_PLT    ((uint32_t)0x00000030)  /* Pause low threshold: 4 cases */
+  #define ETH_MACFCR_PLT_Minus4   ((uint32_t)0x00000000)  /* Pause time minus 4 slot times */
+  #define ETH_MACFCR_PLT_Minus28  ((uint32_t)0x00000010)  /* Pause time minus 28 slot times */
+  #define ETH_MACFCR_PLT_Minus144 ((uint32_t)0x00000020)  /* Pause time minus 144 slot times */
+  #define ETH_MACFCR_PLT_Minus256 ((uint32_t)0x00000030)  /* Pause time minus 256 slot times */      
+#define ETH_MACFCR_UPFD   ((uint32_t)0x00000008)  /* Unicast pause frame detect */
+#define ETH_MACFCR_RFCE   ((uint32_t)0x00000004)  /* Receive flow control enable */
+#define ETH_MACFCR_TFCE   ((uint32_t)0x00000002)  /* Transmit flow control enable */
+#define ETH_MACFCR_FCBBPA ((uint32_t)0x00000001)  /* Flow control busy/backpressure activate */
+
+/* Bit definition for Ethernet MAC VLAN Tag Register */
+#define ETH_MACVLANTR_VLANTC ((uint32_t)0x00010000)  /* 12-bit VLAN tag comparison */
+#define ETH_MACVLANTR_VLANTI ((uint32_t)0x0000FFFF)  /* VLAN tag identifier (for receive frames) */
+
+/* Bit definition for Ethernet MAC Remote Wake-UpFrame Filter Register */ 
+#define ETH_MACRWUFFR_D   ((uint32_t)0xFFFFFFFF)  /* Wake-up frame filter register data */
+/* Eight sequential Writes to this address (offset 0x28) will write all Wake-UpFrame Filter Registers.
+   Eight sequential Reads from this address (offset 0x28) will read all Wake-UpFrame Filter Registers. */
+/* Wake-UpFrame Filter Reg0 : Filter 0 Byte Mask
+   Wake-UpFrame Filter Reg1 : Filter 1 Byte Mask
+   Wake-UpFrame Filter Reg2 : Filter 2 Byte Mask
+   Wake-UpFrame Filter Reg3 : Filter 3 Byte Mask
+   Wake-UpFrame Filter Reg4 : RSVD - Filter3 Command - RSVD - Filter2 Command - 
+                              RSVD - Filter1 Command - RSVD - Filter0 Command
+   Wake-UpFrame Filter Re5 : Filter3 Offset - Filter2 Offset - Filter1 Offset - Filter0 Offset
+   Wake-UpFrame Filter Re6 : Filter1 CRC16 - Filter0 CRC16
+   Wake-UpFrame Filter Re7 : Filter3 CRC16 - Filter2 CRC16 */
+
+/* Bit definition for Ethernet MAC PMT Control and Status Register */ 
+#define ETH_MACPMTCSR_WFFRPR ((uint32_t)0x80000000)  /* Wake-Up Frame Filter Register Pointer Reset */
+#define ETH_MACPMTCSR_GU     ((uint32_t)0x00000200)  /* Global Unicast */
+#define ETH_MACPMTCSR_WFR    ((uint32_t)0x00000040)  /* Wake-Up Frame Received */
+#define ETH_MACPMTCSR_MPR    ((uint32_t)0x00000020)  /* Magic Packet Received */
+#define ETH_MACPMTCSR_WFE    ((uint32_t)0x00000004)  /* Wake-Up Frame Enable */
+#define ETH_MACPMTCSR_MPE    ((uint32_t)0x00000002)  /* Magic Packet Enable */
+#define ETH_MACPMTCSR_PD     ((uint32_t)0x00000001)  /* Power Down */
+
+/* Bit definition for Ethernet MAC Status Register */
+#define ETH_MACSR_TSTS      ((uint32_t)0x00000200)  /* Time stamp trigger status */
+#define ETH_MACSR_MMCTS     ((uint32_t)0x00000040)  /* MMC transmit status */
+#define ETH_MACSR_MMMCRS    ((uint32_t)0x00000020)  /* MMC receive status */
+#define ETH_MACSR_MMCS      ((uint32_t)0x00000010)  /* MMC status */
+#define ETH_MACSR_PMTS      ((uint32_t)0x00000008)  /* PMT status */
+
+/* Bit definition for Ethernet MAC Interrupt Mask Register */
+#define ETH_MACIMR_TSTIM     ((uint32_t)0x00000200)  /* Time stamp trigger interrupt mask */
+#define ETH_MACIMR_PMTIM     ((uint32_t)0x00000008)  /* PMT interrupt mask */
+
+/* Bit definition for Ethernet MAC Address0 High Register */
+#define ETH_MACA0HR_MACA0H   ((uint32_t)0x0000FFFF)  /* MAC address0 high */
+
+/* Bit definition for Ethernet MAC Address0 Low Register */
+#define ETH_MACA0LR_MACA0L   ((uint32_t)0xFFFFFFFF)  /* MAC address0 low */
+
+/* Bit definition for Ethernet MAC Address1 High Register */
+#define ETH_MACA1HR_AE       ((uint32_t)0x80000000)  /* Address enable */
+#define ETH_MACA1HR_SA       ((uint32_t)0x40000000)  /* Source address */
+#define ETH_MACA1HR_MBC      ((uint32_t)0x3F000000)  /* Mask byte control: bits to mask for comparison of the MAC Address bytes */
+  #define ETH_MACA1HR_MBC_HBits15_8    ((uint32_t)0x20000000)  /* Mask MAC Address high reg bits [15:8] */
+  #define ETH_MACA1HR_MBC_HBits7_0     ((uint32_t)0x10000000)  /* Mask MAC Address high reg bits [7:0] */
+  #define ETH_MACA1HR_MBC_LBits31_24   ((uint32_t)0x08000000)  /* Mask MAC Address low reg bits [31:24] */
+  #define ETH_MACA1HR_MBC_LBits23_16   ((uint32_t)0x04000000)  /* Mask MAC Address low reg bits [23:16] */
+  #define ETH_MACA1HR_MBC_LBits15_8    ((uint32_t)0x02000000)  /* Mask MAC Address low reg bits [15:8] */
+  #define ETH_MACA1HR_MBC_LBits7_0     ((uint32_t)0x01000000)  /* Mask MAC Address low reg bits [7:0] */ 
+#define ETH_MACA1HR_MACA1H   ((uint32_t)0x0000FFFF)  /* MAC address1 high */
+
+/* Bit definition for Ethernet MAC Address1 Low Register */
+#define ETH_MACA1LR_MACA1L   ((uint32_t)0xFFFFFFFF)  /* MAC address1 low */
+
+/* Bit definition for Ethernet MAC Address2 High Register */
+#define ETH_MACA2HR_AE       ((uint32_t)0x80000000)  /* Address enable */
+#define ETH_MACA2HR_SA       ((uint32_t)0x40000000)  /* Source address */
+#define ETH_MACA2HR_MBC      ((uint32_t)0x3F000000)  /* Mask byte control */
+  #define ETH_MACA2HR_MBC_HBits15_8    ((uint32_t)0x20000000)  /* Mask MAC Address high reg bits [15:8] */
+  #define ETH_MACA2HR_MBC_HBits7_0     ((uint32_t)0x10000000)  /* Mask MAC Address high reg bits [7:0] */
+  #define ETH_MACA2HR_MBC_LBits31_24   ((uint32_t)0x08000000)  /* Mask MAC Address low reg bits [31:24] */
+  #define ETH_MACA2HR_MBC_LBits23_16   ((uint32_t)0x04000000)  /* Mask MAC Address low reg bits [23:16] */
+  #define ETH_MACA2HR_MBC_LBits15_8    ((uint32_t)0x02000000)  /* Mask MAC Address low reg bits [15:8] */
+  #define ETH_MACA2HR_MBC_LBits7_0     ((uint32_t)0x01000000)  /* Mask MAC Address low reg bits [70] */
+#define ETH_MACA2HR_MACA2H   ((uint32_t)0x0000FFFF)  /* MAC address1 high */
+
+/* Bit definition for Ethernet MAC Address2 Low Register */
+#define ETH_MACA2LR_MACA2L   ((uint32_t)0xFFFFFFFF)  /* MAC address2 low */
+
+/* Bit definition for Ethernet MAC Address3 High Register */
+#define ETH_MACA3HR_AE       ((uint32_t)0x80000000)  /* Address enable */
+#define ETH_MACA3HR_SA       ((uint32_t)0x40000000)  /* Source address */
+#define ETH_MACA3HR_MBC      ((uint32_t)0x3F000000)  /* Mask byte control */
+  #define ETH_MACA3HR_MBC_HBits15_8    ((uint32_t)0x20000000)  /* Mask MAC Address high reg bits [15:8] */
+  #define ETH_MACA3HR_MBC_HBits7_0     ((uint32_t)0x10000000)  /* Mask MAC Address high reg bits [7:0] */
+  #define ETH_MACA3HR_MBC_LBits31_24   ((uint32_t)0x08000000)  /* Mask MAC Address low reg bits [31:24] */
+  #define ETH_MACA3HR_MBC_LBits23_16   ((uint32_t)0x04000000)  /* Mask MAC Address low reg bits [23:16] */
+  #define ETH_MACA3HR_MBC_LBits15_8    ((uint32_t)0x02000000)  /* Mask MAC Address low reg bits [15:8] */
+  #define ETH_MACA3HR_MBC_LBits7_0     ((uint32_t)0x01000000)  /* Mask MAC Address low reg bits [70] */
+#define ETH_MACA3HR_MACA3H   ((uint32_t)0x0000FFFF)  /* MAC address3 high */
+
+/* Bit definition for Ethernet MAC Address3 Low Register */
+#define ETH_MACA3LR_MACA3L   ((uint32_t)0xFFFFFFFF)  /* MAC address3 low */
+
+/******************************************************************************/
+/*                Ethernet MMC Registers bits definition                      */
+/******************************************************************************/
+
+/* Bit definition for Ethernet MMC Contol Register */
+#define ETH_MMCCR_MCF        ((uint32_t)0x00000008)  /* MMC Counter Freeze */
+#define ETH_MMCCR_ROR        ((uint32_t)0x00000004)  /* Reset on Read */
+#define ETH_MMCCR_CSR        ((uint32_t)0x00000002)  /* Counter Stop Rollover */
+#define ETH_MMCCR_CR         ((uint32_t)0x00000001)  /* Counters Reset */
+
+/* Bit definition for Ethernet MMC Receive Interrupt Register */
+#define ETH_MMCRIR_RGUFS     ((uint32_t)0x00020000)  /* Set when Rx good unicast frames counter reaches half the maximum value */
+#define ETH_MMCRIR_RFAES     ((uint32_t)0x00000040)  /* Set when Rx alignment error counter reaches half the maximum value */
+#define ETH_MMCRIR_RFCES     ((uint32_t)0x00000020)  /* Set when Rx crc error counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Transmit Interrupt Register */
+#define ETH_MMCTIR_TGFS      ((uint32_t)0x00200000)  /* Set when Tx good frame count counter reaches half the maximum value */
+#define ETH_MMCTIR_TGFMSCS   ((uint32_t)0x00008000)  /* Set when Tx good multi col counter reaches half the maximum value */
+#define ETH_MMCTIR_TGFSCS    ((uint32_t)0x00004000)  /* Set when Tx good single col counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Receive Interrupt Mask Register */
+#define ETH_MMCRIMR_RGUFM    ((uint32_t)0x00020000)  /* Mask the interrupt when Rx good unicast frames counter reaches half the maximum value */
+#define ETH_MMCRIMR_RFAEM    ((uint32_t)0x00000040)  /* Mask the interrupt when when Rx alignment error counter reaches half the maximum value */
+#define ETH_MMCRIMR_RFCEM    ((uint32_t)0x00000020)  /* Mask the interrupt when Rx crc error counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Transmit Interrupt Mask Register */
+#define ETH_MMCTIMR_TGFM     ((uint32_t)0x00200000)  /* Mask the interrupt when Tx good frame count counter reaches half the maximum value */
+#define ETH_MMCTIMR_TGFMSCM  ((uint32_t)0x00008000)  /* Mask the interrupt when Tx good multi col counter reaches half the maximum value */
+#define ETH_MMCTIMR_TGFSCM   ((uint32_t)0x00004000)  /* Mask the interrupt when Tx good single col counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Transmitted Good Frames after Single Collision Counter Register */
+#define ETH_MMCTGFSCCR_TGFSCC     ((uint32_t)0xFFFFFFFF)  /* Number of successfully transmitted frames after a single collision in Half-duplex mode. */
+
+/* Bit definition for Ethernet MMC Transmitted Good Frames after More than a Single Collision Counter Register */
+#define ETH_MMCTGFMSCCR_TGFMSCC   ((uint32_t)0xFFFFFFFF)  /* Number of successfully transmitted frames after more than a single collision in Half-duplex mode. */
+
+/* Bit definition for Ethernet MMC Transmitted Good Frames Counter Register */
+#define ETH_MMCTGFCR_TGFC    ((uint32_t)0xFFFFFFFF)  /* Number of good frames transmitted. */
+
+/* Bit definition for Ethernet MMC Received Frames with CRC Error Counter Register */
+#define ETH_MMCRFCECR_RFCEC  ((uint32_t)0xFFFFFFFF)  /* Number of frames received with CRC error. */
+
+/* Bit definition for Ethernet MMC Received Frames with Alignement Error Counter Register */
+#define ETH_MMCRFAECR_RFAEC  ((uint32_t)0xFFFFFFFF)  /* Number of frames received with alignment (dribble) error */
+
+/* Bit definition for Ethernet MMC Received Good Unicast Frames Counter Register */
+#define ETH_MMCRGUFCR_RGUFC  ((uint32_t)0xFFFFFFFF)  /* Number of good unicast frames received. */
+
+/******************************************************************************/
+/*               Ethernet PTP Registers bits definition                       */
+/******************************************************************************/
+
+/* Bit definition for Ethernet PTP Time Stamp Contol Register */
+#define ETH_PTPTSCR_TSARU    ((uint32_t)0x00000020)  /* Addend register update */
+#define ETH_PTPTSCR_TSITE    ((uint32_t)0x00000010)  /* Time stamp interrupt trigger enable */
+#define ETH_PTPTSCR_TSSTU    ((uint32_t)0x00000008)  /* Time stamp update */
+#define ETH_PTPTSCR_TSSTI    ((uint32_t)0x00000004)  /* Time stamp initialize */
+#define ETH_PTPTSCR_TSFCU    ((uint32_t)0x00000002)  /* Time stamp fine or coarse update */
+#define ETH_PTPTSCR_TSE      ((uint32_t)0x00000001)  /* Time stamp enable */
+
+/* Bit definition for Ethernet PTP Sub-Second Increment Register */
+#define ETH_PTPSSIR_STSSI    ((uint32_t)0x000000FF)  /* System time Sub-second increment value */
+
+/* Bit definition for Ethernet PTP Time Stamp High Register */
+#define ETH_PTPTSHR_STS      ((uint32_t)0xFFFFFFFF)  /* System Time second */
+
+/* Bit definition for Ethernet PTP Time Stamp Low Register */
+#define ETH_PTPTSLR_STPNS    ((uint32_t)0x80000000)  /* System Time Positive or negative time */
+#define ETH_PTPTSLR_STSS     ((uint32_t)0x7FFFFFFF)  /* System Time sub-seconds */
+
+/* Bit definition for Ethernet PTP Time Stamp High Update Register */
+#define ETH_PTPTSHUR_TSUS    ((uint32_t)0xFFFFFFFF)  /* Time stamp update seconds */
+
+/* Bit definition for Ethernet PTP Time Stamp Low Update Register */
+#define ETH_PTPTSLUR_TSUPNS  ((uint32_t)0x80000000)  /* Time stamp update Positive or negative time */
+#define ETH_PTPTSLUR_TSUSS   ((uint32_t)0x7FFFFFFF)  /* Time stamp update sub-seconds */
+
+/* Bit definition for Ethernet PTP Time Stamp Addend Register */
+#define ETH_PTPTSAR_TSA      ((uint32_t)0xFFFFFFFF)  /* Time stamp addend */
+
+/* Bit definition for Ethernet PTP Target Time High Register */
+#define ETH_PTPTTHR_TTSH     ((uint32_t)0xFFFFFFFF)  /* Target time stamp high */
+
+/* Bit definition for Ethernet PTP Target Time Low Register */
+#define ETH_PTPTTLR_TTSL     ((uint32_t)0xFFFFFFFF)  /* Target time stamp low */
+
+/******************************************************************************/
+/*                 Ethernet DMA Registers bits definition                     */
+/******************************************************************************/
+
+/* Bit definition for Ethernet DMA Bus Mode Register */
+#define ETH_DMABMR_AAB       ((uint32_t)0x02000000)  /* Address-Aligned beats */
+#define ETH_DMABMR_FPM        ((uint32_t)0x01000000)  /* 4xPBL mode */
+#define ETH_DMABMR_USP       ((uint32_t)0x00800000)  /* Use separate PBL */
+#define ETH_DMABMR_RDP       ((uint32_t)0x007E0000)  /* RxDMA PBL */
+  #define ETH_DMABMR_RDP_1Beat    ((uint32_t)0x00020000)  /* maximum number of beats to be transferred in one RxDMA transaction is 1 */
+  #define ETH_DMABMR_RDP_2Beat    ((uint32_t)0x00040000)  /* maximum number of beats to be transferred in one RxDMA transaction is 2 */
+  #define ETH_DMABMR_RDP_4Beat    ((uint32_t)0x00080000)  /* maximum number of beats to be transferred in one RxDMA transaction is 4 */
+  #define ETH_DMABMR_RDP_8Beat    ((uint32_t)0x00100000)  /* maximum number of beats to be transferred in one RxDMA transaction is 8 */
+  #define ETH_DMABMR_RDP_16Beat   ((uint32_t)0x00200000)  /* maximum number of beats to be transferred in one RxDMA transaction is 16 */
+  #define ETH_DMABMR_RDP_32Beat   ((uint32_t)0x00400000)  /* maximum number of beats to be transferred in one RxDMA transaction is 32 */                
+  #define ETH_DMABMR_RDP_4xPBL_4Beat   ((uint32_t)0x01020000)  /* maximum number of beats to be transferred in one RxDMA transaction is 4 */
+  #define ETH_DMABMR_RDP_4xPBL_8Beat   ((uint32_t)0x01040000)  /* maximum number of beats to be transferred in one RxDMA transaction is 8 */
+  #define ETH_DMABMR_RDP_4xPBL_16Beat  ((uint32_t)0x01080000)  /* maximum number of beats to be transferred in one RxDMA transaction is 16 */
+  #define ETH_DMABMR_RDP_4xPBL_32Beat  ((uint32_t)0x01100000)  /* maximum number of beats to be transferred in one RxDMA transaction is 32 */
+  #define ETH_DMABMR_RDP_4xPBL_64Beat  ((uint32_t)0x01200000)  /* maximum number of beats to be transferred in one RxDMA transaction is 64 */
+  #define ETH_DMABMR_RDP_4xPBL_128Beat ((uint32_t)0x01400000)  /* maximum number of beats to be transferred in one RxDMA transaction is 128 */  
+#define ETH_DMABMR_FB        ((uint32_t)0x00010000)  /* Fixed Burst */
+#define ETH_DMABMR_RTPR      ((uint32_t)0x0000C000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_1_1     ((uint32_t)0x00000000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_2_1     ((uint32_t)0x00004000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_3_1     ((uint32_t)0x00008000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_4_1     ((uint32_t)0x0000C000)  /* Rx Tx priority ratio */  
+#define ETH_DMABMR_PBL    ((uint32_t)0x00003F00)  /* Programmable burst length */
+  #define ETH_DMABMR_PBL_1Beat    ((uint32_t)0x00000100)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 1 */
+  #define ETH_DMABMR_PBL_2Beat    ((uint32_t)0x00000200)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 2 */
+  #define ETH_DMABMR_PBL_4Beat    ((uint32_t)0x00000400)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */
+  #define ETH_DMABMR_PBL_8Beat    ((uint32_t)0x00000800)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */
+  #define ETH_DMABMR_PBL_16Beat   ((uint32_t)0x00001000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */
+  #define ETH_DMABMR_PBL_32Beat   ((uint32_t)0x00002000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */                
+  #define ETH_DMABMR_PBL_4xPBL_4Beat   ((uint32_t)0x01000100)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */
+  #define ETH_DMABMR_PBL_4xPBL_8Beat   ((uint32_t)0x01000200)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */
+  #define ETH_DMABMR_PBL_4xPBL_16Beat  ((uint32_t)0x01000400)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */
+  #define ETH_DMABMR_PBL_4xPBL_32Beat  ((uint32_t)0x01000800)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */
+  #define ETH_DMABMR_PBL_4xPBL_64Beat  ((uint32_t)0x01001000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 64 */
+  #define ETH_DMABMR_PBL_4xPBL_128Beat ((uint32_t)0x01002000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 128 */
+#define ETH_DMABMR_DSL       ((uint32_t)0x0000007C)  /* Descriptor Skip Length */
+#define ETH_DMABMR_DA        ((uint32_t)0x00000002)  /* DMA arbitration scheme */
+#define ETH_DMABMR_SR        ((uint32_t)0x00000001)  /* Software reset */
+
+/* Bit definition for Ethernet DMA Transmit Poll Demand Register */
+#define ETH_DMATPDR_TPD      ((uint32_t)0xFFFFFFFF)  /* Transmit poll demand */
+
+/* Bit definition for Ethernet DMA Receive Poll Demand Register */
+#define ETH_DMARPDR_RPD      ((uint32_t)0xFFFFFFFF)  /* Receive poll demand  */
+
+/* Bit definition for Ethernet DMA Receive Descriptor List Address Register */
+#define ETH_DMARDLAR_SRL     ((uint32_t)0xFFFFFFFF)  /* Start of receive list */
+
+/* Bit definition for Ethernet DMA Transmit Descriptor List Address Register */
+#define ETH_DMATDLAR_STL     ((uint32_t)0xFFFFFFFF)  /* Start of transmit list */
+
+/* Bit definition for Ethernet DMA Status Register */
+#define ETH_DMASR_TSTS       ((uint32_t)0x20000000)  /* Time-stamp trigger status */
+#define ETH_DMASR_PMTS       ((uint32_t)0x10000000)  /* PMT status */
+#define ETH_DMASR_MMCS       ((uint32_t)0x08000000)  /* MMC status */
+#define ETH_DMASR_EBS        ((uint32_t)0x03800000)  /* Error bits status */
+  /* combination with EBS[2:0] for GetFlagStatus function */
+  #define ETH_DMASR_EBS_DescAccess      ((uint32_t)0x02000000)  /* Error bits 0-data buffer, 1-desc. access */
+  #define ETH_DMASR_EBS_ReadTransf      ((uint32_t)0x01000000)  /* Error bits 0-write trnsf, 1-read transfr */
+  #define ETH_DMASR_EBS_DataTransfTx    ((uint32_t)0x00800000)  /* Error bits 0-Rx DMA, 1-Tx DMA */
+#define ETH_DMASR_TPS         ((uint32_t)0x00700000)  /* Transmit process state */
+  #define ETH_DMASR_TPS_Stopped         ((uint32_t)0x00000000)  /* Stopped - Reset or Stop Tx Command issued  */
+  #define ETH_DMASR_TPS_Fetching        ((uint32_t)0x00100000)  /* Running - fetching the Tx descriptor */
+  #define ETH_DMASR_TPS_Waiting         ((uint32_t)0x00200000)  /* Running - waiting for status */
+  #define ETH_DMASR_TPS_Reading         ((uint32_t)0x00300000)  /* Running - reading the data from host memory */
+  #define ETH_DMASR_TPS_Suspended       ((uint32_t)0x00600000)  /* Suspended - Tx Descriptor unavailabe */
+  #define ETH_DMASR_TPS_Closing         ((uint32_t)0x00700000)  /* Running - closing Rx descriptor */
+#define ETH_DMASR_RPS         ((uint32_t)0x000E0000)  /* Receive process state */
+  #define ETH_DMASR_RPS_Stopped         ((uint32_t)0x00000000)  /* Stopped - Reset or Stop Rx Command issued */
+  #define ETH_DMASR_RPS_Fetching        ((uint32_t)0x00020000)  /* Running - fetching the Rx descriptor */
+  #define ETH_DMASR_RPS_Waiting         ((uint32_t)0x00060000)  /* Running - waiting for packet */
+  #define ETH_DMASR_RPS_Suspended       ((uint32_t)0x00080000)  /* Suspended - Rx Descriptor unavailable */
+  #define ETH_DMASR_RPS_Closing         ((uint32_t)0x000A0000)  /* Running - closing descriptor */
+  #define ETH_DMASR_RPS_Queuing         ((uint32_t)0x000E0000)  /* Running - queuing the recieve frame into host memory */
+#define ETH_DMASR_NIS        ((uint32_t)0x00010000)  /* Normal interrupt summary */
+#define ETH_DMASR_AIS        ((uint32_t)0x00008000)  /* Abnormal interrupt summary */
+#define ETH_DMASR_ERS        ((uint32_t)0x00004000)  /* Early receive status */
+#define ETH_DMASR_FBES       ((uint32_t)0x00002000)  /* Fatal bus error status */
+#define ETH_DMASR_ETS        ((uint32_t)0x00000400)  /* Early transmit status */
+#define ETH_DMASR_RWTS       ((uint32_t)0x00000200)  /* Receive watchdog timeout status */
+#define ETH_DMASR_RPSS       ((uint32_t)0x00000100)  /* Receive process stopped status */
+#define ETH_DMASR_RBUS       ((uint32_t)0x00000080)  /* Receive buffer unavailable status */
+#define ETH_DMASR_RS         ((uint32_t)0x00000040)  /* Receive status */
+#define ETH_DMASR_TUS        ((uint32_t)0x00000020)  /* Transmit underflow status */
+#define ETH_DMASR_ROS        ((uint32_t)0x00000010)  /* Receive overflow status */
+#define ETH_DMASR_TJTS       ((uint32_t)0x00000008)  /* Transmit jabber timeout status */
+#define ETH_DMASR_TBUS       ((uint32_t)0x00000004)  /* Transmit buffer unavailable status */
+#define ETH_DMASR_TPSS       ((uint32_t)0x00000002)  /* Transmit process stopped status */
+#define ETH_DMASR_TS         ((uint32_t)0x00000001)  /* Transmit status */
+
+/* Bit definition for Ethernet DMA Operation Mode Register */
+#define ETH_DMAOMR_DTCEFD    ((uint32_t)0x04000000)  /* Disable Dropping of TCP/IP checksum error frames */
+#define ETH_DMAOMR_RSF       ((uint32_t)0x02000000)  /* Receive store and forward */
+#define ETH_DMAOMR_DFRF      ((uint32_t)0x01000000)  /* Disable flushing of received frames */
+#define ETH_DMAOMR_TSF       ((uint32_t)0x00200000)  /* Transmit store and forward */
+#define ETH_DMAOMR_FTF       ((uint32_t)0x00100000)  /* Flush transmit FIFO */
+#define ETH_DMAOMR_TTC       ((uint32_t)0x0001C000)  /* Transmit threshold control */
+  #define ETH_DMAOMR_TTC_64Bytes       ((uint32_t)0x00000000)  /* threshold level of the MTL Transmit FIFO is 64 Bytes */
+  #define ETH_DMAOMR_TTC_128Bytes      ((uint32_t)0x00004000)  /* threshold level of the MTL Transmit FIFO is 128 Bytes */
+  #define ETH_DMAOMR_TTC_192Bytes      ((uint32_t)0x00008000)  /* threshold level of the MTL Transmit FIFO is 192 Bytes */
+  #define ETH_DMAOMR_TTC_256Bytes      ((uint32_t)0x0000C000)  /* threshold level of the MTL Transmit FIFO is 256 Bytes */
+  #define ETH_DMAOMR_TTC_40Bytes       ((uint32_t)0x00010000)  /* threshold level of the MTL Transmit FIFO is 40 Bytes */
+  #define ETH_DMAOMR_TTC_32Bytes       ((uint32_t)0x00014000)  /* threshold level of the MTL Transmit FIFO is 32 Bytes */
+  #define ETH_DMAOMR_TTC_24Bytes       ((uint32_t)0x00018000)  /* threshold level of the MTL Transmit FIFO is 24 Bytes */
+  #define ETH_DMAOMR_TTC_16Bytes       ((uint32_t)0x0001C000)  /* threshold level of the MTL Transmit FIFO is 16 Bytes */
+#define ETH_DMAOMR_ST        ((uint32_t)0x00002000)  /* Start/stop transmission command */
+#define ETH_DMAOMR_FEF       ((uint32_t)0x00000080)  /* Forward error frames */
+#define ETH_DMAOMR_FUGF      ((uint32_t)0x00000040)  /* Forward undersized good frames */
+#define ETH_DMAOMR_RTC       ((uint32_t)0x00000018)  /* receive threshold control */
+  #define ETH_DMAOMR_RTC_64Bytes       ((uint32_t)0x00000000)  /* threshold level of the MTL Receive FIFO is 64 Bytes */
+  #define ETH_DMAOMR_RTC_32Bytes       ((uint32_t)0x00000008)  /* threshold level of the MTL Receive FIFO is 32 Bytes */
+  #define ETH_DMAOMR_RTC_96Bytes       ((uint32_t)0x00000010)  /* threshold level of the MTL Receive FIFO is 96 Bytes */
+  #define ETH_DMAOMR_RTC_128Bytes      ((uint32_t)0x00000018)  /* threshold level of the MTL Receive FIFO is 128 Bytes */
+#define ETH_DMAOMR_OSF       ((uint32_t)0x00000004)  /* operate on second frame */
+#define ETH_DMAOMR_SR        ((uint32_t)0x00000002)  /* Start/stop receive */
+
+/* Bit definition for Ethernet DMA Interrupt Enable Register */
+#define ETH_DMAIER_NISE      ((uint32_t)0x00010000)  /* Normal interrupt summary enable */
+#define ETH_DMAIER_AISE      ((uint32_t)0x00008000)  /* Abnormal interrupt summary enable */
+#define ETH_DMAIER_ERIE      ((uint32_t)0x00004000)  /* Early receive interrupt enable */
+#define ETH_DMAIER_FBEIE     ((uint32_t)0x00002000)  /* Fatal bus error interrupt enable */
+#define ETH_DMAIER_ETIE      ((uint32_t)0x00000400)  /* Early transmit interrupt enable */
+#define ETH_DMAIER_RWTIE     ((uint32_t)0x00000200)  /* Receive watchdog timeout interrupt enable */
+#define ETH_DMAIER_RPSIE     ((uint32_t)0x00000100)  /* Receive process stopped interrupt enable */
+#define ETH_DMAIER_RBUIE     ((uint32_t)0x00000080)  /* Receive buffer unavailable interrupt enable */
+#define ETH_DMAIER_RIE       ((uint32_t)0x00000040)  /* Receive interrupt enable */
+#define ETH_DMAIER_TUIE      ((uint32_t)0x00000020)  /* Transmit Underflow interrupt enable */
+#define ETH_DMAIER_ROIE      ((uint32_t)0x00000010)  /* Receive Overflow interrupt enable */
+#define ETH_DMAIER_TJTIE     ((uint32_t)0x00000008)  /* Transmit jabber timeout interrupt enable */
+#define ETH_DMAIER_TBUIE     ((uint32_t)0x00000004)  /* Transmit buffer unavailable interrupt enable */
+#define ETH_DMAIER_TPSIE     ((uint32_t)0x00000002)  /* Transmit process stopped interrupt enable */
+#define ETH_DMAIER_TIE       ((uint32_t)0x00000001)  /* Transmit interrupt enable */
+
+/* Bit definition for Ethernet DMA Missed Frame and Buffer Overflow Counter Register */
+#define ETH_DMAMFBOCR_OFOC   ((uint32_t)0x10000000)  /* Overflow bit for FIFO overflow counter */
+#define ETH_DMAMFBOCR_MFA    ((uint32_t)0x0FFE0000)  /* Number of frames missed by the application */
+#define ETH_DMAMFBOCR_OMFC   ((uint32_t)0x00010000)  /* Overflow bit for missed frame counter */
+#define ETH_DMAMFBOCR_MFC    ((uint32_t)0x0000FFFF)  /* Number of frames missed by the controller */
+
+/* Bit definition for Ethernet DMA Current Host Transmit Descriptor Register */
+#define ETH_DMACHTDR_HTDAP   ((uint32_t)0xFFFFFFFF)  /* Host transmit descriptor address pointer */
+
+/* Bit definition for Ethernet DMA Current Host Receive Descriptor Register */
+#define ETH_DMACHRDR_HRDAP   ((uint32_t)0xFFFFFFFF)  /* Host receive descriptor address pointer */
+
+/* Bit definition for Ethernet DMA Current Host Transmit Buffer Address Register */
+#define ETH_DMACHTBAR_HTBAP  ((uint32_t)0xFFFFFFFF)  /* Host transmit buffer address pointer */
+
+/* Bit definition for Ethernet DMA Current Host Receive Buffer Address Register */
+#define ETH_DMACHRBAR_HRBAP  ((uint32_t)0xFFFFFFFF)  /* Host receive buffer address pointer */
+#endif /* STM32F10X_CL */
+
+/**
+  * @}
+  */
+
+ /**
+  * @}
+  */ 
+
+#ifdef USE_STDPERIPH_DRIVER
+  #include "stm32f10x_conf.h"
+#endif
+
+/** @addtogroup Exported_macro
+  * @{
+  */
+
+#define SET_BIT(REG, BIT)     ((REG) |= (BIT))
+
+#define CLEAR_BIT(REG, BIT)   ((REG) &= ~(BIT))
+
+#define READ_BIT(REG, BIT)    ((REG) & (BIT))
+
+#define CLEAR_REG(REG)        ((REG) = (0x0))
+
+#define WRITE_REG(REG, VAL)   ((REG) = (VAL))
+
+#define READ_REG(REG)         ((REG))
+
+#define MODIFY_REG(REG, CLEARMASK, SETMASK)  WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
+
+/**
+  * @}
+  */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_H */
+
+/**
+  * @}
+  */
+
+  /**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/system_stm32f10x.c b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/system_stm32f10x.c
new file mode 100644
index 0000000000000000000000000000000000000000..ec6b682c8bd826036cada9fccb273f486e5d313c
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/system_stm32f10x.c
@@ -0,0 +1,941 @@
+/**
+  ******************************************************************************
+  * @file    system_stm32f10x.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.
+  ******************************************************************************  
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */
+
+/** @addtogroup CMSIS
+  * @{
+  */
+
+/** @addtogroup stm32f10x_system
+  * @{
+  */  
+  
+/** @addtogroup STM32F10x_System_Private_Includes
+  * @{
+  */
+
+#include "stm32f10x.h"
+#include "led.h"
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Private_Defines
+  * @{
+  */
+
+/*!< Uncomment the line corresponding to the desired System clock (SYSCLK)
+   frequency (after reset the HSI is used as SYSCLK source)
+   
+   IMPORTANT NOTE:
+   ============== 
+   1. After each device reset the HSI is used as System clock source.
+
+   2. Please make sure that the selected System clock doesn't exceed your device's
+      maximum frequency.
+      
+   3. If none of the define below is enabled, the HSI is used as System clock
+    source.
+
+   4. The System clock configuration functions provided within this file assume that:
+        - For Low, Medium and High density devices an external 8MHz crystal is
+          used to drive the System clock.
+        - For Connectivity line devices an external 25MHz crystal is used to drive
+          the System clock.
+     If you are using different crystal you have to adapt those functions accordingly.
+    */
+    
+/* #define SYSCLK_FREQ_HSE    HSE_Value */
+/* #define SYSCLK_FREQ_24MHz  24000000 */
+/* #define SYSCLK_FREQ_36MHz  36000000 */
+/* #define SYSCLK_FREQ_48MHz  48000000 */
+/* #define SYSCLK_FREQ_56MHz  56000000 */
+#define SYSCLK_FREQ_72MHz  72000000
+
+/*!< Uncomment the following line if you need to use external SRAM mounted
+     on STM3210E-EVAL board (STM32 High density devices) as data memory  */ 
+#ifdef STM32F10X_HD
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F10X_HD */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Private_Variables
+  * @{
+  */
+
+/*******************************************************************************
+*  Clock Definitions
+*******************************************************************************/
+#ifdef SYSCLK_FREQ_HSE
+  const uint32_t SystemFrequency         = SYSCLK_FREQ_HSE;        /*!< System Clock Frequency (Core Clock) */
+  const uint32_t SystemFrequency_SysClk  = SYSCLK_FREQ_HSE;        /*!< System clock                        */
+  const uint32_t SystemFrequency_AHBClk  = SYSCLK_FREQ_HSE;        /*!< AHB System bus speed                */
+  const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_HSE;        /*!< APB Peripheral bus 1 (low)  speed   */
+  const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_HSE;        /*!< APB Peripheral bus 2 (high) speed   */
+#elif defined SYSCLK_FREQ_24MHz
+  const uint32_t SystemFrequency         = SYSCLK_FREQ_24MHz;      /*!< System Clock Frequency (Core Clock) */
+  const uint32_t SystemFrequency_SysClk  = SYSCLK_FREQ_24MHz;      /*!< System clock                        */
+  const uint32_t SystemFrequency_AHBClk  = SYSCLK_FREQ_24MHz;      /*!< AHB System bus speed                */
+  const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_24MHz;      /*!< APB Peripheral bus 1 (low)  speed   */
+  const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_24MHz;      /*!< APB Peripheral bus 2 (high) speed   */
+#elif defined SYSCLK_FREQ_36MHz
+  const uint32_t SystemFrequency         = SYSCLK_FREQ_36MHz;      /*!< System Clock Frequency (Core Clock) */
+  const uint32_t SystemFrequency_SysClk  = SYSCLK_FREQ_36MHz;      /*!< System clock                        */
+  const uint32_t SystemFrequency_AHBClk  = SYSCLK_FREQ_36MHz;      /*!< AHB System bus speed                */
+  const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_36MHz;      /*!< APB Peripheral bus 1 (low)  speed   */
+  const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_36MHz;      /*!< APB Peripheral bus 2 (high) speed   */
+#elif defined SYSCLK_FREQ_48MHz
+  const uint32_t SystemFrequency         = SYSCLK_FREQ_48MHz;      /*!< System Clock Frequency (Core Clock) */
+  const uint32_t SystemFrequency_SysClk  = SYSCLK_FREQ_48MHz;      /*!< System clock                        */
+  const uint32_t SystemFrequency_AHBClk  = SYSCLK_FREQ_48MHz;      /*!< AHB System bus speed                */
+  const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_48MHz/2);  /*!< APB Peripheral bus 1 (low)  speed   */
+  const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_48MHz;      /*!< APB Peripheral bus 2 (high) speed   */
+#elif defined SYSCLK_FREQ_56MHz
+  const uint32_t SystemFrequency         = SYSCLK_FREQ_56MHz;      /*!< System Clock Frequency (Core Clock) */
+  const uint32_t SystemFrequency_SysClk  = SYSCLK_FREQ_56MHz;      /*!< System clock                        */
+  const uint32_t SystemFrequency_AHBClk  = SYSCLK_FREQ_56MHz;      /*!< AHB System bus speed                */
+  const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_56MHz/2);  /*!< APB Peripheral bus 1 (low)  speed   */
+  const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_56MHz;      /*!< APB Peripheral bus 2 (high) speed   */  
+#elif defined SYSCLK_FREQ_72MHz
+  const uint32_t SystemFrequency         = SYSCLK_FREQ_72MHz;      /*!< System Clock Frequency (Core Clock) */
+  const uint32_t SystemFrequency_SysClk  = SYSCLK_FREQ_72MHz;      /*!< System clock                        */
+  const uint32_t SystemFrequency_AHBClk  = SYSCLK_FREQ_72MHz;      /*!< AHB System bus speed                */
+  const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_72MHz/2);  /*!< APB Peripheral bus 1 (low)  speed   */
+  const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_72MHz;      /*!< APB Peripheral bus 2 (high) speed   */
+#else /*!< HSI Selected as System Clock source */
+  const uint32_t SystemFrequency         = HSI_Value;              /*!< System Clock Frequency (Core Clock) */
+  const uint32_t SystemFrequency_SysClk  = HSI_Value;              /*!< System clock                        */
+  const uint32_t SystemFrequency_AHBClk  = HSI_Value;              /*!< AHB System bus speed                */
+  const uint32_t SystemFrequency_APB1Clk = HSI_Value;              /*!< APB Peripheral bus 1 (low)  speed   */
+  const uint32_t SystemFrequency_APB2Clk = HSI_Value;              /*!< APB Peripheral bus 2 (high) speed   */
+#endif
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Private_FunctionPrototypes
+  * @{
+  */
+
+static void SetSysClock(void);
+
+#ifdef SYSCLK_FREQ_HSE
+  static void SetSysClockToHSE(void);
+#elif defined SYSCLK_FREQ_24MHz
+  static void SetSysClockTo24(void);
+#elif defined SYSCLK_FREQ_36MHz
+  static void SetSysClockTo36(void);
+#elif defined SYSCLK_FREQ_48MHz
+  static void SetSysClockTo48(void);
+#elif defined SYSCLK_FREQ_56MHz
+  static void SetSysClockTo56(void);  
+#elif defined SYSCLK_FREQ_72MHz
+  static void SetSysClockTo72(void);
+#endif
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Setup the microcontroller system
+  *         Initialize the Embedded Flash Interface, the PLL and update the SystemFrequency variable.
+  * @note   This function should be used only after reset.
+  * @param  None
+  * @retval None
+  */
+void SystemInit (void)
+{
+  /* Reset the RCC clock configuration to the default reset state(for debug purpose) */
+  /* Set HSION bit */
+  RCC->CR |= (uint32_t)0x00000001;
+
+  /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
+#ifndef STM32F10X_CL
+  RCC->CFGR &= (uint32_t)0xF8FF0000;
+#else
+  RCC->CFGR &= (uint32_t)0xF0FF0000;
+#endif /* STM32F10X_CL */   
+  
+  /* Reset HSEON, CSSON and PLLON bits */
+  RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+  /* Reset HSEBYP bit */
+  RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+  /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
+  RCC->CFGR &= (uint32_t)0xFF80FFFF;
+
+#ifndef STM32F10X_CL
+  /* Disable all interrupts and clear pending bits  */
+  RCC->CIR = 0x009F0000;
+#else
+  /* Reset PLL2ON and PLL3ON bits */
+  RCC->CR &= (uint32_t)0xEBFFFFFF;
+
+  /* Disable all interrupts and clear pending bits  */
+  RCC->CIR = 0x00FF0000;
+
+  /* Reset CFGR2 register */
+  RCC->CFGR2 = 0x00000000;
+#endif /* STM32F10X_CL */
+    
+  /* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
+  /* Configure the Flash Latency cycles and enable prefetch buffer */
+  SetSysClock();
+
+}
+
+/**
+  * @brief  Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers.
+  * @param  None
+  * @retval None
+  */
+static void SetSysClock(void)
+{
+#ifdef SYSCLK_FREQ_HSE
+  SetSysClockToHSE();
+#elif defined SYSCLK_FREQ_24MHz
+  SetSysClockTo24();
+#elif defined SYSCLK_FREQ_36MHz
+  SetSysClockTo36();
+#elif defined SYSCLK_FREQ_48MHz
+  SetSysClockTo48();
+#elif defined SYSCLK_FREQ_56MHz
+  SetSysClockTo56();  
+#elif defined SYSCLK_FREQ_72MHz
+  SetSysClockTo72();
+#endif
+ 
+ /* If none of the define above is enabled, the HSI is used as System clock
+    source (default after reset) */ 
+}
+
+/**
+  * @brief  Setup the external memory controller. Called in startup_stm32f10x.s 
+  *          before jump to __main
+  * @param  None
+  * @retval None
+  */ 
+#ifdef DATA_IN_ExtSRAM
+/**
+  * @brief  Setup the external memory controller. 
+  *         Called in startup_stm32f10x_xx.s/.c before jump to main.
+  * 	      This function configures the external SRAM mounted on STM3210E-EVAL
+  *         board (STM32 High density devices). This SRAM will be used as program
+  *         data memory (including heap and stack).
+  * @param  None
+  * @retval None
+  */ 
+void SystemInit_ExtMemCtl(void) 
+{
+/*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is 
+  required, then adjust the Register Addresses */
+
+  /* Enable FSMC clock */
+  RCC->AHBENR = 0x00000114;
+  
+  /* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */  
+  RCC->APB2ENR = 0x000001E0;
+  
+/* ---------------  SRAM Data lines, NOE and NWE configuration ---------------*/
+/*----------------  SRAM Address lines configuration -------------------------*/
+/*----------------  NOE and NWE configuration --------------------------------*/  
+/*----------------  NE3 configuration ----------------------------------------*/
+/*----------------  NBL0, NBL1 configuration ---------------------------------*/
+  
+  GPIOD->CRL = 0x44BB44BB;  
+  GPIOD->CRH = 0xBBBBBBBB;
+
+  GPIOE->CRL = 0xB44444BB;  
+  GPIOE->CRH = 0xBBBBBBBB;
+
+  GPIOF->CRL = 0x44BBBBBB;  
+  GPIOF->CRH = 0xBBBB4444;
+
+  GPIOG->CRL = 0x44BBBBBB;  
+  GPIOG->CRH = 0x44444B44;
+   
+/*----------------  FSMC Configuration ---------------------------------------*/  
+/*----------------  Enable FSMC Bank1_SRAM Bank ------------------------------*/
+  
+  FSMC_Bank1->BTCR[4] = 0x00001011;
+  FSMC_Bank1->BTCR[5] = 0x00000200;
+}
+#endif /* DATA_IN_ExtSRAM */
+
+#ifdef SYSCLK_FREQ_HSE
+/**
+  * @brief  Selects HSE as System clock source and configure HCLK, PCLK2
+  *          and PCLK1 prescalers.
+  * @note   This function should be used only after reset.
+  * @param  None
+  * @retval None
+  */
+static void SetSysClockToHSE(void)
+{
+  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+  
+  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/    
+  /* Enable HSE */    
+  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+ 
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC->CR & RCC_CR_HSERDY;
+    StartUpCounter++;  
+  } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut));
+
+  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+  {
+    HSEStatus = (uint32_t)0x01;
+  }
+  else
+  {
+    HSEStatus = (uint32_t)0x00;
+  }  
+
+  if (HSEStatus == (uint32_t)0x01)
+  {
+    /* Enable Prefetch Buffer */
+    FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+    /* Flash 0 wait state */
+    FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+
+#ifndef STM32F10X_CL
+    FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0;
+#else
+    if (HSE_Value <= 24000000)
+	{
+      FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0;
+	}
+	else
+	{
+      FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;
+	}
+#endif /* STM32F10X_CL */
+ 
+    /* HCLK = SYSCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+      
+    /* PCLK2 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+    
+    /* PCLK1 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
+    
+    /* Select HSE as system clock source */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSE;    
+
+    /* Wait till HSE is used as system clock source */
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x04)
+    {
+    }
+  }
+  else
+  { /* If HSE fails to start-up, the application will have wrong clock 
+         configuration. User can add here some code to deal with this error */    
+
+    /* Go to infinite loop */
+    while (1)
+    {
+    }
+  }  
+}
+#elif defined SYSCLK_FREQ_24MHz
+/**
+  * @brief  Sets System clock frequency to 24MHz and configure HCLK, PCLK2 
+  *          and PCLK1 prescalers.
+  * @note   This function should be used only after reset.
+  * @param  None
+  * @retval None
+  */
+static void SetSysClockTo24(void)
+{
+  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+  
+  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/    
+  /* Enable HSE */    
+  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+ 
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC->CR & RCC_CR_HSERDY;
+    StartUpCounter++;  
+  } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut));
+
+  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+  {
+    HSEStatus = (uint32_t)0x01;
+  }
+  else
+  {
+    HSEStatus = (uint32_t)0x00;
+  }  
+
+  if (HSEStatus == (uint32_t)0x01)
+  {
+    /* Enable Prefetch Buffer */
+    FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+    /* Flash 0 wait state */
+    FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+    FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0;    
+ 
+    /* HCLK = SYSCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+      
+    /* PCLK2 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+    
+    /* PCLK1 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
+    
+#ifdef STM32F10X_CL
+    /* Configure PLLs ------------------------------------------------------*/
+    /* PLL configuration: PLLCLK = PREDIV1 * 6 = 24 MHz */ 
+    RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | 
+                            RCC_CFGR_PLLMULL6); 
+
+    /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
+    /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 10 = 4 MHz */       
+    RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
+                              RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
+    RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
+                             RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV10);
+  
+    /* Enable PLL2 */
+    RCC->CR |= RCC_CR_PLL2ON;
+    /* Wait till PLL2 is ready */
+    while((RCC->CR & RCC_CR_PLL2RDY) == 0)
+    {
+    }   
+#else    
+    /*  PLL configuration:  = (HSE / 2) * 6 = 24 MHz */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL6);
+#endif /* STM32F10X_CL */
+
+    /* Enable PLL */
+    RCC->CR |= RCC_CR_PLLON;
+
+    /* Wait till PLL is ready */
+    while((RCC->CR & RCC_CR_PLLRDY) == 0)
+    {
+    }
+
+    /* Select PLL as system clock source */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;    
+
+    /* Wait till PLL is used as system clock source */
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+    {
+    }
+  }
+  else
+  { /* If HSE fails to start-up, the application will have wrong clock 
+         configuration. User can add here some code to deal with this error */    
+
+    /* Go to infinite loop */
+    while (1)
+    {
+    }
+  } 
+}
+#elif defined SYSCLK_FREQ_36MHz
+/**
+  * @brief  Sets System clock frequency to 36MHz and configure HCLK, PCLK2 
+  *          and PCLK1 prescalers. 
+  * @note   This function should be used only after reset.
+  * @param  None
+  * @retval None
+  */
+static void SetSysClockTo36(void)
+{
+  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+  
+  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/    
+  /* Enable HSE */    
+  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+ 
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC->CR & RCC_CR_HSERDY;
+    StartUpCounter++;  
+  } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut));
+
+  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+  {
+    HSEStatus = (uint32_t)0x01;
+  }
+  else
+  {
+    HSEStatus = (uint32_t)0x00;
+  }  
+
+  if (HSEStatus == (uint32_t)0x01)
+  {
+    /* Enable Prefetch Buffer */
+    FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+    /* Flash 1 wait state */
+    FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+    FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;    
+ 
+    /* HCLK = SYSCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+      
+    /* PCLK2 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+    
+    /* PCLK1 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
+    
+#ifdef STM32F10X_CL
+    /* Configure PLLs ------------------------------------------------------*/
+    
+    /* PLL configuration: PLLCLK = PREDIV1 * 9 = 36 MHz */ 
+    RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | 
+                            RCC_CFGR_PLLMULL9); 
+
+	/*!< PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
+    /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 10 = 4 MHz */
+        
+    RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
+                              RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
+    RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
+                             RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV10);
+  
+    /* Enable PLL2 */
+    RCC->CR |= RCC_CR_PLL2ON;
+    /* Wait till PLL2 is ready */
+    while((RCC->CR & RCC_CR_PLL2RDY) == 0)
+    {
+    }
+    
+#else    
+    /*  PLL configuration: PLLCLK = (HSE / 2) * 9 = 36 MHz */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL9);
+#endif /* STM32F10X_CL */
+
+    /* Enable PLL */
+    RCC->CR |= RCC_CR_PLLON;
+
+    /* Wait till PLL is ready */
+    while((RCC->CR & RCC_CR_PLLRDY) == 0)
+    {
+    }
+
+    /* Select PLL as system clock source */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;    
+
+    /* Wait till PLL is used as system clock source */
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+    {
+    }
+  }
+  else
+  { /* If HSE fails to start-up, the application will have wrong clock 
+         configuration. User can add here some code to deal with this error */    
+
+    /* Go to infinite loop */
+    while (1)
+    {
+    }
+  } 
+}
+#elif defined SYSCLK_FREQ_48MHz
+/**
+  * @brief  Sets System clock frequency to 48MHz and configure HCLK, PCLK2 
+  *          and PCLK1 prescalers. 
+  * @note   This function should be used only after reset.
+  * @param  None
+  * @retval None
+  */
+static void SetSysClockTo48(void)
+{
+  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+  
+  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/    
+  /* Enable HSE */    
+  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+ 
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC->CR & RCC_CR_HSERDY;
+    StartUpCounter++;  
+  } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut));
+
+  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+  {
+    HSEStatus = (uint32_t)0x01;
+  }
+  else
+  {
+    HSEStatus = (uint32_t)0x00;
+  }  
+
+  if (HSEStatus == (uint32_t)0x01)
+  {
+    /* Enable Prefetch Buffer */
+    FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+    /* Flash 1 wait state */
+    FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+    FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;    
+ 
+    /* HCLK = SYSCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+      
+    /* PCLK2 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+    
+    /* PCLK1 = HCLK/2 */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
+    
+#ifdef STM32F10X_CL
+    /* Configure PLLs ------------------------------------------------------*/
+    /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
+    /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */
+        
+    RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
+                              RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
+    RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
+                             RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5);
+  
+    /* Enable PLL2 */
+    RCC->CR |= RCC_CR_PLL2ON;
+    /* Wait till PLL2 is ready */
+    while((RCC->CR & RCC_CR_PLL2RDY) == 0)
+    {
+    }
+    
+   
+    /* PLL configuration: PLLCLK = PREDIV1 * 6 = 48 MHz */ 
+    RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | 
+                            RCC_CFGR_PLLMULL6); 
+#else    
+    /*  PLL configuration: PLLCLK = HSE * 6 = 48 MHz */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL6);
+#endif /* STM32F10X_CL */
+
+    /* Enable PLL */
+    RCC->CR |= RCC_CR_PLLON;
+
+    /* Wait till PLL is ready */
+    while((RCC->CR & RCC_CR_PLLRDY) == 0)
+    {
+    }
+
+    /* Select PLL as system clock source */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;    
+
+    /* Wait till PLL is used as system clock source */
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+    {
+    }
+  }
+  else
+  { /* If HSE fails to start-up, the application will have wrong clock 
+         configuration. User can add here some code to deal with this error */    
+
+    /* Go to infinite loop */
+    while (1)
+    {
+    }
+  } 
+}
+
+#elif defined SYSCLK_FREQ_56MHz
+/**
+  * @brief  Sets System clock frequency to 56MHz and configure HCLK, PCLK2 
+  *          and PCLK1 prescalers. 
+  * @note   This function should be used only after reset.
+  * @param  None
+  * @retval None
+  */
+static void SetSysClockTo56(void)
+{
+  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+  
+  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/   
+  /* Enable HSE */    
+  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+ 
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC->CR & RCC_CR_HSERDY;
+    StartUpCounter++;  
+  } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut));
+
+  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+  {
+    HSEStatus = (uint32_t)0x01;
+  }
+  else
+  {
+    HSEStatus = (uint32_t)0x00;
+  }  
+
+  if (HSEStatus == (uint32_t)0x01)
+  {
+    /* Enable Prefetch Buffer */
+    FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+    /* Flash 2 wait state */
+    FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+    FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;    
+ 
+    /* HCLK = SYSCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+      
+    /* PCLK2 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+    
+    /* PCLK1 = HCLK/2 */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
+
+#ifdef STM32F10X_CL
+    /* Configure PLLs ------------------------------------------------------*/
+    /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
+    /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */
+        
+    RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
+                              RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
+    RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
+                             RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5);
+  
+    /* Enable PLL2 */
+    RCC->CR |= RCC_CR_PLL2ON;
+    /* Wait till PLL2 is ready */
+    while((RCC->CR & RCC_CR_PLL2RDY) == 0)
+    {
+    }
+    
+   
+    /* PLL configuration: PLLCLK = PREDIV1 * 7 = 56 MHz */ 
+    RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | 
+                            RCC_CFGR_PLLMULL7); 
+#else     
+    /* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL7);
+
+#endif /* STM32F10X_CL */
+
+    /* Enable PLL */
+    RCC->CR |= RCC_CR_PLLON;
+
+    /* Wait till PLL is ready */
+    while((RCC->CR & RCC_CR_PLLRDY) == 0)
+    {
+    }
+
+    /* Select PLL as system clock source */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;    
+
+    /* Wait till PLL is used as system clock source */
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+    {
+    }
+  }
+  else
+  { /* If HSE fails to start-up, the application will have wrong clock 
+         configuration. User can add here some code to deal with this error */    
+
+    /* Go to infinite loop */
+    while (1)
+    {
+    }
+  } 
+}
+
+#elif defined SYSCLK_FREQ_72MHz
+/**
+  * @brief  Sets System clock frequency to 72MHz and configure HCLK, PCLK2 
+  *          and PCLK1 prescalers. 
+  * @note   This function should be used only after reset.
+  * @param  None
+  * @retval None
+  */
+static void SetSysClockTo72(void)
+{
+  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+  
+  /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/    
+  /* Enable HSE */    
+  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+ 
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC->CR & RCC_CR_HSERDY;
+    StartUpCounter++;  
+  } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut));
+
+  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+  {
+    HSEStatus = (uint32_t)0x01;
+  }
+  else
+  {
+    HSEStatus = (uint32_t)0x00;
+  }  
+
+  if (HSEStatus == (uint32_t)0x01)
+  {
+    /* Enable Prefetch Buffer */
+    FLASH->ACR |= FLASH_ACR_PRFTBE;
+
+    /* Flash 2 wait state */
+    FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
+    FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;    
+
+ 
+    /* HCLK = SYSCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
+      
+    /* PCLK2 = HCLK */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
+    
+    /* PCLK1 = HCLK/2 */
+    RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
+
+#ifdef STM32F10X_CL
+    /* Configure PLLs ------------------------------------------------------*/
+    /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
+    /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */
+        
+    RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
+                              RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
+    RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
+                             RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5);
+  
+    /* Enable PLL2 */
+    RCC->CR |= RCC_CR_PLL2ON;
+    /* Wait till PLL2 is ready */
+    while((RCC->CR & RCC_CR_PLL2RDY) == 0)
+    {
+    }
+    
+   
+    /* PLL configuration: PLLCLK = PREDIV1 * 9 = 72 MHz */ 
+    RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | 
+                            RCC_CFGR_PLLMULL9); 
+#else
+    /*  PLL configuration: PLLCLK = HSEDIV2 * 9 = 72 MHz */
+    /*  ADCCLK = PCLK2/6 = 72 / 6 = 12 MHz*/
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
+    RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL9 | RCC_CFGR_ADCPRE_DIV6);
+#endif /* STM32F10X_CL */
+
+    /* Enable PLL */
+    RCC->CR |= RCC_CR_PLLON;
+
+    /* Wait till PLL is ready */
+    while((RCC->CR & RCC_CR_PLLRDY) == 0)
+    {
+    }
+    
+    /* Select PLL as system clock source */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+    RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;    
+
+    /* Wait till PLL is used as system clock source */
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
+    {
+    }
+  }
+  else
+  { /* If HSE fails to start-up, the application will have wrong clock 
+         configuration. User can add here some code to deal with this error */    
+    GPIO_InitTypeDef GPIO_InitStructure;
+
+    //Cannot start the main oscillator: red/green LED of death...
+    GPIO_InitStructure.GPIO_Pin = LED_GPIO_RED | LED_GPIO_GREEN;
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+
+    GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+    GPIO_ResetBits(GPIOB, LED_RED);
+    GPIO_ResetBits(GPIOB, LED_GREEN);
+    /* Go to infinite loop */
+    while (1)
+    {
+    }
+  }
+}
+#endif
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+  
+/**
+  * @}
+  */    
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/system_stm32f10x.h b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/system_stm32f10x.h
new file mode 100644
index 0000000000000000000000000000000000000000..67b98d6944255a2fca2dffa99126913109c2f3e5
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/CM3/system_stm32f10x.h
@@ -0,0 +1,100 @@
+/**
+  ******************************************************************************
+  * @file    system_stm32f10x.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   CMSIS Cortex-M3 Device Peripheral Access Layer System Header File.
+  ******************************************************************************  
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */
+
+/** @addtogroup CMSIS
+  * @{
+  */
+
+/** @addtogroup stm32f10x_system
+  * @{
+  */  
+  
+/**
+  * @brief Define to prevent recursive inclusion
+  */
+#ifndef __SYSTEM_STM32F10X_H
+#define __SYSTEM_STM32F10X_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif 
+
+/** @addtogroup STM32F10x_System_Includes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+
+/** @addtogroup STM32F10x_System_Exported_types
+  * @{
+  */
+
+extern const uint32_t SystemFrequency;          /*!< System Clock Frequency (Core Clock) */
+extern const uint32_t SystemFrequency_SysClk;   /*!< System clock                        */
+extern const uint32_t SystemFrequency_AHBClk;   /*!< AHB System bus speed                */
+extern const uint32_t SystemFrequency_APB1Clk;  /*!< APB Peripheral Bus 1 (low)  speed   */
+extern const uint32_t SystemFrequency_APB2Clk;  /*!< APB Peripheral Bus 2 (high) speed   */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Exported_Constants
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F10x_System_Exported_Functions
+  * @{
+  */
+  
+extern void SystemInit(void);
+/**
+  * @}
+  */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F10X_H */
+
+/**
+  * @}
+  */
+  
+/**
+  * @}
+  */  
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/Core/Documentation/CMSIS_Core.htm b/crazyflie-firmware-src/src/lib/CMSIS/Core/Documentation/CMSIS_Core.htm
new file mode 100644
index 0000000000000000000000000000000000000000..60b79b8083d19c0385a50cf808fa62cec3902d18
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/Core/Documentation/CMSIS_Core.htm
@@ -0,0 +1,1231 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html xmlns:p="urn:schemas-microsoft-com:office:powerpoint" xmlns:v="urn:schemas-microsoft-com:vml" xmlns:o="urn:schemas-microsoft-com:office:office"><head>
+  
+  <title>CMSIS: Cortex Microcontroller Software Interface Standard</title><meta http-equiv="Content-Type" content="text/html; charset=windows-1252">
+  <meta name="ProgId" content="FrontPage.Editor.Document">
+  <style>
+<!--
+/*-----------------------------------------------------------Keil Software CHM Style Sheet
+-----------------------------------------------------------*/
+body { color: #000000; background-color: #FFFFFF; font-size: 75%; font-family: Verdana, Arial, 'Sans Serif' }
+a:link { color: #0000FF; text-decoration: underline }
+a:visited { color: #0000FF; text-decoration: underline }
+a:active { color: #FF0000; text-decoration: underline }
+a:hover { color: #FF0000; text-decoration: underline }
+h1 { font-family: Verdana; font-size: 18pt; color: #000080; font-weight: bold; text-align: Center; margin-right: 3 }
+h2 { font-family: Verdana; font-size: 14pt; color: #000080; font-weight: bold; background-color: #CCCCCC; margin-top: 24; margin-bottom: 3; padding: 6 }
+h3 { font-family: Verdana; font-size: 10pt; font-weight: bold; background-color: #CCCCCC; margin-top: 24; margin-bottom: 3; padding: 6 }
+pre { font-family: Courier New; font-size: 10pt; background-color: #CCFFCC; margin-left: 24; margin-right: 24 }
+ul { list-style-type: square; margin-top: 6pt; margin-bottom: 0 }
+ol { margin-top: 6pt; margin-bottom: 0 }
+li { clear: both; margin-bottom: 6pt }
+table { font-size: 100%; border-width: 0; padding: 0 }
+th { color: #FFFFFF; background-color: #000080; text-align: left; vertical-align: bottom; padding-right: 6pt }
+tr { text-align: left; vertical-align: top }
+td { text-align: left; vertical-align: top; padding-right: 6pt }
+.ToolT { font-size: 8pt; color: #808080 }
+.TinyT { font-size: 8pt; text-align: Center }
+code { color: #000000; background-color: #E0E0E0; font-family: 'Courier New', Courier; line-height: 120%; font-style: normal }
+/*-----------------------------------------------------------Notes
+-----------------------------------------------------------*/
+p.note { font-weight: bold; clear: both; margin-bottom: 3pt; padding-top: 6pt }
+/*-----------------------------------------------------------Expanding/Contracting Divisions
+-----------------------------------------------------------*/
+#expand { text-decoration: none; margin-bottom: 3pt }
+img.expand { border-style: none; border-width: medium }
+div.expand { display: none; margin-left: 9pt; margin-top: 0 }
+/*-----------------------------------------------------------Where List Tags
+-----------------------------------------------------------*/
+p.wh { font-weight: bold; clear: both; margin-top: 6pt; margin-bottom: 3pt }
+table.wh { width: 100% }
+td.whItem { white-space: nowrap; font-style: italic; padding-right: 6pt; padding-bottom: 6pt }
+td.whDesc { padding-bottom: 6pt }
+/*-----------------------------------------------------------Keil Table Tags
+-----------------------------------------------------------*/
+table.kt { width: 100%; border: 1pt solid #000000 }
+th.kt { white-space: nowrap; border-bottom: 1pt solid #000000; padding-left: 6pt; padding-right: 6pt; padding-top: 4pt; padding-bottom: 4pt }
+tr.kt { }
+td.kt { color: #000000; background-color: #E0E0E0; border-top: 1pt solid #A0A0A0; padding-left: 6pt; padding-right: 6pt; padding-top: 2pt; padding-bottom: 2pt }
+/*----------------------------------------------------------------------------------------------------------------------*/
+    .style1 {
+	background-color: #E0E0E0;
+}
+.O
+	{color:#1D315B;
+	font-size:149%;}
+    -->
+  </style></head>
+<body>
+<h1>Cortex Microcontroller Software Interface Standard</h1>
+
+<p align="center">This file describes the Cortex Microcontroller Software Interface Standard (CMSIS).</p>
+<p align="center">Version: 1.20 - 22. May 2009</p>
+
+<p class="TinyT">Information in this file, the accompany manuals, and software is<br>
+                 Copyright © ARM Ltd.<br>All rights reserved.
+</p>
+
+<hr>
+
+<p><span style="FONT-WEIGHT: bold">Revision History</span></p>
+<ul>
+	<li>Version 1.00: initial release. </li>
+	<li>Version 1.01: added __LDREX<em>x</em>, __STREX<em>x</em>, and __CLREX.</li>
+	<li>Version 1.02: added Cortex-M0. </li>
+	<li>Version 1.10: second review. </li>
+	<li>Version 1.20: third review. </li>
+</ul>
+
+<hr>
+
+<h2>Contents</h2>
+
+<ol>
+  <li class="LI2"><a href="#1">About</a></li>
+  <li class="LI2"><a href="#2">Coding Rules and Conventions</a></li>
+  <li class="LI2"><a href="#3">CMSIS Files</a></li>
+  <li class="LI2"><a href="#4">Core Peripheral Access Layer</a></li>
+  <li class="LI2"><a href="#5">CMSIS Example</a></li>
+</ol>
+
+<h2><a name="1"></a>About</h2>
+
+<p>
+  The <strong>Cortex Microcontroller Software Interface Standard (CMSIS)</strong> answers the challenges
+  that are faced when software components are deployed to physical microcontroller devices based on a
+  Cortex-M0 / Cortex-M1 or Cortex-M3 processor. The CMSIS will be also expanded to future Cortex-M 
+  processor cores (the term Cortex-Mx is used to indicate that). The CMSIS is defined in close co-operation
+  with various silicon and software vendors and provides a common approach to interface to peripherals, 
+  real-time operating systems, and middleware components.
+</p>
+
+<p>ARM provides as part of the CMSIS the following software layers that are
+available for various compiler implementations:</p>
+<ul>
+  <li><strong>Core Peripheral Access Layer</strong>: contains name definitions, 
+    address definitions and helper functions to
+    access core registers and peripherals. It defines also an device
+    independent interface for RTOS Kernels that includes debug channel
+    definitions.</li>
+  <li><strong>Middleware Access Layer:</strong> provides common methods to
+    access peripherals for the software industry. The Middleware Access Layer
+    is adapted by the Silicon Vendor for the device specific peripherals used
+    by middleware components. The middleware access layer is currently in 
+	development and not yet part of this documentation</li>
+</ul>
+
+<p>These software layers are expanded by Silicon partners with:</p>
+<ul>
+  <li><strong>Device Peripheral Access Layer</strong>: provides definitions
+    for all device peripherals</li>
+  <li><strong>Access Functions for Peripherals (optional)</strong>: provides
+    additional helper functions for peripherals</li>
+</ul>
+
+<p>CMSIS defines for a Cortex-Mx Microcontroller System:</p>
+<ul>
+  <li style="text-align: left;">A common way to access peripheral registers
+    and a common way to define exception vectors.</li>
+  <li style="text-align: left;">The register names of the <strong>Core
+    Peripherals</strong> and<strong> </strong>the names of the <strong>Core
+    Exception Vectors</strong>.</li>
+  <li>An device independent interface for RTOS Kernels including a debug
+    channel.</li>
+  <li style="text-align: left;">Interfaces for middleware components (TCP/IP
+    Stack, Flash File System).</li>
+</ul>
+
+<p>
+  By using CMSIS compliant software components, the user can easier re-use template code. 
+  CMSIS is intended to enable the combination of software components from multiple middleware vendors.
+</p>
+
+<h2><a name="2"></a>Coding Rules and Conventions</h2>
+
+<p>
+  The following section describes the coding rules and conventions used in the CMSIS 
+  implementation. It contains also information about data types and version number information.
+</p>
+
+<h3>Essentials</h3>
+<ul>
+  <li>The CMSIS C code conforms to MISRA 2004 rules. In case of MISRA violations, 
+      there are disable and enable sequences for PC-LINT inserted.</li>
+  <li>ANSI standard data types defined in the ANSI C header file
+    <strong>&lt;stdint.h&gt;</strong> are used.</li>
+  <li>#define constants that include expressions must be enclosed by
+    parenthesis.</li>
+  <li>Variables and parameters have a complete data type.</li>
+  <li>All functions in the <strong>Core Peripheral Access Layer</strong> are
+    re-entrant.</li>
+  <li>The <strong>Core Peripheral Access Layer</strong> has no blocking code
+    (which means that wait/query loops are done at other software layers such as 
+    the <strong>Middleware Access Layer</strong>).</li>
+  <li>For each exception/interrupt there is definition for:
+  <ul>
+    <li>an exception/interrupt handler with the postfix <strong>_Handler </strong>
+	(for exceptions) or <strong>_IRQHandler</strong> (for interrupts).</li>
+    <li>a default exception/interrupt handler (weak definition) that contains an endless loop.</li>
+    <li>a #define of the interrupt number with the postfix <strong>_IRQn</strong>.</li>
+  </ul></li>
+</ul>
+
+<h3>Recommendations</h3>
+
+<p>The CMSIS recommends the following conventions for identifiers.</p>
+<ul>
+  <li><strong>CAPITAL</strong> names to identify Core Registers, Peripheral Registers, and CPU Instructions.</li>
+  <li><strong>CamelCase</strong> names to identify peripherals access functions and interrupts.</li>
+  <li><strong>PERIPHERAL_</strong> prefix to identify functions that belong to specify peripherals.</li>
+  <li><strong>Doxygen</strong> comments for all functions are included as described under <strong>Function Comments</strong> below.</li>
+</ul>
+
+<b>Comments</b>
+
+<ul>
+  <li>Comments use the ANSI C90 style (<em>/* comment */</em>) or C++ style 
+  (<em>// comment</em>). It is assumed that the programming tools support today 
+	consistently the C++ comment style.</li>
+  <li><strong>Function Comments</strong> provide for each function the following information:
+  <ul>
+    <li>one-line brief function overview.</li>
+    <li>detailed parameter explanation.</li>
+    <li>detailed information about return values.</li>
+    <li>detailed description of the actual function.</li>
+  </ul>
+  <p><b>Doxygen Example:</b></p>
+  <pre>
+/** 
+ * @brief  Enable Interrupt in NVIC Interrupt Controller
+ * @param  IRQn  interrupt number that specifies the interrupt
+ * @return none.
+ * Enable the specified interrupt in the NVIC Interrupt Controller.
+ * Other settings of the interrupt such as priority are not affected.
+ */</pre>
+  </li>
+</ul>
+
+<h3>Data Types and IO Type Qualifiers</h3>
+
+<p>
+  The <strong>Cortex-Mx HAL</strong> uses the standard types from the standard ANSI C header file
+  <strong>&lt;stdint.h&gt;</strong>. <strong>IO Type Qualifiers</strong> are used to specify the access
+  to peripheral variables. IO Type Qualifiers are indented to be used for automatic generation of 
+  debug information of peripheral registers.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt" nowrap="nowrap">IO Type Qualifier</th>
+      <th class="kt">#define</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">__I</td>
+      <td class="kt">volatile const</td>
+      <td class="kt">Read access only</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">__O</td>
+      <td class="kt">volatile</td>
+      <td class="kt">Write access only</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">__IO</td>
+      <td class="kt">volatile</td>
+      <td class="kt">Read and write access</td>
+    </tr>
+  </tbody>
+</table>
+
+<h3>CMSIS Version Number</h3>
+<p>
+  File <strong>core_cm3.h</strong> contains the version number of the CMSIS with the following define:
+</p>
+
+<pre>
+#define __CM3_CMSIS_VERSION_MAIN  (0x00)      /* [31:16] main version       */
+#define __CM3_CMSIS_VERSION_SUB   (0x03)      /* [15:0]  sub version        */
+#define __CM3_CMSIS_VERSION       ((__CM3_CMSIS_VERSION_MAIN &lt;&lt; 16) | __CM3_CMSIS_VERSION_SUB)</pre>
+
+<p>
+  File <strong>core_cm0.h</strong> contains the version number of the CMSIS with the following define:
+</p>
+
+<pre>
+#define __CM0_CMSIS_VERSION_MAIN  (0x00)      /* [31:16] main version       */
+#define __CM0_CMSIS_VERSION_SUB   (0x00)      /* [15:0]  sub version        */
+#define __CM0_CMSIS_VERSION       ((__CM0_CMSIS_VERSION_MAIN &lt;&lt; 16) | __CM0_CMSIS_VERSION_SUB)</pre>
+
+
+<h3>CMSIS Cortex Core</h3>
+<p>
+  File <strong>core_cm3.h</strong> contains the type of the CMSIS Cortex-Mx with the following define:
+</p>
+
+<pre>
+#define __CORTEX_M                (0x03)</pre>
+
+<p>
+  File <strong>core_cm0.h</strong> contains the type of the CMSIS Cortex-Mx with the following define:
+</p>
+
+<pre>
+#define __CORTEX_M                (0x00)</pre>
+
+
+<h2><a name="3"></a>CMSIS Files</h2>
+<p>
+  This section describes the Files provided in context with the CMSIS to access the Cortex-Mx
+  hardware and peripherals.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt" nowrap="nowrap">File</th>
+      <th class="kt">Provider</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap"><i>device.h</i></td>
+      <td class="kt">Device specific (provided by silicon partner)</td>
+      <td class="kt">Defines the peripherals for the actual device. The file may use 
+        several other include files to define the peripherals of the actual device.</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">core_cm0.h</td>
+      <td class="kt">ARM (for RealView ARMCC, IAR, and GNU GCC)</td>
+      <td class="kt">Defines the core peripherals for the Cortex-M0 CPU and core peripherals.</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">core_cm3.h</td>
+      <td class="kt">ARM (for RealView ARMCC, IAR, and GNU GCC)</td>
+      <td class="kt">Defines the core peripherals for the Cortex-M3 CPU and core peripherals.</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">core_cm0.c</td>
+      <td class="kt">ARM (for RealView ARMCC, IAR, and GNU GCC)</td>
+      <td class="kt">Provides helper functions that access core registers.</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">core_cm0.c</td>
+      <td class="kt">ARM (for RealView ARMCC, IAR, and GNU GCC)</td>
+      <td class="kt">Provides helper functions that access core registers.</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">startup<i>_device</i></td>
+      <td class="kt">ARM (adapted by compiler partner / silicon partner)</td>
+      <td class="kt">Provides the Cortex-Mx startup code and the complete (device specific) Interrupt Vector Table</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">system<i>_device</i></td>
+      <td class="kt">ARM (adapted by silicon partner)</td>
+      <td class="kt">Provides a device specific configuration file for the device. It configures the device initializes 
+        typically the oscillator (PLL) that is part of the microcontroller device</td>
+    </tr>
+  </tbody>
+</table>
+
+<h3><em>device.h</em></h3>
+
+<p>
+  The file <em><strong>device.h</strong></em> is provided by the silicon vendor and is the 
+  <u><strong>central include file</strong></u> that the application programmer is using in 
+  the C source code. This file contains:
+</p>
+<ul>
+  <li>
+	<p><strong>Interrupt Number Definition</strong>: provides interrupt numbers 
+	(IRQn) for all core and device specific exceptions and interrupts.</p>
+	</li>
+	<li>
+	<p><strong>Configuration for core_cm0.h / core_cm3.h</strong>: reflects the 
+	actual configuration of the Cortex-Mx processor that is part of the actual 
+	device. As such the file <strong>core_cm0.h / core_cm3.h</strong> is included that 
+	implements access to processor registers and core peripherals. </p>
+	</li>
+	<li>
+	<p><strong>Device Peripheral Access Layer</strong>: provides definitions
+    for all device peripherals. It contains all data structures and the address 
+	mapping for the device specific peripherals. </p>
+	</li>
+  <li><strong>Access Functions for Peripherals (optional)</strong>: provides
+    additional helper functions for peripherals that are useful for programming 
+	of these peripherals. Access Functions may be provided as inline functions 
+	or can be extern references to a device specific library provided by the 
+	silicon vendor.</li>
+</ul>
+
+
+<h4><strong>Interrupt Number Definition</strong></h4>
+
+<p>To access the device specific interrupts the device.h file defines IRQn 
+numbers for the complete device using a enum typedef as shown below:</p>
+<pre>
+typedef enum IRQn
+{
+/******  Cortex-M3 Processor Exceptions/Interrupt Numbers ************************************************/
+  NonMaskableInt_IRQn             = -14,      /*!&lt; 2 Non Maskable Interrupt                              */
+  HardFault_IRQn                  = -13,      /*!&lt; 3 Cortex-M3 Hard Fault Interrupt                      */
+  MemoryManagement_IRQn           = -12,      /*!&lt; 4 Cortex-M3 Memory Management Interrupt               */
+  BusFault_IRQn                   = -11,      /*!&lt; 5 Cortex-M3 Bus Fault Interrupt                       */
+  UsageFault_IRQn                 = -10,      /*!&lt; 6 Cortex-M3 Usage Fault Interrupt                     */
+  SVCall_IRQn                     = -5,       /*!&lt; 11 Cortex-M3 SV Call Interrupt                        */
+  DebugMonitor_IRQn               = -4,       /*!&lt; 12 Cortex-M3 Debug Monitor Interrupt                  */
+  PendSV_IRQn                     = -2,       /*!&lt; 14 Cortex-M3 Pend SV Interrupt                        */
+  SysTick_IRQn                    = -1,       /*!&lt; 15 Cortex-M3 System Tick Interrupt                    */
+/******  STM32 specific Interrupt Numbers ****************************************************************/
+  WWDG_STM_IRQn                   = 0,        /*!&lt; Window WatchDog Interrupt                             */
+  PVD_STM_IRQn                    = 1,        /*!&lt; PVD through EXTI Line detection Interrupt             */
+  :
+  :
+  } IRQn_Type;</pre>
+
+
+<h4>Configuration for core_cm0.h / core_cm3.h</h4>
+<p>
+  The Cortex-Mx core configuration options which are defined for each device implementation. Some 
+  configuration options are reflected in the CMSIS layer using the #define settings described below.
+</p>
+<p>
+  To access core peripherals file <em><strong>device.h</strong></em> includes file <b>core_cm0.h / core_cm3.h</b>.
+  Several features in <strong>core_cm0.h / core_cm3.h</strong> are configured by the following defines that must be 
+  defined before <strong>#include &lt;core_cm0.h&gt;</strong> / <strong>#include &lt;core_cm3.h&gt;</strong>
+  preprocessor command.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt" nowrap="nowrap">#define</th>
+      <th class="kt" nowrap="nowrap">File</th>
+      <th class="kt" nowrap="nowrap">Value</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">__NVIC_PRIO_BITS</td>
+      <td class="kt">core_cm0.h</td>
+      <td class="kt" nowrap="nowrap">(2)</td>
+      <td class="kt">Number of priority bits implemented in the NVIC (device specific)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">__NVIC_PRIO_BITS</td>
+      <td class="kt">core_cm3.h</td>
+      <td class="kt" nowrap="nowrap">(2 ... 8)</td>
+      <td class="kt">Number of priority bits implemented in the NVIC (device specific)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">__MPU_PRESENT</td>
+      <td class="kt">core_cm0.h, core_cm3.h</td>
+      <td class="kt" nowrap="nowrap">(0, 1)</td>
+      <td class="kt">Defines if an MPU is present or not</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">__Vendor_SysTickConfig</td>
+      <td class="kt">core_cm0.h, core_cm3.h</td>
+      <td class="kt" nowrap="nowrap">(1)</td>
+      <td class="kt">When this define is setup to 1, the <strong>SysTickConfig</strong> function 
+		in <strong>core_cm3.h</strong> is excluded. In this case the <em><strong>device.h</strong></em> 
+		file must contain a vendor specific implementation of this function.</td>
+    </tr>
+  </tbody>
+</table>
+
+
+<h4>Device Peripheral Access Layer</h4>
+<p>
+  Each peripheral uses a <strong>PERIPHERAL_</strong> prefix to identify peripheral registers 
+  and functions that access this specific peripheral. If more than one peripheral of the same 
+  type exists, identifiers have a postfix (digit or letter). For example:
+</p>
+<ul>
+	<li>UART_Type: defines the generic register layout for all UART channels in a device.</li>
+	<li>UART1: is a pointer to a register structure that refers to a specific UART. 
+      For example UART1-&gt;DR is the data register of UART1.</li>
+	<li>UART_SendChar(UART1, c): is a generic function that works with all UART's in the device. 
+      To communicate the UART that it accesses the first parameter is a pointer to the actual 
+      UART register structure.</li>
+	<li>UART1_SendChar(c): is an UART1 specific implementation (in this case the send function).</li>
+</ul>
+
+<h5>Minimal Requiements</h5>
+<p>
+  To access the peripheral registers and related function in a device the files <strong><em>device.h</em></strong> 
+  and <strong>core_cm0.h</strong> / <strong>core_cm3.h</strong> defines as a minimum:
+</p>
+<ul>
+  <li>The <strong>Register Layout Typedef</strong> for each peripheral that defines all register names.
+      Names that start with RESERVE are used to introduce space into the structure to adjust the addresses of
+      the peripheral registers. For example:
+      <pre>
+typedef struct {
+  __IO uint32_t CTRL;      /* SysTick Control and Status Register */
+  __IO uint32_t LOAD;      /* SysTick Reload Value Register       */
+  __IO uint32_t VAL;       /* SysTick Current Value Register      */
+  __I  uint32_t CALIB;     /* SysTick Calibration Register        */
+  } SysTick_Type;</pre>
+  </li>
+
+  <li><strong>Base Address</strong> for each peripheral (in case of multiple peripherals 
+       that use the same <strong>register layout typedef</strong> multiple base addresses are defined). For example:
+    <pre>
+#define SysTick_BASE (SCS_BASE + 0x0010)            /* SysTick Base Address */</pre>
+  </li>
+
+  <li><strong>Access Definition</strong> for each peripheral (in case of multiple peripherals that use 
+      the same <strong>register layout typedef</strong> multiple access definitions exist, i.e. UART0, 
+      UART1). For Example:
+    <pre>
+#define SysTick ((SysTick_Type *) SysTick_BASE)     /* SysTick access definition */</pre>
+  </li>
+</ul>
+
+<p>
+  These definitions allow to access the peripheral registers from user code with simple assignments like:
+</p>
+<pre>SysTick-&gt;CTRL = 0;</pre>
+
+<h5>Optional Features</h5>
+<p>In addition the <em> <strong>device.h </strong></em>file may define:</p>
+<ul>
+	<li>#define constants that simplify access to the peripheral registers. 
+	These constant define bit-positions or other specific patterns are that 
+	required for the programming of the peripheral registers. The identifiers 
+	used start with the name of the <strong>PERIPERHAL_</strong>. It is 
+	recommended to use CAPITAL letters for such #define constants.</li>
+	<li>Functions that perform more complex functions with the peripheral (i.e. 
+	status query before a sending register is accessed). Again these function 
+	start with the name of the <strong>PERIPHERAL_</strong>. </li>
+</ul>
+
+<h3>core_cm0.h and core_cm0.c</h3>
+<p>
+  File <b>core_cm0.h</b> describes the data structures for the Cortex-M0 core peripherals and does 
+  the address mapping of this structures. It also provides basic access to the Cortex-M0 core registers 
+  and core peripherals with efficient functions (defined as <strong>static inline</strong>).
+</p>
+<p>
+  File <b>core_cm0.c</b> defines several helper functions that access processor registers.
+</p>
+<p>Together these files implement the <a href="#4">Core Peripheral Access Layer</a> for a Cortex-M0.</p>
+
+<h3>core_cm3.h and core_cm3.c</h3>
+<p>
+  File <b>core_cm3.h</b> describes the data structures for the Cortex-M3 core peripherals and does 
+  the address mapping of this structures. It also provides basic access to the Cortex-M3 core registers 
+  and core peripherals with efficient functions (defined as <strong>static inline</strong>).
+</p>
+<p>
+  File <b>core_cm3.c</b> defines several helper functions that access processor registers.
+</p>
+<p>Together these files implement the <a href="#4">Core Peripheral Access Layer</a> for a Cortex-M3.</p>
+
+<h3>startup_<em>device</em></h3>
+<p>
+  A template file for <strong>startup_<em>device</em></strong> is provided by ARM for each supported
+  compiler. It is adapted by the silicon vendor to include interrupt vectors for all device specific 
+  interrupt handlers. Each interrupt handler is defined as <strong><em>weak</em></strong> function 
+  to an dummy handler. Therefore the interrupt handler can be directly used in application software 
+  without any requirements to adapt the <strong>startup_<em>device</em></strong> file.
+</p>
+<p>
+  The following exception names are fixed and define the start of the vector table for a Cortex-M0:
+</p>
+<pre>
+__Vectors       DCD     __initial_sp              ; Top of Stack
+                DCD     Reset_Handler             ; Reset Handler
+                DCD     NMI_Handler               ; NMI Handler
+                DCD     HardFault_Handler         ; Hard Fault Handler
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     SVC_Handler               ; SVCall Handler
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     PendSV_Handler            ; PendSV Handler
+                DCD     SysTick_Handler           ; SysTick Handler</pre>
+
+<p>
+  The following exception names are fixed and define the start of the vector table for a Cortex-M3:
+</p>
+<pre>
+__Vectors       DCD     __initial_sp              ; Top of Stack
+                DCD     Reset_Handler             ; Reset Handler
+                DCD     NMI_Handler               ; NMI Handler
+                DCD     HardFault_Handler         ; Hard Fault Handler
+                DCD     MemManage_Handler         ; MPU Fault Handler
+                DCD     BusFault_Handler          ; Bus Fault Handler
+                DCD     UsageFault_Handler        ; Usage Fault Handler
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     0                         ; Reserved
+                DCD     SVC_Handler               ; SVCall Handler
+                DCD     DebugMon_Handler          ; Debug Monitor Handler
+                DCD     0                         ; Reserved
+                DCD     PendSV_Handler            ; PendSV Handler
+                DCD     SysTick_Handler           ; SysTick Handler</pre>
+
+<p>
+  In the following examples for device specific interrupts are shown:
+</p>
+<pre>
+; External Interrupts
+                DCD     WWDG_IRQHandler           ; Window Watchdog
+                DCD     PVD_IRQHandler            ; PVD through EXTI Line detect
+                DCD     TAMPER_IRQHandler         ; Tamper</pre>
+
+<p>
+  Device specific interrupts must have a dummy function that can be overwritten in user code. 
+  Below is an example for this dummy function.
+</p>
+<pre>
+Default_Handler PROC
+                EXPORT WWDG_IRQHandler   [WEAK]
+                EXPORT PVD_IRQHandler    [WEAK]
+                EXPORT TAMPER_IRQHandler [WEAK]
+                :
+                :
+                WWDG_IRQHandler
+                PVD_IRQHandler
+                TAMPER_IRQHandler
+                :
+                :
+                B .
+                ENDP</pre>
+                
+<p>
+  The user application may simply define an interrupt handler function by using the handler name
+  as shown below.
+</p>
+<pre>
+void WWDG_IRQHandler(void)
+{
+  :
+  :
+}</pre>
+
+
+<h3><a name="4"></a>system_<em>device</em>.c</h3>
+<p>
+  A template file for <strong>system_<em>device</em>.c</strong> is provided by ARM but adapted by 
+  the silicon vendor to match their actual device. As a <strong>minimum requirement</strong> 
+  this file must provide a device specific system configuration function and a global variable 
+  that contains the system frequency. It configures the device and initializes typically the 
+  oscillator (PLL) that is part of the microcontroller device.
+</p>
+<p>
+  The file <strong>system_</strong><em><strong>device</strong></em><strong>.c</strong> must provide
+  as a minimum requirement the SystemInit function as shown below.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt">Function Definition</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void SystemInit (void)</td>
+      <td class="kt">Setup the microcontroller system. Typically this function configures the 
+                     oscillator (PLL) that is part of the microcontroller device. For systems 
+                     with variable clock speed it also updates the variable SystemFrequency.</td>
+    </tr>
+  </tbody>
+</table>
+
+<p>
+  Also part of the file <strong>system_</strong><em><strong>device</strong></em><strong>.c</strong> 
+  is the variable <strong>SystemFrequency</strong> which contains the current CPU clock speed shown below.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt">Variable Definition</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t SystemFrequency</td>
+      <td class="kt">Contains the system frequency (which is the system clock	frequency supplied 
+                     to the SysTick timer and the processor core clock). This variable can be 
+                     used by the user application after the call to the function SystemInit() 
+                     to setup the SysTick timer or configure other parameters. It may also be 
+                     used by debugger to query the frequency of the debug timer or configure 
+                     the trace clock speed.<br><br>
+		                 This variable may also be defined in the <strong>const</strong> space. 
+		                 The compiler must be configured to avoid the removal of this variable in 
+		                 case that the application program is not using it. It is important for 
+		                 debug systems that the variable is physically present in memory so that 
+		                 it can be examined to configure the debugger.</td>
+    </tr>
+  </tbody>
+</table>
+
+<p class="Note">Note</p>
+<ul>
+  <li><p>The above definitions are the minimum requirements for the file <strong>
+	system_</strong><em><strong>device</strong></em><strong>.c</strong>. This 
+	file may export more functions or variables that provide a more flexible 
+	configuration of the microcontroller system.</p>
+  </li>
+</ul>
+
+
+<h2>Core Peripheral Access Layer</h2>
+
+<h3>Cortex-Mx Core Register Access</h3>
+<p>
+  The following functions are defined in <strong>core_cm0.h</strong> / <strong>core_cm3.h</strong>
+  and provide access to Cortex-Mx core registers.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt">Function Definition</th>
+      <th class="kt">Core</th>
+      <th class="kt">Core Register</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __enable_irq (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">PRIMASK = 0</td>
+      <td class="kt">Global Interrupt enable (using the instruction <strong>CPSIE 
+		i</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __disable_irq (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">PRIMASK = 1</td>
+      <td class="kt">Global Interrupt disable (using the instruction <strong>
+		CPSID i</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __set_PRIMASK (uint32_t value)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">PRIMASK = value</td>
+      <td class="kt">Assign value to Priority Mask Register (using the instruction 
+		<strong>MSR</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __get_PRIMASK (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">return PRIMASK</td>
+      <td class="kt">Return Priority Mask Register (using the instruction 
+		<strong>MRS</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __enable_fault_irq (void)</td>
+      <td class="kt">M3</td>
+      <td class="kt">FAULTMASK = 0</td>
+      <td class="kt">Global Fault exception and Interrupt enable (using the 
+		instruction <strong>CPSIE 
+		f</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __disable_fault_irq (void)</td>
+      <td class="kt">M3</td>
+      <td class="kt">FAULTMASK = 1</td>
+      <td class="kt">Global Fault exception and Interrupt disable (using the 
+		instruction <strong>CPSID f</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __set_FAULTMASK (uint32_t value)</td>
+      <td class="kt">M3</td>
+      <td class="kt">FAULTMASK = value</td>
+      <td class="kt">Assign value to Fault Mask Register (using the instruction 
+		<strong>MSR</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __get_FAULTMASK (void)</td>
+      <td class="kt">M3</td>
+      <td class="kt">return FAULTMASK</td>
+      <td class="kt">Return Fault Mask Register (using the instruction <strong>MRS</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __set_BASEPRI (uint32_t value)</td>
+      <td class="kt">M3</td>
+      <td class="kt">BASEPRI = value</td>
+      <td class="kt">Set Base Priority (using the instruction <strong>MSR</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uiuint32_t __get_BASEPRI (void)</td>
+      <td class="kt">M3</td>
+      <td class="kt">return BASEPRI</td>
+      <td class="kt">Return Base Priority (using the instruction <strong>MRS</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __set_CONTROL (uint32_t value)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">CONTROL = value</td>
+      <td class="kt">Set CONTROL register value (using the instruction <strong>MSR</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __get_CONTROL (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">return CONTROL</td>
+      <td class="kt">Return Control Register Value (using the instruction
+		<strong>MRS</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __set_PSP (uint32_t TopOfProcStack)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">PSP = TopOfProcStack</td>
+      <td class="kt">Set Process Stack Pointer value (using the instruction
+		<strong>MSR</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __get_PSP (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">return PSP</td>
+      <td class="kt">Return Process Stack Pointer (using the instruction <strong>MRS</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __set_MSP (uint32_t TopOfMainStack)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">MSP = TopOfMainStack</td>
+      <td class="kt">Set Main Stack Pointer (using the instruction <strong>MSR</strong>)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __get_MSP (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">return MSP</td>
+      <td class="kt">Return Main Stack Pointer (using the instruction <strong>MRS</strong>)</td>
+    </tr>
+  </tbody>
+</table>
+
+<h3>Cortex-Mx Instruction Access</h3>
+<p>
+  The following functions are defined in <strong>core_cm0.h</strong> / <strong>core_cm3.h</strong>and
+  generate specific Cortex-Mx instructions. The functions are implemented in the file 
+  <strong>core_cm0.c</strong> / <strong>core_cm3.c</strong>.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt">Name</th>
+      <th class="kt">Core</th>
+      <th class="kt">Generated CPU Instruction</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __WFI (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">WFI</td>
+      <td class="kt">Wait for Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __WFE (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">WFE</td>
+      <td class="kt">Wait for Event</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __SEV (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">SEV</td>
+      <td class="kt">Set Event</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __ISB (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">ISB</td>
+      <td class="kt">Instruction Synchronization Barrier</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __DSB (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">DSB</td>
+      <td class="kt">Data Synchronization Barrier</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void __DMB (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">DMB</td>
+      <td class="kt">Data Memory Barrier</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __REV (uint32_t value)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">REV</td>
+      <td class="kt">Reverse byte order in integer value.</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __REV16 (uint16_t value)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">REV16</td>
+      <td class="kt">Reverse byte order in unsigned short value. </td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">sint32_t __REVSH (sint16_t value)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">REVSH</td>
+      <td class="kt">Reverse byte order in signed short value with sign extension to integer.</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __RBIT (uint32_t value)</td>
+      <td class="kt">M3</td>
+      <td class="kt">RBIT</td>
+      <td class="kt">Reverse bit order of value</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint8_t __LDREXB (uint8_t *addr)</td>
+      <td class="kt">M3</td>
+      <td class="kt">LDREXB</td>
+      <td class="kt">Load exclusive byte</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint16_t __LDREXH (uint16_t *addr)</td>
+      <td class="kt">M3</td>
+      <td class="kt">LDREXH</td>
+      <td class="kt">Load exclusive half-word</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __LDREXW (uint32_t *addr)</td>
+      <td class="kt">M3</td>
+      <td class="kt">LDREXW</td>
+      <td class="kt">Load exclusive word</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __STREXB (uint8_t value, uint8_t *addr)</td>
+      <td class="kt">M3</td>
+      <td class="kt">STREXB</td>
+      <td class="kt">Store exclusive byte</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __STREXB (uint16_t value, uint16_t *addr)</td>
+      <td class="kt">M3</td>
+      <td class="kt">STREXH</td>
+      <td class="kt">Store exclusive half-word</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t __STREXB (uint32_t value, uint32_t *addr)</td>
+      <td class="kt">M3</td>
+      <td class="kt">STREXW</td>
+      <td class="kt">Store exclusive word</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void  __CLREX (void)</td>
+      <td class="kt">M3</td>
+      <td class="kt">CLREX</td>
+      <td class="kt">Remove the exclusive lock created by __LDREXB, __LDREXH, or __LDREXW</td>
+    </tr>
+  </tbody>
+</table>
+
+
+<h3>NVIC Access Functions</h3>
+<p>
+  The CMSIS provides access to the NVIC via the register interface structure and several helper
+  functions that simplify the setup of the NVIC. The CMSIS HAL uses IRQ numbers (IRQn) to 
+  identify the interrupts. The first device interrupt has the IRQn value 0. Therefore negative 
+  IRQn values are used for processor core exceptions.
+</p>
+<p>
+  For the IRQn values of core exceptions the file <strong><em>device.h</em></strong> provides 
+  the following enum names.
+</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt" nowrap="nowrap">Core Exception enum Value</th>
+      <th class="kt">Core</th>
+      <th class="kt">IRQn</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">NonMaskableInt_IRQn</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">-14</td>
+      <td class="kt">Cortex-Mx Non Maskable Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">HardFault_IRQn</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">-13</td>
+      <td class="kt">Cortex-Mx Hard Fault Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">MemoryManagement_IRQn</td>
+      <td class="kt">M3</td>
+      <td class="kt">-12</td>
+      <td class="kt">Cortex-Mx Memory Management Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">BusFault_IRQn</td>
+      <td class="kt">M3</td>
+      <td class="kt">-11</td>
+      <td class="kt">Cortex-Mx Bus Fault Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">UsageFault_IRQn</td>
+      <td class="kt">M3</td>
+      <td class="kt">-10</td>
+      <td class="kt">Cortex-Mx Usage Fault Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">SVCall_IRQn</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">-5</td>
+      <td class="kt">Cortex-Mx SV Call Interrupt </td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">DebugMonitor_IRQn</td>
+      <td class="kt">M3</td>
+      <td class="kt">-4</td>
+      <td class="kt">Cortex-Mx Debug Monitor Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">PendSV_IRQn</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">-2</td>
+      <td class="kt">Cortex-Mx Pend SV Interrupt</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">SysTick_IRQn</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">-1</td>
+      <td class="kt">Cortex-Mx System Tick Interrupt</td>
+    </tr>
+  </tbody>
+</table>
+
+<p>The following functions simplify the setup of the NVIC.
+The functions are defined as <strong>static inline</strong>.</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt" nowrap="nowrap">Name</th>
+      <th class="kt">Core</th>
+      <th class="kt">Parameter</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void NVIC_SetPriorityGrouping (uint32_t PriorityGroup)</td>
+      <td class="kt">M3</td>
+      <td class="kt">Priority Grouping Value</td>
+      <td class="kt">Set the Priority Grouping (Groups . Subgroups)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void NVIC_EnableIRQ (IRQn_Type IRQn)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">IRQ Number</td>
+      <td class="kt">Enable IRQn</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void NVIC_DisableIRQ (IRQn_Type IRQn)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">IRQ Number</td>
+      <td class="kt">Disable IRQn</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t NVIC_GetPendingIRQ (IRQn_Type IRQn)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">IRQ Number</td>
+      <td class="kt">Return 1 if IRQn is pending else 0</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void NVIC_SetPendingIRQ (IRQn_Type IRQn)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">IRQ Number</td>
+      <td class="kt">Set IRQn Pending</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void NVIC_ClearPendingIRQ (IRQn_Type IRQn)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">IRQ Number</td>
+      <td class="kt">Clear IRQn Pending Status</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t NVIC_GetActive (IRQn_Type IRQn)</td>
+      <td class="kt">M3</td>
+      <td class="kt">IRQ Number</td>
+      <td class="kt">Return 1 if IRQn is active else 0</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void NVIC_SetPriority (IRQn_Type IRQn, uint32_t priority)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">IRQ Number, Priority</td>
+      <td class="kt">Set Priority for IRQn<br>
+                     (not threadsafe for Cortex-M0)</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t NVIC_GetPriority (IRQn_Type IRQn)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">IRQ Number</td>
+      <td class="kt">Get Priority for IRQn</td>
+    </tr>
+    <tr>
+<!--      <td class="kt" nowrap="nowrap">uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)</td> -->
+      <td class="kt">uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)</td>
+      <td class="kt">M3</td>
+      <td class="kt">IRQ Number, Priority Group, Preemtive Priority, Sub Priority</td>
+      <td class="kt">Encode priority for given group, preemtive and sub priority</td>
+    </tr>
+<!--      <td class="kt" nowrap="nowrap">NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)</td> -->
+      <td class="kt">NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)</td>
+      <td class="kt">M3</td>
+      <td class="kt">IRQ Number, Priority, pointer to Priority Group, pointer to Preemtive Priority, pointer to Sub Priority</td>
+      <td class="kt">Deccode given priority to group, preemtive and sub priority</td>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void NVIC_SystemReset (void)</td>
+      <td class="kt">M0, M3</td>
+      <td class="kt">(void)</td>
+      <td class="kt">Resets the System</td>
+    </tr>
+  </tbody>
+</table>
+<p class="Note">Note</p>
+<ul>
+  <li><p>The processor exceptions have negative enum values. Device specific interrupts 
+	       have positive enum values and start with 0. The values are defined in
+         <b><em>device.h</em></b> file.
+      </p>
+  </li>
+  <li><p>The values for <b>PreemptPriority</b> and <b>SubPriority</b>
+         used in functions <b>NVIC_EncodePriority</b> and <b>NVIC_DecodePriority</b>
+         depend on the available __NVIC_PRIO_BITS implemented in the NVIC.
+      </p>
+  </li>
+</ul>
+
+
+<h3>SysTick Configuration Function</h3>
+
+<p>The following function is used to configure the SysTick timer and start the 
+SysTick interrupt.</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt" nowrap="nowrap">Name</th>
+      <th class="kt">Parameter</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">uint32_t Sys<span class="style1">TickConfig 
+		(uint32_t ticks)</span></td>
+      <td class="kt">ticks is SysTick counter reload value</td>
+      <td class="kt">Setup the SysTick timer and enable the SysTick interrupt. After this 
+		call the SysTick timer creates interrupts with the specified time 
+		interval. <br>
+		<br>
+		Return: 0 when successful, 1 on failure.<br>
+		</td>
+    </tr>
+  </tbody>
+</table>
+
+
+<h3>Cortex-M3 ITM Debug Access</h3>
+
+<p>The Cortex-M3 incorporates the Instrumented Trace Macrocell (ITM) that 
+provides together with the Serial Viewer Output trace capabilities for the 
+microcontroller system. The ITM has 32 communication channels; two ITM 
+communication channels are used by CMSIS to output the following information:</p>
+<ul>
+	<li>ITM Channel 0: implements the <strong>ITM_putchar</strong> function 
+	which can be used for printf-style output via the debug interface.</li>
+	<li>ITM Channel 31: is reserved for the RTOS kernel and can be used for 
+	kernel awareness debugging.</li>
+</ul>
+<p class="Note">Note</p>
+<ul>
+  <li><p>The ITM channel 31 is selected for the RTOS kernel since some kernels 
+	may use the Privileged level for program execution. ITM 
+	channels have 4 groups with 8 channels each, whereby each group can be 
+	configured for access rights in the Unprivileged level. The ITM channel 0 
+	may be therefore enabled for the user task whereas ITM channel 31 may be 
+	accessible only in Privileged level from the RTOS kernel itself.</p>
+  </li>
+</ul>
+
+<p>The prototype of the <strong>ITM_putchar</strong> routine is shown in the 
+table below.</p>
+
+<table class="kt" border="0" cellpadding="0" cellspacing="0">
+  <tbody>
+    <tr>
+      <th class="kt" nowrap="nowrap">Name</th>
+      <th class="kt">Parameter</th>
+      <th class="kt">Description</th>
+    </tr>
+    <tr>
+      <td class="kt" nowrap="nowrap">void uint32_t ITM_putchar(uint32_t chr)</td>
+      <td class="kt">character to output</td>
+      <td class="kt">The function outputs a character via the ITM channel 0. The 
+		                 function returns when no debugger is connected that has booked the 
+		                 output. It is blocking when a debugger is connected, but the 
+		                 previous character send is not transmitted. <br><br>
+		                 Return: the input character 'chr'.</td>
+    </tr>
+  </tbody>
+</table>
+
+
+<p>
+  Example for the usage of the ITM Channel 31 for RTOS Kernels:
+</p>
+<pre>
+  // check if debugger connected and ITM channel enabled for tracing
+  if ((CoreDebug-&gt;DEMCR &amp; CoreDebug_DEMCR_TRCENA) &amp;&amp;
+  (ITM-&gt;TCR &amp; ITM_TCR_ITMENA) &amp;&amp;
+  (ITM-&gt;TER &amp; (1UL &lt;&lt; 31))) {
+    // transmit trace data
+    while (ITM-&gt;PORT31_U32 == 0);
+    ITM-&gt;PORT[31].u8 = task_id;      // id of next task
+    while (ITM-&gt;PORT[31].u32 == 0);
+    ITM-&gt;PORT[31].u32 = task_status; // status information
+  }</pre>
+
+
+<h2><a name="5"></a>CMSIS Example</h2>
+<p>
+  The following section shows a typical example for using the CMSIS layer in user applications.
+</p>
+<pre>
+#include &lt;device.h&gt;                              // file name depends on the device used.
+
+void SysTick_Handler (void)  {                   // SysTick Interrupt Handler
+  ;
+}
+
+void TIM1_UP_IRQHandler (void)  {                // Timer Interrupt Handler
+  ;
+}
+
+void timer1_init(int frequency) {
+                                                 // set up Timer (device specific)
+  NVIC_SetPriority (TIM1_UP_IRQn, 1);            // Set Timer priority
+  NVIC_EnableIRQ (TIM1_UP_IRQn);                 // Enable Timer Interrupt
+}
+
+void main (void) {
+  SystemInit ();
+
+  if (SysTick_Config (SystemFrequency / 1000)) { // Setup SysTick Timer for 1 msec interrupts
+    :                                            // Handle Error
+    :
+    while (1);
+  }
+
+  timer1_init ();                                // device specific timer
+
+  while (1);
+}</pre>
+
+
+</body></html>
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/License.doc b/crazyflie-firmware-src/src/lib/CMSIS/License.doc
new file mode 100644
index 0000000000000000000000000000000000000000..b6b8acecc137bca709444106cba045d3d01daedd
Binary files /dev/null and b/crazyflie-firmware-src/src/lib/CMSIS/License.doc differ
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Include/stm32f4xx.h b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Include/stm32f4xx.h
new file mode 100644
index 0000000000000000000000000000000000000000..eca2616915ee5567af47b88836a211a58badfa84
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Include/stm32f4xx.h
@@ -0,0 +1,9153 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   CMSIS Cortex-M4 Device Peripheral Access Layer Header File. 
+  *          This file contains all the peripheral register's definitions, bits 
+  *          definitions and memory mapping for STM32F4xx devices.            
+  *            
+  *          The file is the unique include file that the application programmer
+  *          is using in the C source code, usually in main.c. This file contains:
+  *           - Configuration section that allows to select:
+  *              - The device used in the target application
+  *              - To use or not the peripheral’s drivers in application code(i.e. 
+  *                code will be based on direct access to peripheral’s registers 
+  *                rather than drivers API), this option is controlled by 
+  *                "#define USE_STDPERIPH_DRIVER"
+  *              - To change few application-specific parameters such as the HSE 
+  *                crystal frequency
+  *           - Data structures and the address mapping for all peripherals
+  *           - Peripheral's registers declarations and bits definition
+  *           - Macros to access peripheral’s registers hardware
+  *  
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/** @addtogroup CMSIS
+  * @{
+  */
+
+/** @addtogroup stm32f4xx
+  * @{
+  */
+    
+#ifndef __STM32F4xx_H
+#define __STM32F4xx_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif /* __cplusplus */
+  
+/** @addtogroup Library_configuration_section
+  * @{
+  */
+  
+/* Uncomment the line below according to the target STM32 device used in your
+   application 
+  */
+
+#if !defined (STM32F40_41xxx) && !defined (STM32F427_437xx) && !defined (STM32F429_439xx) && !defined (STM32F401xx)
+  /* #define STM32F40_41xxx */   /*!< STM32F405RG, STM32F405VG, STM32F405ZG, STM32F415RG, STM32F415VG, STM32F415ZG,  
+                                     STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG, STM32F407IE, 
+                                     STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */
+
+  /* #define STM32F427_437xx */   /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG, STM32F427II,  
+                                       STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG, STM32F437II Devices */
+                                    
+  /* #define STM32F429_439xx */   /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI,  
+                                       STM32F429NG, STM32F439NI, STM32F429IG, STM32F429II, STM32F439VG, STM32F439VI, 
+                                       STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG, STM32F439NI,
+                                       STM32F439IG and STM32F439II Devices */
+                                    
+  /* #define STM32F401xx */     /*!< STM32F401CB, STM32F401CC,  STM32F401RB, STM32F401RC, STM32F401VB, STM32F401VC  
+                                     STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CExx, STM32F401RE, STM32F401VE Devices */  
+  
+#endif
+
+/* Old STM32F40XX definition, maintained for legacy purpose */
+#ifdef STM32F40XX
+  #define STM32F40_41xxx
+#endif /* STM32F40XX */
+
+/* Old STM32F427X definition, maintained for legacy purpose */
+#ifdef STM32F427X
+  #define STM32F427_437xx
+#endif /* STM32F427X */
+
+/*  Tip: To avoid modifying this file each time you need to switch between these
+        devices, you can define the device in your toolchain compiler preprocessor.
+  */
+
+#if !defined (STM32F40_41xxx) && !defined (STM32F427_437xx) && !defined (STM32F429_439xx) && !defined (STM32F401xx)
+ #error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)"
+#endif
+
+#if !defined  (USE_STDPERIPH_DRIVER)
+/**
+ * @brief Comment the line below if you will not use the peripherals drivers.
+   In this case, these drivers will not be included and the application code will 
+   be based on direct access to peripherals registers 
+   */
+  /*#define USE_STDPERIPH_DRIVER */
+#endif /* USE_STDPERIPH_DRIVER */
+
+/**
+ * @brief In the following line adjust the value of External High Speed oscillator (HSE)
+   used in your application 
+   
+   Tip: To avoid modifying this file each time you need to use different HSE, you
+        can define the HSE value in your toolchain compiler preprocessor.
+  */           
+
+#if !defined  (HSE_VALUE) 
+  #define HSE_VALUE    ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
+  
+#endif /* HSE_VALUE */
+
+/**
+ * @brief In the following line adjust the External High Speed oscillator (HSE) Startup 
+   Timeout value 
+   */
+#if !defined  (HSE_STARTUP_TIMEOUT) 
+  #define HSE_STARTUP_TIMEOUT    ((uint16_t)0x05000)   /*!< Time out for HSE start up */
+#endif /* HSE_STARTUP_TIMEOUT */   
+
+#if !defined  (HSI_VALUE)   
+  #define HSI_VALUE    ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */   
+
+/**
+ * @brief STM32F4XX Standard Peripherals Library version number V1.3.0
+   */
+#define __STM32F4XX_STDPERIPH_VERSION_MAIN   (0x01) /*!< [31:24] main version */                                  
+#define __STM32F4XX_STDPERIPH_VERSION_SUB1   (0x03) /*!< [23:16] sub1 version */
+#define __STM32F4XX_STDPERIPH_VERSION_SUB2   (0x00) /*!< [15:8]  sub2 version */
+#define __STM32F4XX_STDPERIPH_VERSION_RC     (0x00) /*!< [7:0]  release candidate */ 
+#define __STM32F4XX_STDPERIPH_VERSION        ((__STM32F4XX_STDPERIPH_VERSION_MAIN << 24)\
+                                             |(__STM32F4XX_STDPERIPH_VERSION_SUB1 << 16)\
+                                             |(__STM32F4XX_STDPERIPH_VERSION_SUB2 << 8)\
+                                             |(__STM32F4XX_STDPERIPH_VERSION_RC))
+                                             
+/**
+  * @}
+  */
+
+/** @addtogroup Configuration_section_for_CMSIS
+  * @{
+  */
+
+/**
+ * @brief Configuration of the Cortex-M4 Processor and Core Peripherals 
+ */
+#define __CM4_REV                 0x0001  /*!< Core revision r0p1                            */
+#define __MPU_PRESENT             1       /*!< STM32F4XX provides an MPU                     */
+#define __NVIC_PRIO_BITS          4       /*!< STM32F4XX uses 4 Bits for the Priority Levels */
+#define __Vendor_SysTickConfig    0       /*!< Set to 1 if different SysTick Config is used  */
+#define __FPU_PRESENT             1       /*!< FPU present                                   */
+
+/**
+ * @brief STM32F4XX Interrupt Number Definition, according to the selected device 
+ *        in @ref Library_configuration_section 
+ */
+typedef enum IRQn
+{
+/******  Cortex-M4 Processor Exceptions Numbers ****************************************************************/
+  NonMaskableInt_IRQn         = -14,    /*!< 2 Non Maskable Interrupt                                          */
+  MemoryManagement_IRQn       = -12,    /*!< 4 Cortex-M4 Memory Management Interrupt                           */
+  BusFault_IRQn               = -11,    /*!< 5 Cortex-M4 Bus Fault Interrupt                                   */
+  UsageFault_IRQn             = -10,    /*!< 6 Cortex-M4 Usage Fault Interrupt                                 */
+  SVCall_IRQn                 = -5,     /*!< 11 Cortex-M4 SV Call Interrupt                                    */
+  DebugMonitor_IRQn           = -4,     /*!< 12 Cortex-M4 Debug Monitor Interrupt                              */
+  PendSV_IRQn                 = -2,     /*!< 14 Cortex-M4 Pend SV Interrupt                                    */
+  SysTick_IRQn                = -1,     /*!< 15 Cortex-M4 System Tick Interrupt                                */
+/******  STM32 specific Interrupt Numbers **********************************************************************/
+  WWDG_IRQn                   = 0,      /*!< Window WatchDog Interrupt                                         */
+  PVD_IRQn                    = 1,      /*!< PVD through EXTI Line detection Interrupt                         */
+  TAMP_STAMP_IRQn             = 2,      /*!< Tamper and TimeStamp interrupts through the EXTI line             */
+  RTC_WKUP_IRQn               = 3,      /*!< RTC Wakeup interrupt through the EXTI line                        */
+  FLASH_IRQn                  = 4,      /*!< FLASH global Interrupt                                            */
+  RCC_IRQn                    = 5,      /*!< RCC global Interrupt                                              */
+  EXTI0_IRQn                  = 6,      /*!< EXTI Line0 Interrupt                                              */
+  EXTI1_IRQn                  = 7,      /*!< EXTI Line1 Interrupt                                              */
+  EXTI2_IRQn                  = 8,      /*!< EXTI Line2 Interrupt                                              */
+  EXTI3_IRQn                  = 9,      /*!< EXTI Line3 Interrupt                                              */
+  EXTI4_IRQn                  = 10,     /*!< EXTI Line4 Interrupt                                              */
+  DMA1_Stream0_IRQn           = 11,     /*!< DMA1 Stream 0 global Interrupt                                    */
+  DMA1_Stream1_IRQn           = 12,     /*!< DMA1 Stream 1 global Interrupt                                    */
+  DMA1_Stream2_IRQn           = 13,     /*!< DMA1 Stream 2 global Interrupt                                    */
+  DMA1_Stream3_IRQn           = 14,     /*!< DMA1 Stream 3 global Interrupt                                    */
+  DMA1_Stream4_IRQn           = 15,     /*!< DMA1 Stream 4 global Interrupt                                    */
+  DMA1_Stream5_IRQn           = 16,     /*!< DMA1 Stream 5 global Interrupt                                    */
+  DMA1_Stream6_IRQn           = 17,     /*!< DMA1 Stream 6 global Interrupt                                    */
+  ADC_IRQn                    = 18,     /*!< ADC1, ADC2 and ADC3 global Interrupts                             */
+
+#if defined (STM32F40_41xxx)
+  CAN1_TX_IRQn                = 19,     /*!< CAN1 TX Interrupt                                                 */
+  CAN1_RX0_IRQn               = 20,     /*!< CAN1 RX0 Interrupt                                                */
+  CAN1_RX1_IRQn               = 21,     /*!< CAN1 RX1 Interrupt                                                */
+  CAN1_SCE_IRQn               = 22,     /*!< CAN1 SCE Interrupt                                                */
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                                     */
+  TIM1_BRK_TIM9_IRQn          = 24,     /*!< TIM1 Break interrupt and TIM9 global interrupt                    */
+  TIM1_UP_TIM10_IRQn          = 25,     /*!< TIM1 Update Interrupt and TIM10 global interrupt                  */
+  TIM1_TRG_COM_TIM11_IRQn     = 26,     /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                                    */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                             */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                             */
+  TIM4_IRQn                   = 30,     /*!< TIM4 global Interrupt                                             */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                              */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                              */
+  I2C2_EV_IRQn                = 33,     /*!< I2C2 Event Interrupt                                              */
+  I2C2_ER_IRQn                = 34,     /*!< I2C2 Error Interrupt                                              */  
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                             */
+  SPI2_IRQn                   = 36,     /*!< SPI2 global Interrupt                                             */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                                           */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                                           */
+  USART3_IRQn                 = 39,     /*!< USART3 global Interrupt                                           */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                                   */
+  RTC_Alarm_IRQn              = 41,     /*!< RTC Alarm (A and B) through EXTI Line Interrupt                   */
+  OTG_FS_WKUP_IRQn            = 42,     /*!< USB OTG FS Wakeup through EXTI line interrupt                     */    
+  TIM8_BRK_TIM12_IRQn         = 43,     /*!< TIM8 Break Interrupt and TIM12 global interrupt                   */
+  TIM8_UP_TIM13_IRQn          = 44,     /*!< TIM8 Update Interrupt and TIM13 global interrupt                  */
+  TIM8_TRG_COM_TIM14_IRQn     = 45,     /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */
+  TIM8_CC_IRQn                = 46,     /*!< TIM8 Capture Compare Interrupt                                    */
+  DMA1_Stream7_IRQn           = 47,     /*!< DMA1 Stream7 Interrupt                                            */
+  FSMC_IRQn                   = 48,     /*!< FSMC global Interrupt                                             */
+  SDIO_IRQn                   = 49,     /*!< SDIO global Interrupt                                             */
+  TIM5_IRQn                   = 50,     /*!< TIM5 global Interrupt                                             */
+  SPI3_IRQn                   = 51,     /*!< SPI3 global Interrupt                                             */
+  UART4_IRQn                  = 52,     /*!< UART4 global Interrupt                                            */
+  UART5_IRQn                  = 53,     /*!< UART5 global Interrupt                                            */
+  TIM6_DAC_IRQn               = 54,     /*!< TIM6 global and DAC1&2 underrun error  interrupts                 */
+  TIM7_IRQn                   = 55,     /*!< TIM7 global interrupt                                             */
+  DMA2_Stream0_IRQn           = 56,     /*!< DMA2 Stream 0 global Interrupt                                    */
+  DMA2_Stream1_IRQn           = 57,     /*!< DMA2 Stream 1 global Interrupt                                    */
+  DMA2_Stream2_IRQn           = 58,     /*!< DMA2 Stream 2 global Interrupt                                    */
+  DMA2_Stream3_IRQn           = 59,     /*!< DMA2 Stream 3 global Interrupt                                    */
+  DMA2_Stream4_IRQn           = 60,     /*!< DMA2 Stream 4 global Interrupt                                    */
+  ETH_IRQn                    = 61,     /*!< Ethernet global Interrupt                                         */
+  ETH_WKUP_IRQn               = 62,     /*!< Ethernet Wakeup through EXTI line Interrupt                       */
+  CAN2_TX_IRQn                = 63,     /*!< CAN2 TX Interrupt                                                 */
+  CAN2_RX0_IRQn               = 64,     /*!< CAN2 RX0 Interrupt                                                */
+  CAN2_RX1_IRQn               = 65,     /*!< CAN2 RX1 Interrupt                                                */
+  CAN2_SCE_IRQn               = 66,     /*!< CAN2 SCE Interrupt                                                */
+  OTG_FS_IRQn                 = 67,     /*!< USB OTG FS global Interrupt                                       */
+  DMA2_Stream5_IRQn           = 68,     /*!< DMA2 Stream 5 global interrupt                                    */
+  DMA2_Stream6_IRQn           = 69,     /*!< DMA2 Stream 6 global interrupt                                    */
+  DMA2_Stream7_IRQn           = 70,     /*!< DMA2 Stream 7 global interrupt                                    */
+  USART6_IRQn                 = 71,     /*!< USART6 global interrupt                                           */
+  I2C3_EV_IRQn                = 72,     /*!< I2C3 event interrupt                                              */
+  I2C3_ER_IRQn                = 73,     /*!< I2C3 error interrupt                                              */
+  OTG_HS_EP1_OUT_IRQn         = 74,     /*!< USB OTG HS End Point 1 Out global interrupt                       */
+  OTG_HS_EP1_IN_IRQn          = 75,     /*!< USB OTG HS End Point 1 In global interrupt                        */
+  OTG_HS_WKUP_IRQn            = 76,     /*!< USB OTG HS Wakeup through EXTI interrupt                          */
+  OTG_HS_IRQn                 = 77,     /*!< USB OTG HS global interrupt                                       */
+  DCMI_IRQn                   = 78,     /*!< DCMI global interrupt                                             */
+  CRYP_IRQn                   = 79,     /*!< CRYP crypto global interrupt                                      */
+  HASH_RNG_IRQn               = 80,     /*!< Hash and Rng global interrupt                                     */
+  FPU_IRQn                    = 81      /*!< FPU global interrupt                                              */
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx)
+  CAN1_TX_IRQn                = 19,     /*!< CAN1 TX Interrupt                                                 */
+  CAN1_RX0_IRQn               = 20,     /*!< CAN1 RX0 Interrupt                                                */
+  CAN1_RX1_IRQn               = 21,     /*!< CAN1 RX1 Interrupt                                                */
+  CAN1_SCE_IRQn               = 22,     /*!< CAN1 SCE Interrupt                                                */
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                                     */
+  TIM1_BRK_TIM9_IRQn          = 24,     /*!< TIM1 Break interrupt and TIM9 global interrupt                    */
+  TIM1_UP_TIM10_IRQn          = 25,     /*!< TIM1 Update Interrupt and TIM10 global interrupt                  */
+  TIM1_TRG_COM_TIM11_IRQn     = 26,     /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                                    */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                             */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                             */
+  TIM4_IRQn                   = 30,     /*!< TIM4 global Interrupt                                             */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                              */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                              */
+  I2C2_EV_IRQn                = 33,     /*!< I2C2 Event Interrupt                                              */
+  I2C2_ER_IRQn                = 34,     /*!< I2C2 Error Interrupt                                              */  
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                             */
+  SPI2_IRQn                   = 36,     /*!< SPI2 global Interrupt                                             */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                                           */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                                           */
+  USART3_IRQn                 = 39,     /*!< USART3 global Interrupt                                           */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                                   */
+  RTC_Alarm_IRQn              = 41,     /*!< RTC Alarm (A and B) through EXTI Line Interrupt                   */
+  OTG_FS_WKUP_IRQn            = 42,     /*!< USB OTG FS Wakeup through EXTI line interrupt                     */    
+  TIM8_BRK_TIM12_IRQn         = 43,     /*!< TIM8 Break Interrupt and TIM12 global interrupt                   */
+  TIM8_UP_TIM13_IRQn          = 44,     /*!< TIM8 Update Interrupt and TIM13 global interrupt                  */
+  TIM8_TRG_COM_TIM14_IRQn     = 45,     /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */
+  TIM8_CC_IRQn                = 46,     /*!< TIM8 Capture Compare Interrupt                                    */
+  DMA1_Stream7_IRQn           = 47,     /*!< DMA1 Stream7 Interrupt                                            */
+  FMC_IRQn                    = 48,     /*!< FMC global Interrupt                                              */
+  SDIO_IRQn                   = 49,     /*!< SDIO global Interrupt                                             */
+  TIM5_IRQn                   = 50,     /*!< TIM5 global Interrupt                                             */
+  SPI3_IRQn                   = 51,     /*!< SPI3 global Interrupt                                             */
+  UART4_IRQn                  = 52,     /*!< UART4 global Interrupt                                            */
+  UART5_IRQn                  = 53,     /*!< UART5 global Interrupt                                            */
+  TIM6_DAC_IRQn               = 54,     /*!< TIM6 global and DAC1&2 underrun error  interrupts                 */
+  TIM7_IRQn                   = 55,     /*!< TIM7 global interrupt                                             */
+  DMA2_Stream0_IRQn           = 56,     /*!< DMA2 Stream 0 global Interrupt                                    */
+  DMA2_Stream1_IRQn           = 57,     /*!< DMA2 Stream 1 global Interrupt                                    */
+  DMA2_Stream2_IRQn           = 58,     /*!< DMA2 Stream 2 global Interrupt                                    */
+  DMA2_Stream3_IRQn           = 59,     /*!< DMA2 Stream 3 global Interrupt                                    */
+  DMA2_Stream4_IRQn           = 60,     /*!< DMA2 Stream 4 global Interrupt                                    */
+  ETH_IRQn                    = 61,     /*!< Ethernet global Interrupt                                         */
+  ETH_WKUP_IRQn               = 62,     /*!< Ethernet Wakeup through EXTI line Interrupt                       */
+  CAN2_TX_IRQn                = 63,     /*!< CAN2 TX Interrupt                                                 */
+  CAN2_RX0_IRQn               = 64,     /*!< CAN2 RX0 Interrupt                                                */
+  CAN2_RX1_IRQn               = 65,     /*!< CAN2 RX1 Interrupt                                                */
+  CAN2_SCE_IRQn               = 66,     /*!< CAN2 SCE Interrupt                                                */
+  OTG_FS_IRQn                 = 67,     /*!< USB OTG FS global Interrupt                                       */
+  DMA2_Stream5_IRQn           = 68,     /*!< DMA2 Stream 5 global interrupt                                    */
+  DMA2_Stream6_IRQn           = 69,     /*!< DMA2 Stream 6 global interrupt                                    */
+  DMA2_Stream7_IRQn           = 70,     /*!< DMA2 Stream 7 global interrupt                                    */
+  USART6_IRQn                 = 71,     /*!< USART6 global interrupt                                           */
+  I2C3_EV_IRQn                = 72,     /*!< I2C3 event interrupt                                              */
+  I2C3_ER_IRQn                = 73,     /*!< I2C3 error interrupt                                              */
+  OTG_HS_EP1_OUT_IRQn         = 74,     /*!< USB OTG HS End Point 1 Out global interrupt                       */
+  OTG_HS_EP1_IN_IRQn          = 75,     /*!< USB OTG HS End Point 1 In global interrupt                        */
+  OTG_HS_WKUP_IRQn            = 76,     /*!< USB OTG HS Wakeup through EXTI interrupt                          */
+  OTG_HS_IRQn                 = 77,     /*!< USB OTG HS global interrupt                                       */
+  DCMI_IRQn                   = 78,     /*!< DCMI global interrupt                                             */
+  CRYP_IRQn                   = 79,     /*!< CRYP crypto global interrupt                                      */
+  HASH_RNG_IRQn               = 80,     /*!< Hash and Rng global interrupt                                     */
+  FPU_IRQn                    = 81,     /*!< FPU global interrupt                                              */
+  UART7_IRQn                  = 82,     /*!< UART7 global interrupt                                            */
+  UART8_IRQn                  = 83,     /*!< UART8 global interrupt                                            */
+  SPI4_IRQn                   = 84,     /*!< SPI4 global Interrupt                                             */
+  SPI5_IRQn                   = 85,     /*!< SPI5 global Interrupt                                             */
+  SPI6_IRQn                   = 86,     /*!< SPI6 global Interrupt                                             */
+  SAI1_IRQn                   = 87,     /*!< SAI1 global Interrupt                                             */
+  DMA2D_IRQn                  = 90      /*!< DMA2D global Interrupt                                            */   
+#endif /* STM32F427_437xx */
+    
+#if defined (STM32F429_439xx)
+  CAN1_TX_IRQn                = 19,     /*!< CAN1 TX Interrupt                                                 */
+  CAN1_RX0_IRQn               = 20,     /*!< CAN1 RX0 Interrupt                                                */
+  CAN1_RX1_IRQn               = 21,     /*!< CAN1 RX1 Interrupt                                                */
+  CAN1_SCE_IRQn               = 22,     /*!< CAN1 SCE Interrupt                                                */
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                                     */
+  TIM1_BRK_TIM9_IRQn          = 24,     /*!< TIM1 Break interrupt and TIM9 global interrupt                    */
+  TIM1_UP_TIM10_IRQn          = 25,     /*!< TIM1 Update Interrupt and TIM10 global interrupt                  */
+  TIM1_TRG_COM_TIM11_IRQn     = 26,     /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                                    */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                             */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                             */
+  TIM4_IRQn                   = 30,     /*!< TIM4 global Interrupt                                             */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                              */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                              */
+  I2C2_EV_IRQn                = 33,     /*!< I2C2 Event Interrupt                                              */
+  I2C2_ER_IRQn                = 34,     /*!< I2C2 Error Interrupt                                              */  
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                             */
+  SPI2_IRQn                   = 36,     /*!< SPI2 global Interrupt                                             */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                                           */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                                           */
+  USART3_IRQn                 = 39,     /*!< USART3 global Interrupt                                           */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                                   */
+  RTC_Alarm_IRQn              = 41,     /*!< RTC Alarm (A and B) through EXTI Line Interrupt                   */
+  OTG_FS_WKUP_IRQn            = 42,     /*!< USB OTG FS Wakeup through EXTI line interrupt                     */    
+  TIM8_BRK_TIM12_IRQn         = 43,     /*!< TIM8 Break Interrupt and TIM12 global interrupt                   */
+  TIM8_UP_TIM13_IRQn          = 44,     /*!< TIM8 Update Interrupt and TIM13 global interrupt                  */
+  TIM8_TRG_COM_TIM14_IRQn     = 45,     /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */
+  TIM8_CC_IRQn                = 46,     /*!< TIM8 Capture Compare Interrupt                                    */
+  DMA1_Stream7_IRQn           = 47,     /*!< DMA1 Stream7 Interrupt                                            */
+  FMC_IRQn                    = 48,     /*!< FMC global Interrupt                                              */
+  SDIO_IRQn                   = 49,     /*!< SDIO global Interrupt                                             */
+  TIM5_IRQn                   = 50,     /*!< TIM5 global Interrupt                                             */
+  SPI3_IRQn                   = 51,     /*!< SPI3 global Interrupt                                             */
+  UART4_IRQn                  = 52,     /*!< UART4 global Interrupt                                            */
+  UART5_IRQn                  = 53,     /*!< UART5 global Interrupt                                            */
+  TIM6_DAC_IRQn               = 54,     /*!< TIM6 global and DAC1&2 underrun error  interrupts                 */
+  TIM7_IRQn                   = 55,     /*!< TIM7 global interrupt                                             */
+  DMA2_Stream0_IRQn           = 56,     /*!< DMA2 Stream 0 global Interrupt                                    */
+  DMA2_Stream1_IRQn           = 57,     /*!< DMA2 Stream 1 global Interrupt                                    */
+  DMA2_Stream2_IRQn           = 58,     /*!< DMA2 Stream 2 global Interrupt                                    */
+  DMA2_Stream3_IRQn           = 59,     /*!< DMA2 Stream 3 global Interrupt                                    */
+  DMA2_Stream4_IRQn           = 60,     /*!< DMA2 Stream 4 global Interrupt                                    */
+  ETH_IRQn                    = 61,     /*!< Ethernet global Interrupt                                         */
+  ETH_WKUP_IRQn               = 62,     /*!< Ethernet Wakeup through EXTI line Interrupt                       */
+  CAN2_TX_IRQn                = 63,     /*!< CAN2 TX Interrupt                                                 */
+  CAN2_RX0_IRQn               = 64,     /*!< CAN2 RX0 Interrupt                                                */
+  CAN2_RX1_IRQn               = 65,     /*!< CAN2 RX1 Interrupt                                                */
+  CAN2_SCE_IRQn               = 66,     /*!< CAN2 SCE Interrupt                                                */
+  OTG_FS_IRQn                 = 67,     /*!< USB OTG FS global Interrupt                                       */
+  DMA2_Stream5_IRQn           = 68,     /*!< DMA2 Stream 5 global interrupt                                    */
+  DMA2_Stream6_IRQn           = 69,     /*!< DMA2 Stream 6 global interrupt                                    */
+  DMA2_Stream7_IRQn           = 70,     /*!< DMA2 Stream 7 global interrupt                                    */
+  USART6_IRQn                 = 71,     /*!< USART6 global interrupt                                           */
+  I2C3_EV_IRQn                = 72,     /*!< I2C3 event interrupt                                              */
+  I2C3_ER_IRQn                = 73,     /*!< I2C3 error interrupt                                              */
+  OTG_HS_EP1_OUT_IRQn         = 74,     /*!< USB OTG HS End Point 1 Out global interrupt                       */
+  OTG_HS_EP1_IN_IRQn          = 75,     /*!< USB OTG HS End Point 1 In global interrupt                        */
+  OTG_HS_WKUP_IRQn            = 76,     /*!< USB OTG HS Wakeup through EXTI interrupt                          */
+  OTG_HS_IRQn                 = 77,     /*!< USB OTG HS global interrupt                                       */
+  DCMI_IRQn                   = 78,     /*!< DCMI global interrupt                                             */
+  CRYP_IRQn                   = 79,     /*!< CRYP crypto global interrupt                                      */
+  HASH_RNG_IRQn               = 80,     /*!< Hash and Rng global interrupt                                     */
+  FPU_IRQn                    = 81,     /*!< FPU global interrupt                                              */
+  UART7_IRQn                  = 82,     /*!< UART7 global interrupt                                            */
+  UART8_IRQn                  = 83,     /*!< UART8 global interrupt                                            */
+  SPI4_IRQn                   = 84,     /*!< SPI4 global Interrupt                                             */
+  SPI5_IRQn                   = 85,     /*!< SPI5 global Interrupt                                             */
+  SPI6_IRQn                   = 86,     /*!< SPI6 global Interrupt                                             */
+  SAI1_IRQn                   = 87,     /*!< SAI1 global Interrupt                                             */
+  LTDC_IRQn                   = 88,     /*!< LTDC global Interrupt                                             */
+  LTDC_ER_IRQn                = 89,     /*!< LTDC Error global Interrupt                                       */
+  DMA2D_IRQn                  = 90      /*!< DMA2D global Interrupt                                            */   
+#endif /* STM32F429_439xx */
+   
+#if defined (STM32F401xx)
+  EXTI9_5_IRQn                = 23,     /*!< External Line[9:5] Interrupts                                     */
+  TIM1_BRK_TIM9_IRQn          = 24,     /*!< TIM1 Break interrupt and TIM9 global interrupt                    */
+  TIM1_UP_TIM10_IRQn          = 25,     /*!< TIM1 Update Interrupt and TIM10 global interrupt                  */
+  TIM1_TRG_COM_TIM11_IRQn     = 26,     /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */
+  TIM1_CC_IRQn                = 27,     /*!< TIM1 Capture Compare Interrupt                                    */
+  TIM2_IRQn                   = 28,     /*!< TIM2 global Interrupt                                             */
+  TIM3_IRQn                   = 29,     /*!< TIM3 global Interrupt                                             */
+  TIM4_IRQn                   = 30,     /*!< TIM4 global Interrupt                                             */
+  I2C1_EV_IRQn                = 31,     /*!< I2C1 Event Interrupt                                              */
+  I2C1_ER_IRQn                = 32,     /*!< I2C1 Error Interrupt                                              */
+  I2C2_EV_IRQn                = 33,     /*!< I2C2 Event Interrupt                                              */
+  I2C2_ER_IRQn                = 34,     /*!< I2C2 Error Interrupt                                              */  
+  SPI1_IRQn                   = 35,     /*!< SPI1 global Interrupt                                             */
+  SPI2_IRQn                   = 36,     /*!< SPI2 global Interrupt                                             */
+  USART1_IRQn                 = 37,     /*!< USART1 global Interrupt                                           */
+  USART2_IRQn                 = 38,     /*!< USART2 global Interrupt                                           */
+  EXTI15_10_IRQn              = 40,     /*!< External Line[15:10] Interrupts                                   */
+  RTC_Alarm_IRQn              = 41,     /*!< RTC Alarm (A and B) through EXTI Line Interrupt                   */
+  OTG_FS_WKUP_IRQn            = 42,     /*!< USB OTG FS Wakeup through EXTI line interrupt                     */  
+  DMA1_Stream7_IRQn           = 47,     /*!< DMA1 Stream7 Interrupt                                            */
+  SDIO_IRQn                   = 49,     /*!< SDIO global Interrupt                                             */
+  TIM5_IRQn                   = 50,     /*!< TIM5 global Interrupt                                             */
+  SPI3_IRQn                   = 51,     /*!< SPI3 global Interrupt                                             */
+  DMA2_Stream0_IRQn           = 56,     /*!< DMA2 Stream 0 global Interrupt                                    */
+  DMA2_Stream1_IRQn           = 57,     /*!< DMA2 Stream 1 global Interrupt                                    */
+  DMA2_Stream2_IRQn           = 58,     /*!< DMA2 Stream 2 global Interrupt                                    */
+  DMA2_Stream3_IRQn           = 59,     /*!< DMA2 Stream 3 global Interrupt                                    */
+  DMA2_Stream4_IRQn           = 60,     /*!< DMA2 Stream 4 global Interrupt                                    */
+  OTG_FS_IRQn                 = 67,     /*!< USB OTG FS global Interrupt                                       */
+  DMA2_Stream5_IRQn           = 68,     /*!< DMA2 Stream 5 global interrupt                                    */
+  DMA2_Stream6_IRQn           = 69,     /*!< DMA2 Stream 6 global interrupt                                    */
+  DMA2_Stream7_IRQn           = 70,     /*!< DMA2 Stream 7 global interrupt                                    */
+  USART6_IRQn                 = 71,     /*!< USART6 global interrupt                                           */
+  I2C3_EV_IRQn                = 72,     /*!< I2C3 event interrupt                                              */
+  I2C3_ER_IRQn                = 73,     /*!< I2C3 error interrupt                                              */
+  FPU_IRQn                    = 81,      /*!< FPU global interrupt                                             */
+  SPI4_IRQn                   = 84       /*!< SPI4 global Interrupt                                            */
+#endif /* STM32F401xx */
+
+} IRQn_Type;
+
+/**
+  * @}
+  */
+
+#include "core_cm4.h"             /* Cortex-M4 processor and core peripherals */
+#include "system_stm32f4xx.h"
+#include <stdint.h>
+
+/** @addtogroup Exported_types
+  * @{
+  */  
+/*!< STM32F10x Standard Peripheral Library old types (maintained for legacy purpose) */
+typedef int32_t  s32;
+typedef int16_t s16;
+typedef int8_t  s8;
+
+typedef const int32_t sc32;  /*!< Read Only */
+typedef const int16_t sc16;  /*!< Read Only */
+typedef const int8_t sc8;   /*!< Read Only */
+
+typedef __IO int32_t  vs32;
+typedef __IO int16_t  vs16;
+typedef __IO int8_t   vs8;
+
+typedef __I int32_t vsc32;  /*!< Read Only */
+typedef __I int16_t vsc16;  /*!< Read Only */
+typedef __I int8_t vsc8;   /*!< Read Only */
+
+typedef uint32_t  u32;
+typedef uint16_t u16;
+typedef uint8_t  u8;
+
+typedef const uint32_t uc32;  /*!< Read Only */
+typedef const uint16_t uc16;  /*!< Read Only */
+typedef const uint8_t uc8;   /*!< Read Only */
+
+typedef __IO uint32_t  vu32;
+typedef __IO uint16_t vu16;
+typedef __IO uint8_t  vu8;
+
+typedef __I uint32_t vuc32;  /*!< Read Only */
+typedef __I uint16_t vuc16;  /*!< Read Only */
+typedef __I uint8_t vuc8;   /*!< Read Only */
+
+typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;
+
+typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
+#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
+
+typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
+
+/**
+  * @}
+  */
+
+/** @addtogroup Peripheral_registers_structures
+  * @{
+  */   
+
+/** 
+  * @brief Analog to Digital Converter  
+  */
+
+typedef struct
+{
+  __IO uint32_t SR;     /*!< ADC status register,                         Address offset: 0x00 */
+  __IO uint32_t CR1;    /*!< ADC control register 1,                      Address offset: 0x04 */      
+  __IO uint32_t CR2;    /*!< ADC control register 2,                      Address offset: 0x08 */
+  __IO uint32_t SMPR1;  /*!< ADC sample time register 1,                  Address offset: 0x0C */
+  __IO uint32_t SMPR2;  /*!< ADC sample time register 2,                  Address offset: 0x10 */
+  __IO uint32_t JOFR1;  /*!< ADC injected channel data offset register 1, Address offset: 0x14 */
+  __IO uint32_t JOFR2;  /*!< ADC injected channel data offset register 2, Address offset: 0x18 */
+  __IO uint32_t JOFR3;  /*!< ADC injected channel data offset register 3, Address offset: 0x1C */
+  __IO uint32_t JOFR4;  /*!< ADC injected channel data offset register 4, Address offset: 0x20 */
+  __IO uint32_t HTR;    /*!< ADC watchdog higher threshold register,      Address offset: 0x24 */
+  __IO uint32_t LTR;    /*!< ADC watchdog lower threshold register,       Address offset: 0x28 */
+  __IO uint32_t SQR1;   /*!< ADC regular sequence register 1,             Address offset: 0x2C */
+  __IO uint32_t SQR2;   /*!< ADC regular sequence register 2,             Address offset: 0x30 */
+  __IO uint32_t SQR3;   /*!< ADC regular sequence register 3,             Address offset: 0x34 */
+  __IO uint32_t JSQR;   /*!< ADC injected sequence register,              Address offset: 0x38*/
+  __IO uint32_t JDR1;   /*!< ADC injected data register 1,                Address offset: 0x3C */
+  __IO uint32_t JDR2;   /*!< ADC injected data register 2,                Address offset: 0x40 */
+  __IO uint32_t JDR3;   /*!< ADC injected data register 3,                Address offset: 0x44 */
+  __IO uint32_t JDR4;   /*!< ADC injected data register 4,                Address offset: 0x48 */
+  __IO uint32_t DR;     /*!< ADC regular data register,                   Address offset: 0x4C */
+} ADC_TypeDef;
+
+typedef struct
+{
+  __IO uint32_t CSR;    /*!< ADC Common status register,                  Address offset: ADC1 base address + 0x300 */
+  __IO uint32_t CCR;    /*!< ADC common control register,                 Address offset: ADC1 base address + 0x304 */
+  __IO uint32_t CDR;    /*!< ADC common regular data register for dual
+                             AND triple modes,                            Address offset: ADC1 base address + 0x308 */
+} ADC_Common_TypeDef;
+
+
+/** 
+  * @brief Controller Area Network TxMailBox 
+  */
+
+typedef struct
+{
+  __IO uint32_t TIR;  /*!< CAN TX mailbox identifier register */
+  __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */
+  __IO uint32_t TDLR; /*!< CAN mailbox data low register */
+  __IO uint32_t TDHR; /*!< CAN mailbox data high register */
+} CAN_TxMailBox_TypeDef;
+
+/** 
+  * @brief Controller Area Network FIFOMailBox 
+  */
+  
+typedef struct
+{
+  __IO uint32_t RIR;  /*!< CAN receive FIFO mailbox identifier register */
+  __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */
+  __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */
+  __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */
+} CAN_FIFOMailBox_TypeDef;
+
+/** 
+  * @brief Controller Area Network FilterRegister 
+  */
+  
+typedef struct
+{
+  __IO uint32_t FR1; /*!< CAN Filter bank register 1 */
+  __IO uint32_t FR2; /*!< CAN Filter bank register 1 */
+} CAN_FilterRegister_TypeDef;
+
+/** 
+  * @brief Controller Area Network 
+  */
+  
+typedef struct
+{
+  __IO uint32_t              MCR;                 /*!< CAN master control register,         Address offset: 0x00          */
+  __IO uint32_t              MSR;                 /*!< CAN master status register,          Address offset: 0x04          */
+  __IO uint32_t              TSR;                 /*!< CAN transmit status register,        Address offset: 0x08          */
+  __IO uint32_t              RF0R;                /*!< CAN receive FIFO 0 register,         Address offset: 0x0C          */
+  __IO uint32_t              RF1R;                /*!< CAN receive FIFO 1 register,         Address offset: 0x10          */
+  __IO uint32_t              IER;                 /*!< CAN interrupt enable register,       Address offset: 0x14          */
+  __IO uint32_t              ESR;                 /*!< CAN error status register,           Address offset: 0x18          */
+  __IO uint32_t              BTR;                 /*!< CAN bit timing register,             Address offset: 0x1C          */
+  uint32_t                   RESERVED0[88];       /*!< Reserved, 0x020 - 0x17F                                            */
+  CAN_TxMailBox_TypeDef      sTxMailBox[3];       /*!< CAN Tx MailBox,                      Address offset: 0x180 - 0x1AC */
+  CAN_FIFOMailBox_TypeDef    sFIFOMailBox[2];     /*!< CAN FIFO MailBox,                    Address offset: 0x1B0 - 0x1CC */
+  uint32_t                   RESERVED1[12];       /*!< Reserved, 0x1D0 - 0x1FF                                            */
+  __IO uint32_t              FMR;                 /*!< CAN filter master register,          Address offset: 0x200         */
+  __IO uint32_t              FM1R;                /*!< CAN filter mode register,            Address offset: 0x204         */
+  uint32_t                   RESERVED2;           /*!< Reserved, 0x208                                                    */
+  __IO uint32_t              FS1R;                /*!< CAN filter scale register,           Address offset: 0x20C         */
+  uint32_t                   RESERVED3;           /*!< Reserved, 0x210                                                    */
+  __IO uint32_t              FFA1R;               /*!< CAN filter FIFO assignment register, Address offset: 0x214         */
+  uint32_t                   RESERVED4;           /*!< Reserved, 0x218                                                    */
+  __IO uint32_t              FA1R;                /*!< CAN filter activation register,      Address offset: 0x21C         */
+  uint32_t                   RESERVED5[8];        /*!< Reserved, 0x220-0x23F                                              */ 
+  CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register,                 Address offset: 0x240-0x31C   */
+} CAN_TypeDef;
+
+/** 
+  * @brief CRC calculation unit 
+  */
+
+typedef struct
+{
+  __IO uint32_t DR;         /*!< CRC Data register,             Address offset: 0x00 */
+  __IO uint8_t  IDR;        /*!< CRC Independent data register, Address offset: 0x04 */
+  uint8_t       RESERVED0;  /*!< Reserved, 0x05                                      */
+  uint16_t      RESERVED1;  /*!< Reserved, 0x06                                      */
+  __IO uint32_t CR;         /*!< CRC Control register,          Address offset: 0x08 */
+} CRC_TypeDef;
+
+/** 
+  * @brief Digital to Analog Converter
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;       /*!< DAC control register,                                    Address offset: 0x00 */
+  __IO uint32_t SWTRIGR;  /*!< DAC software trigger register,                           Address offset: 0x04 */
+  __IO uint32_t DHR12R1;  /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */
+  __IO uint32_t DHR12L1;  /*!< DAC channel1 12-bit left aligned data holding register,  Address offset: 0x0C */
+  __IO uint32_t DHR8R1;   /*!< DAC channel1 8-bit right aligned data holding register,  Address offset: 0x10 */
+  __IO uint32_t DHR12R2;  /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */
+  __IO uint32_t DHR12L2;  /*!< DAC channel2 12-bit left aligned data holding register,  Address offset: 0x18 */
+  __IO uint32_t DHR8R2;   /*!< DAC channel2 8-bit right-aligned data holding register,  Address offset: 0x1C */
+  __IO uint32_t DHR12RD;  /*!< Dual DAC 12-bit right-aligned data holding register,     Address offset: 0x20 */
+  __IO uint32_t DHR12LD;  /*!< DUAL DAC 12-bit left aligned data holding register,      Address offset: 0x24 */
+  __IO uint32_t DHR8RD;   /*!< DUAL DAC 8-bit right aligned data holding register,      Address offset: 0x28 */
+  __IO uint32_t DOR1;     /*!< DAC channel1 data output register,                       Address offset: 0x2C */
+  __IO uint32_t DOR2;     /*!< DAC channel2 data output register,                       Address offset: 0x30 */
+  __IO uint32_t SR;       /*!< DAC status register,                                     Address offset: 0x34 */
+} DAC_TypeDef;
+
+/** 
+  * @brief Debug MCU
+  */
+
+typedef struct
+{
+  __IO uint32_t IDCODE;  /*!< MCU device ID code,               Address offset: 0x00 */
+  __IO uint32_t CR;      /*!< Debug MCU configuration register, Address offset: 0x04 */
+  __IO uint32_t APB1FZ;  /*!< Debug MCU APB1 freeze register,   Address offset: 0x08 */
+  __IO uint32_t APB2FZ;  /*!< Debug MCU APB2 freeze register,   Address offset: 0x0C */
+}DBGMCU_TypeDef;
+
+/** 
+  * @brief DCMI
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;       /*!< DCMI control register 1,                       Address offset: 0x00 */
+  __IO uint32_t SR;       /*!< DCMI status register,                          Address offset: 0x04 */
+  __IO uint32_t RISR;     /*!< DCMI raw interrupt status register,            Address offset: 0x08 */
+  __IO uint32_t IER;      /*!< DCMI interrupt enable register,                Address offset: 0x0C */
+  __IO uint32_t MISR;     /*!< DCMI masked interrupt status register,         Address offset: 0x10 */
+  __IO uint32_t ICR;      /*!< DCMI interrupt clear register,                 Address offset: 0x14 */
+  __IO uint32_t ESCR;     /*!< DCMI embedded synchronization code register,   Address offset: 0x18 */
+  __IO uint32_t ESUR;     /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */
+  __IO uint32_t CWSTRTR;  /*!< DCMI crop window start,                        Address offset: 0x20 */
+  __IO uint32_t CWSIZER;  /*!< DCMI crop window size,                         Address offset: 0x24 */
+  __IO uint32_t DR;       /*!< DCMI data register,                            Address offset: 0x28 */
+} DCMI_TypeDef;
+
+/** 
+  * @brief DMA Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;     /*!< DMA stream x configuration register      */
+  __IO uint32_t NDTR;   /*!< DMA stream x number of data register     */
+  __IO uint32_t PAR;    /*!< DMA stream x peripheral address register */
+  __IO uint32_t M0AR;   /*!< DMA stream x memory 0 address register   */
+  __IO uint32_t M1AR;   /*!< DMA stream x memory 1 address register   */
+  __IO uint32_t FCR;    /*!< DMA stream x FIFO control register       */
+} DMA_Stream_TypeDef;
+
+typedef struct
+{
+  __IO uint32_t LISR;   /*!< DMA low interrupt status register,      Address offset: 0x00 */
+  __IO uint32_t HISR;   /*!< DMA high interrupt status register,     Address offset: 0x04 */
+  __IO uint32_t LIFCR;  /*!< DMA low interrupt flag clear register,  Address offset: 0x08 */
+  __IO uint32_t HIFCR;  /*!< DMA high interrupt flag clear register, Address offset: 0x0C */
+} DMA_TypeDef;
+ 
+/** 
+  * @brief DMA2D Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;            /*!< DMA2D Control Register,                         Address offset: 0x00 */
+  __IO uint32_t ISR;           /*!< DMA2D Interrupt Status Register,                Address offset: 0x04 */
+  __IO uint32_t IFCR;          /*!< DMA2D Interrupt Flag Clear Register,            Address offset: 0x08 */
+  __IO uint32_t FGMAR;         /*!< DMA2D Foreground Memory Address Register,       Address offset: 0x0C */
+  __IO uint32_t FGOR;          /*!< DMA2D Foreground Offset Register,               Address offset: 0x10 */
+  __IO uint32_t BGMAR;         /*!< DMA2D Background Memory Address Register,       Address offset: 0x14 */
+  __IO uint32_t BGOR;          /*!< DMA2D Background Offset Register,               Address offset: 0x18 */
+  __IO uint32_t FGPFCCR;       /*!< DMA2D Foreground PFC Control Register,          Address offset: 0x1C */
+  __IO uint32_t FGCOLR;        /*!< DMA2D Foreground Color Register,                Address offset: 0x20 */
+  __IO uint32_t BGPFCCR;       /*!< DMA2D Background PFC Control Register,          Address offset: 0x24 */
+  __IO uint32_t BGCOLR;        /*!< DMA2D Background Color Register,                Address offset: 0x28 */
+  __IO uint32_t FGCMAR;        /*!< DMA2D Foreground CLUT Memory Address Register,  Address offset: 0x2C */
+  __IO uint32_t BGCMAR;        /*!< DMA2D Background CLUT Memory Address Register,  Address offset: 0x30 */
+  __IO uint32_t OPFCCR;        /*!< DMA2D Output PFC Control Register,              Address offset: 0x34 */
+  __IO uint32_t OCOLR;         /*!< DMA2D Output Color Register,                    Address offset: 0x38 */
+  __IO uint32_t OMAR;          /*!< DMA2D Output Memory Address Register,           Address offset: 0x3C */
+  __IO uint32_t OOR;           /*!< DMA2D Output Offset Register,                   Address offset: 0x40 */
+  __IO uint32_t NLR;           /*!< DMA2D Number of Line Register,                  Address offset: 0x44 */
+  __IO uint32_t LWR;           /*!< DMA2D Line Watermark Register,                  Address offset: 0x48 */
+  __IO uint32_t AMTCR;         /*!< DMA2D AHB Master Timer Configuration Register,  Address offset: 0x4C */
+  uint32_t      RESERVED[236]; /*!< Reserved, 0x50-0x3FF */
+  __IO uint32_t FGCLUT[256];   /*!< DMA2D Foreground CLUT,                          Address offset:400-7FF */
+  __IO uint32_t BGCLUT[256];   /*!< DMA2D Background CLUT,                          Address offset:800-BFF */
+} DMA2D_TypeDef;
+
+/** 
+  * @brief Ethernet MAC
+  */
+
+typedef struct
+{
+  __IO uint32_t MACCR;
+  __IO uint32_t MACFFR;
+  __IO uint32_t MACHTHR;
+  __IO uint32_t MACHTLR;
+  __IO uint32_t MACMIIAR;
+  __IO uint32_t MACMIIDR;
+  __IO uint32_t MACFCR;
+  __IO uint32_t MACVLANTR;             /*    8 */
+  uint32_t      RESERVED0[2];
+  __IO uint32_t MACRWUFFR;             /*   11 */
+  __IO uint32_t MACPMTCSR;
+  uint32_t      RESERVED1[2];
+  __IO uint32_t MACSR;                 /*   15 */
+  __IO uint32_t MACIMR;
+  __IO uint32_t MACA0HR;
+  __IO uint32_t MACA0LR;
+  __IO uint32_t MACA1HR;
+  __IO uint32_t MACA1LR;
+  __IO uint32_t MACA2HR;
+  __IO uint32_t MACA2LR;
+  __IO uint32_t MACA3HR;
+  __IO uint32_t MACA3LR;               /*   24 */
+  uint32_t      RESERVED2[40];
+  __IO uint32_t MMCCR;                 /*   65 */
+  __IO uint32_t MMCRIR;
+  __IO uint32_t MMCTIR;
+  __IO uint32_t MMCRIMR;
+  __IO uint32_t MMCTIMR;               /*   69 */
+  uint32_t      RESERVED3[14];
+  __IO uint32_t MMCTGFSCCR;            /*   84 */
+  __IO uint32_t MMCTGFMSCCR;
+  uint32_t      RESERVED4[5];
+  __IO uint32_t MMCTGFCR;
+  uint32_t      RESERVED5[10];
+  __IO uint32_t MMCRFCECR;
+  __IO uint32_t MMCRFAECR;
+  uint32_t      RESERVED6[10];
+  __IO uint32_t MMCRGUFCR;
+  uint32_t      RESERVED7[334];
+  __IO uint32_t PTPTSCR;
+  __IO uint32_t PTPSSIR;
+  __IO uint32_t PTPTSHR;
+  __IO uint32_t PTPTSLR;
+  __IO uint32_t PTPTSHUR;
+  __IO uint32_t PTPTSLUR;
+  __IO uint32_t PTPTSAR;
+  __IO uint32_t PTPTTHR;
+  __IO uint32_t PTPTTLR;
+  __IO uint32_t RESERVED8;
+  __IO uint32_t PTPTSSR;
+  uint32_t      RESERVED9[565];
+  __IO uint32_t DMABMR;
+  __IO uint32_t DMATPDR;
+  __IO uint32_t DMARPDR;
+  __IO uint32_t DMARDLAR;
+  __IO uint32_t DMATDLAR;
+  __IO uint32_t DMASR;
+  __IO uint32_t DMAOMR;
+  __IO uint32_t DMAIER;
+  __IO uint32_t DMAMFBOCR;
+  __IO uint32_t DMARSWTR;
+  uint32_t      RESERVED10[8];
+  __IO uint32_t DMACHTDR;
+  __IO uint32_t DMACHRDR;
+  __IO uint32_t DMACHTBAR;
+  __IO uint32_t DMACHRBAR;
+} ETH_TypeDef;
+
+/** 
+  * @brief External Interrupt/Event Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t IMR;    /*!< EXTI Interrupt mask register,            Address offset: 0x00 */
+  __IO uint32_t EMR;    /*!< EXTI Event mask register,                Address offset: 0x04 */
+  __IO uint32_t RTSR;   /*!< EXTI Rising trigger selection register,  Address offset: 0x08 */
+  __IO uint32_t FTSR;   /*!< EXTI Falling trigger selection register, Address offset: 0x0C */
+  __IO uint32_t SWIER;  /*!< EXTI Software interrupt event register,  Address offset: 0x10 */
+  __IO uint32_t PR;     /*!< EXTI Pending register,                   Address offset: 0x14 */
+} EXTI_TypeDef;
+
+/** 
+  * @brief FLASH Registers
+  */
+
+typedef struct
+{
+  __IO uint32_t ACR;      /*!< FLASH access control register,   Address offset: 0x00 */
+  __IO uint32_t KEYR;     /*!< FLASH key register,              Address offset: 0x04 */
+  __IO uint32_t OPTKEYR;  /*!< FLASH option key register,       Address offset: 0x08 */
+  __IO uint32_t SR;       /*!< FLASH status register,           Address offset: 0x0C */
+  __IO uint32_t CR;       /*!< FLASH control register,          Address offset: 0x10 */
+  __IO uint32_t OPTCR;    /*!< FLASH option control register ,  Address offset: 0x14 */
+  __IO uint32_t OPTCR1;   /*!< FLASH option control register 1, Address offset: 0x18 */
+} FLASH_TypeDef;
+
+#if defined (STM32F40_41xxx)
+/** 
+  * @brief Flexible Static Memory Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t BTCR[8];    /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */   
+} FSMC_Bank1_TypeDef; 
+
+/** 
+  * @brief Flexible Static Memory Controller Bank1E
+  */
+  
+typedef struct
+{
+  __IO uint32_t BWTR[7];    /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */
+} FSMC_Bank1E_TypeDef;
+
+/** 
+  * @brief Flexible Static Memory Controller Bank2
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR2;       /*!< NAND Flash control register 2,                       Address offset: 0x60 */
+  __IO uint32_t SR2;        /*!< NAND Flash FIFO status and interrupt register 2,     Address offset: 0x64 */
+  __IO uint32_t PMEM2;      /*!< NAND Flash Common memory space timing register 2,    Address offset: 0x68 */
+  __IO uint32_t PATT2;      /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */
+  uint32_t      RESERVED0;  /*!< Reserved, 0x70                                                            */
+  __IO uint32_t ECCR2;      /*!< NAND Flash ECC result registers 2,                   Address offset: 0x74 */
+} FSMC_Bank2_TypeDef;
+
+/** 
+  * @brief Flexible Static Memory Controller Bank3
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR3;       /*!< NAND Flash control register 3,                       Address offset: 0x80 */
+  __IO uint32_t SR3;        /*!< NAND Flash FIFO status and interrupt register 3,     Address offset: 0x84 */
+  __IO uint32_t PMEM3;      /*!< NAND Flash Common memory space timing register 3,    Address offset: 0x88 */
+  __IO uint32_t PATT3;      /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */
+  uint32_t      RESERVED0;  /*!< Reserved, 0x90                                                            */
+  __IO uint32_t ECCR3;      /*!< NAND Flash ECC result registers 3,                   Address offset: 0x94 */
+} FSMC_Bank3_TypeDef;
+
+/** 
+  * @brief Flexible Static Memory Controller Bank4
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR4;       /*!< PC Card  control register 4,                       Address offset: 0xA0 */
+  __IO uint32_t SR4;        /*!< PC Card  FIFO status and interrupt register 4,     Address offset: 0xA4 */
+  __IO uint32_t PMEM4;      /*!< PC Card  Common memory space timing register 4,    Address offset: 0xA8 */
+  __IO uint32_t PATT4;      /*!< PC Card  Attribute memory space timing register 4, Address offset: 0xAC */
+  __IO uint32_t PIO4;       /*!< PC Card  I/O space timing register 4,              Address offset: 0xB0 */
+} FSMC_Bank4_TypeDef; 
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+/** 
+  * @brief Flexible Memory Controller
+  */
+
+typedef struct
+{
+  __IO uint32_t BTCR[8];    /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */   
+} FMC_Bank1_TypeDef; 
+
+/** 
+  * @brief Flexible Memory Controller Bank1E
+  */
+  
+typedef struct
+{
+  __IO uint32_t BWTR[7];    /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */
+} FMC_Bank1E_TypeDef;
+
+/** 
+  * @brief Flexible Memory Controller Bank2
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR2;       /*!< NAND Flash control register 2,                       Address offset: 0x60 */
+  __IO uint32_t SR2;        /*!< NAND Flash FIFO status and interrupt register 2,     Address offset: 0x64 */
+  __IO uint32_t PMEM2;      /*!< NAND Flash Common memory space timing register 2,    Address offset: 0x68 */
+  __IO uint32_t PATT2;      /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */
+  uint32_t      RESERVED0;  /*!< Reserved, 0x70                                                            */
+  __IO uint32_t ECCR2;      /*!< NAND Flash ECC result registers 2,                   Address offset: 0x74 */
+} FMC_Bank2_TypeDef;
+
+/** 
+  * @brief Flexible Memory Controller Bank3
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR3;       /*!< NAND Flash control register 3,                       Address offset: 0x80 */
+  __IO uint32_t SR3;        /*!< NAND Flash FIFO status and interrupt register 3,     Address offset: 0x84 */
+  __IO uint32_t PMEM3;      /*!< NAND Flash Common memory space timing register 3,    Address offset: 0x88 */
+  __IO uint32_t PATT3;      /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */
+  uint32_t      RESERVED0;  /*!< Reserved, 0x90                                                            */
+  __IO uint32_t ECCR3;      /*!< NAND Flash ECC result registers 3,                   Address offset: 0x94 */
+} FMC_Bank3_TypeDef;
+
+/** 
+  * @brief Flexible Memory Controller Bank4
+  */
+  
+typedef struct
+{
+  __IO uint32_t PCR4;       /*!< PC Card  control register 4,                       Address offset: 0xA0 */
+  __IO uint32_t SR4;        /*!< PC Card  FIFO status and interrupt register 4,     Address offset: 0xA4 */
+  __IO uint32_t PMEM4;      /*!< PC Card  Common memory space timing register 4,    Address offset: 0xA8 */
+  __IO uint32_t PATT4;      /*!< PC Card  Attribute memory space timing register 4, Address offset: 0xAC */
+  __IO uint32_t PIO4;       /*!< PC Card  I/O space timing register 4,              Address offset: 0xB0 */
+} FMC_Bank4_TypeDef; 
+
+/** 
+  * @brief Flexible Memory Controller Bank5_6
+  */
+  
+typedef struct
+{
+  __IO uint32_t SDCR[2];        /*!< SDRAM Control registers ,      Address offset: 0x140-0x144  */
+  __IO uint32_t SDTR[2];        /*!< SDRAM Timing registers ,       Address offset: 0x148-0x14C  */
+  __IO uint32_t SDCMR;       /*!< SDRAM Command Mode register,    Address offset: 0x150  */
+  __IO uint32_t SDRTR;       /*!< SDRAM Refresh Timer register,   Address offset: 0x154  */
+  __IO uint32_t SDSR;        /*!< SDRAM Status register,          Address offset: 0x158  */
+} FMC_Bank5_6_TypeDef; 
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+/** 
+  * @brief General Purpose I/O
+  */
+
+typedef struct
+{
+  __IO uint32_t MODER;    /*!< GPIO port mode register,               Address offset: 0x00      */
+  __IO uint32_t OTYPER;   /*!< GPIO port output type register,        Address offset: 0x04      */
+  __IO uint32_t OSPEEDR;  /*!< GPIO port output speed register,       Address offset: 0x08      */
+  __IO uint32_t PUPDR;    /*!< GPIO port pull-up/pull-down register,  Address offset: 0x0C      */
+  __IO uint32_t IDR;      /*!< GPIO port input data register,         Address offset: 0x10      */
+  __IO uint32_t ODR;      /*!< GPIO port output data register,        Address offset: 0x14      */
+  __IO uint16_t BSRRL;    /*!< GPIO port bit set/reset low register,  Address offset: 0x18      */
+  __IO uint16_t BSRRH;    /*!< GPIO port bit set/reset high register, Address offset: 0x1A      */
+  __IO uint32_t LCKR;     /*!< GPIO port configuration lock register, Address offset: 0x1C      */
+  __IO uint32_t AFR[2];   /*!< GPIO alternate function registers,     Address offset: 0x20-0x24 */
+} GPIO_TypeDef;
+
+/** 
+  * @brief System configuration controller
+  */
+  
+typedef struct
+{
+  __IO uint32_t MEMRMP;       /*!< SYSCFG memory remap register,                      Address offset: 0x00      */
+  __IO uint32_t PMC;          /*!< SYSCFG peripheral mode configuration register,     Address offset: 0x04      */
+  __IO uint32_t EXTICR[4];    /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */
+  uint32_t      RESERVED[2];  /*!< Reserved, 0x18-0x1C                                                          */ 
+  __IO uint32_t CMPCR;        /*!< SYSCFG Compensation cell control register,         Address offset: 0x20      */
+} SYSCFG_TypeDef;
+
+/** 
+  * @brief Inter-integrated Circuit Interface
+  */
+
+typedef struct
+{
+  __IO uint16_t CR1;        /*!< I2C Control register 1,     Address offset: 0x00 */
+  uint16_t      RESERVED0;  /*!< Reserved, 0x02                                   */
+  __IO uint16_t CR2;        /*!< I2C Control register 2,     Address offset: 0x04 */
+  uint16_t      RESERVED1;  /*!< Reserved, 0x06                                   */
+  __IO uint16_t OAR1;       /*!< I2C Own address register 1, Address offset: 0x08 */
+  uint16_t      RESERVED2;  /*!< Reserved, 0x0A                                   */
+  __IO uint16_t OAR2;       /*!< I2C Own address register 2, Address offset: 0x0C */
+  uint16_t      RESERVED3;  /*!< Reserved, 0x0E                                   */
+  __IO uint16_t DR;         /*!< I2C Data register,          Address offset: 0x10 */
+  uint16_t      RESERVED4;  /*!< Reserved, 0x12                                   */
+  __IO uint16_t SR1;        /*!< I2C Status register 1,      Address offset: 0x14 */
+  uint16_t      RESERVED5;  /*!< Reserved, 0x16                                   */
+  __IO uint16_t SR2;        /*!< I2C Status register 2,      Address offset: 0x18 */
+  uint16_t      RESERVED6;  /*!< Reserved, 0x1A                                   */
+  __IO uint16_t CCR;        /*!< I2C Clock control register, Address offset: 0x1C */
+  uint16_t      RESERVED7;  /*!< Reserved, 0x1E                                   */
+  __IO uint16_t TRISE;      /*!< I2C TRISE register,         Address offset: 0x20 */
+  uint16_t      RESERVED8;  /*!< Reserved, 0x22                                   */
+  __IO uint16_t FLTR;       /*!< I2C FLTR register,          Address offset: 0x24 */
+  uint16_t      RESERVED9;  /*!< Reserved, 0x26                                   */
+} I2C_TypeDef;
+
+/** 
+  * @brief Independent WATCHDOG
+  */
+
+typedef struct
+{
+  __IO uint32_t KR;   /*!< IWDG Key register,       Address offset: 0x00 */
+  __IO uint32_t PR;   /*!< IWDG Prescaler register, Address offset: 0x04 */
+  __IO uint32_t RLR;  /*!< IWDG Reload register,    Address offset: 0x08 */
+  __IO uint32_t SR;   /*!< IWDG Status register,    Address offset: 0x0C */
+} IWDG_TypeDef;
+
+/** 
+  * @brief LCD-TFT Display Controller
+  */
+  
+typedef struct
+{
+  uint32_t      RESERVED0[2];  /*!< Reserved, 0x00-0x04 */
+  __IO uint32_t SSCR;          /*!< LTDC Synchronization Size Configuration Register,    Address offset: 0x08 */
+  __IO uint32_t BPCR;          /*!< LTDC Back Porch Configuration Register,              Address offset: 0x0C */
+  __IO uint32_t AWCR;          /*!< LTDC Active Width Configuration Register,            Address offset: 0x10 */
+  __IO uint32_t TWCR;          /*!< LTDC Total Width Configuration Register,             Address offset: 0x14 */
+  __IO uint32_t GCR;           /*!< LTDC Global Control Register,                        Address offset: 0x18 */
+  uint32_t      RESERVED1[2];  /*!< Reserved, 0x1C-0x20 */
+  __IO uint32_t SRCR;          /*!< LTDC Shadow Reload Configuration Register,           Address offset: 0x24 */
+  uint32_t      RESERVED2[1];  /*!< Reserved, 0x28 */
+  __IO uint32_t BCCR;          /*!< LTDC Background Color Configuration Register,        Address offset: 0x2C */
+  uint32_t      RESERVED3[1];  /*!< Reserved, 0x30 */
+  __IO uint32_t IER;           /*!< LTDC Interrupt Enable Register,                      Address offset: 0x34 */
+  __IO uint32_t ISR;           /*!< LTDC Interrupt Status Register,                      Address offset: 0x38 */
+  __IO uint32_t ICR;           /*!< LTDC Interrupt Clear Register,                       Address offset: 0x3C */
+  __IO uint32_t LIPCR;         /*!< LTDC Line Interrupt Position Configuration Register, Address offset: 0x40 */
+  __IO uint32_t CPSR;          /*!< LTDC Current Position Status Register,               Address offset: 0x44 */
+  __IO uint32_t CDSR;         /*!< LTDC Current Display Status Register,                       Address offset: 0x48 */
+} LTDC_TypeDef;  
+
+/** 
+  * @brief LCD-TFT Display layer x Controller
+  */
+  
+typedef struct
+{  
+  __IO uint32_t CR;            /*!< LTDC Layerx Control Register                                  Address offset: 0x84 */
+  __IO uint32_t WHPCR;         /*!< LTDC Layerx Window Horizontal Position Configuration Register Address offset: 0x88 */
+  __IO uint32_t WVPCR;         /*!< LTDC Layerx Window Vertical Position Configuration Register   Address offset: 0x8C */
+  __IO uint32_t CKCR;          /*!< LTDC Layerx Color Keying Configuration Register               Address offset: 0x90 */
+  __IO uint32_t PFCR;          /*!< LTDC Layerx Pixel Format Configuration Register               Address offset: 0x94 */
+  __IO uint32_t CACR;          /*!< LTDC Layerx Constant Alpha Configuration Register             Address offset: 0x98 */
+  __IO uint32_t DCCR;          /*!< LTDC Layerx Default Color Configuration Register              Address offset: 0x9C */
+  __IO uint32_t BFCR;          /*!< LTDC Layerx Blending Factors Configuration Register           Address offset: 0xA0 */
+  uint32_t      RESERVED0[2];  /*!< Reserved */
+  __IO uint32_t CFBAR;         /*!< LTDC Layerx Color Frame Buffer Address Register               Address offset: 0xAC */
+  __IO uint32_t CFBLR;         /*!< LTDC Layerx Color Frame Buffer Length Register                Address offset: 0xB0 */
+  __IO uint32_t CFBLNR;        /*!< LTDC Layerx ColorFrame Buffer Line Number Register            Address offset: 0xB4 */
+  uint32_t      RESERVED1[3];  /*!< Reserved */
+  __IO uint32_t CLUTWR;         /*!< LTDC Layerx CLUT Write Register                               Address offset: 0x144 */
+
+} LTDC_Layer_TypeDef;
+
+/** 
+  * @brief Power Control
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;   /*!< PWR power control register,        Address offset: 0x00 */
+  __IO uint32_t CSR;  /*!< PWR power control/status register, Address offset: 0x04 */
+} PWR_TypeDef;
+
+/** 
+  * @brief Reset and Clock Control
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;            /*!< RCC clock control register,                                  Address offset: 0x00 */
+  __IO uint32_t PLLCFGR;       /*!< RCC PLL configuration register,                              Address offset: 0x04 */
+  __IO uint32_t CFGR;          /*!< RCC clock configuration register,                            Address offset: 0x08 */
+  __IO uint32_t CIR;           /*!< RCC clock interrupt register,                                Address offset: 0x0C */
+  __IO uint32_t AHB1RSTR;      /*!< RCC AHB1 peripheral reset register,                          Address offset: 0x10 */
+  __IO uint32_t AHB2RSTR;      /*!< RCC AHB2 peripheral reset register,                          Address offset: 0x14 */
+  __IO uint32_t AHB3RSTR;      /*!< RCC AHB3 peripheral reset register,                          Address offset: 0x18 */
+  uint32_t      RESERVED0;     /*!< Reserved, 0x1C                                                                    */
+  __IO uint32_t APB1RSTR;      /*!< RCC APB1 peripheral reset register,                          Address offset: 0x20 */
+  __IO uint32_t APB2RSTR;      /*!< RCC APB2 peripheral reset register,                          Address offset: 0x24 */
+  uint32_t      RESERVED1[2];  /*!< Reserved, 0x28-0x2C                                                               */
+  __IO uint32_t AHB1ENR;       /*!< RCC AHB1 peripheral clock register,                          Address offset: 0x30 */
+  __IO uint32_t AHB2ENR;       /*!< RCC AHB2 peripheral clock register,                          Address offset: 0x34 */
+  __IO uint32_t AHB3ENR;       /*!< RCC AHB3 peripheral clock register,                          Address offset: 0x38 */
+  uint32_t      RESERVED2;     /*!< Reserved, 0x3C                                                                    */
+  __IO uint32_t APB1ENR;       /*!< RCC APB1 peripheral clock enable register,                   Address offset: 0x40 */
+  __IO uint32_t APB2ENR;       /*!< RCC APB2 peripheral clock enable register,                   Address offset: 0x44 */
+  uint32_t      RESERVED3[2];  /*!< Reserved, 0x48-0x4C                                                               */
+  __IO uint32_t AHB1LPENR;     /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */
+  __IO uint32_t AHB2LPENR;     /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */
+  __IO uint32_t AHB3LPENR;     /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */
+  uint32_t      RESERVED4;     /*!< Reserved, 0x5C                                                                    */
+  __IO uint32_t APB1LPENR;     /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */
+  __IO uint32_t APB2LPENR;     /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */
+  uint32_t      RESERVED5[2];  /*!< Reserved, 0x68-0x6C                                                               */
+  __IO uint32_t BDCR;          /*!< RCC Backup domain control register,                          Address offset: 0x70 */
+  __IO uint32_t CSR;           /*!< RCC clock control & status register,                         Address offset: 0x74 */
+  uint32_t      RESERVED6[2];  /*!< Reserved, 0x78-0x7C                                                               */
+  __IO uint32_t SSCGR;         /*!< RCC spread spectrum clock generation register,               Address offset: 0x80 */
+  __IO uint32_t PLLI2SCFGR;    /*!< RCC PLLI2S configuration register,                           Address offset: 0x84 */
+  __IO uint32_t PLLSAICFGR;    /*!< RCC PLLSAI configuration register,                           Address offset: 0x88 */
+  __IO uint32_t DCKCFGR;       /*!< RCC Dedicated Clocks configuration register,                 Address offset: 0x8C */
+
+} RCC_TypeDef;
+
+/** 
+  * @brief Real-Time Clock
+  */
+
+typedef struct
+{
+  __IO uint32_t TR;      /*!< RTC time register,                                        Address offset: 0x00 */
+  __IO uint32_t DR;      /*!< RTC date register,                                        Address offset: 0x04 */
+  __IO uint32_t CR;      /*!< RTC control register,                                     Address offset: 0x08 */
+  __IO uint32_t ISR;     /*!< RTC initialization and status register,                   Address offset: 0x0C */
+  __IO uint32_t PRER;    /*!< RTC prescaler register,                                   Address offset: 0x10 */
+  __IO uint32_t WUTR;    /*!< RTC wakeup timer register,                                Address offset: 0x14 */
+  __IO uint32_t CALIBR;  /*!< RTC calibration register,                                 Address offset: 0x18 */
+  __IO uint32_t ALRMAR;  /*!< RTC alarm A register,                                     Address offset: 0x1C */
+  __IO uint32_t ALRMBR;  /*!< RTC alarm B register,                                     Address offset: 0x20 */
+  __IO uint32_t WPR;     /*!< RTC write protection register,                            Address offset: 0x24 */
+  __IO uint32_t SSR;     /*!< RTC sub second register,                                  Address offset: 0x28 */
+  __IO uint32_t SHIFTR;  /*!< RTC shift control register,                               Address offset: 0x2C */
+  __IO uint32_t TSTR;    /*!< RTC time stamp time register,                             Address offset: 0x30 */
+  __IO uint32_t TSDR;    /*!< RTC time stamp date register,                             Address offset: 0x34 */
+  __IO uint32_t TSSSR;   /*!< RTC time-stamp sub second register,                       Address offset: 0x38 */
+  __IO uint32_t CALR;    /*!< RTC calibration register,                                 Address offset: 0x3C */
+  __IO uint32_t TAFCR;   /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */
+  __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register,                          Address offset: 0x44 */
+  __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register,                          Address offset: 0x48 */
+  uint32_t RESERVED7;    /*!< Reserved, 0x4C                                                                 */
+  __IO uint32_t BKP0R;   /*!< RTC backup register 1,                                    Address offset: 0x50 */
+  __IO uint32_t BKP1R;   /*!< RTC backup register 1,                                    Address offset: 0x54 */
+  __IO uint32_t BKP2R;   /*!< RTC backup register 2,                                    Address offset: 0x58 */
+  __IO uint32_t BKP3R;   /*!< RTC backup register 3,                                    Address offset: 0x5C */
+  __IO uint32_t BKP4R;   /*!< RTC backup register 4,                                    Address offset: 0x60 */
+  __IO uint32_t BKP5R;   /*!< RTC backup register 5,                                    Address offset: 0x64 */
+  __IO uint32_t BKP6R;   /*!< RTC backup register 6,                                    Address offset: 0x68 */
+  __IO uint32_t BKP7R;   /*!< RTC backup register 7,                                    Address offset: 0x6C */
+  __IO uint32_t BKP8R;   /*!< RTC backup register 8,                                    Address offset: 0x70 */
+  __IO uint32_t BKP9R;   /*!< RTC backup register 9,                                    Address offset: 0x74 */
+  __IO uint32_t BKP10R;  /*!< RTC backup register 10,                                   Address offset: 0x78 */
+  __IO uint32_t BKP11R;  /*!< RTC backup register 11,                                   Address offset: 0x7C */
+  __IO uint32_t BKP12R;  /*!< RTC backup register 12,                                   Address offset: 0x80 */
+  __IO uint32_t BKP13R;  /*!< RTC backup register 13,                                   Address offset: 0x84 */
+  __IO uint32_t BKP14R;  /*!< RTC backup register 14,                                   Address offset: 0x88 */
+  __IO uint32_t BKP15R;  /*!< RTC backup register 15,                                   Address offset: 0x8C */
+  __IO uint32_t BKP16R;  /*!< RTC backup register 16,                                   Address offset: 0x90 */
+  __IO uint32_t BKP17R;  /*!< RTC backup register 17,                                   Address offset: 0x94 */
+  __IO uint32_t BKP18R;  /*!< RTC backup register 18,                                   Address offset: 0x98 */
+  __IO uint32_t BKP19R;  /*!< RTC backup register 19,                                   Address offset: 0x9C */
+} RTC_TypeDef;
+
+
+/** 
+  * @brief Serial Audio Interface
+  */
+  
+typedef struct
+{
+  __IO uint32_t GCR;      /*!< SAI global configuration register,        Address offset: 0x00 */
+} SAI_TypeDef;
+
+typedef struct
+{
+  __IO uint32_t CR1;      /*!< SAI block x configuration register 1,     Address offset: 0x04 */
+  __IO uint32_t CR2;      /*!< SAI block x configuration register 2,     Address offset: 0x08 */
+  __IO uint32_t FRCR;     /*!< SAI block x frame configuration register, Address offset: 0x0C */
+  __IO uint32_t SLOTR;    /*!< SAI block x slot register,                Address offset: 0x10 */
+  __IO uint32_t IMR;      /*!< SAI block x interrupt mask register,      Address offset: 0x14 */
+  __IO uint32_t SR;       /*!< SAI block x status register,              Address offset: 0x18 */
+  __IO uint32_t CLRFR;    /*!< SAI block x clear flag register,          Address offset: 0x1C */
+  __IO uint32_t DR;       /*!< SAI block x data register,                Address offset: 0x20 */
+} SAI_Block_TypeDef;
+
+/** 
+  * @brief SD host Interface
+  */
+
+typedef struct
+{
+  __IO uint32_t POWER;          /*!< SDIO power control register,    Address offset: 0x00 */
+  __IO uint32_t CLKCR;          /*!< SDI clock control register,     Address offset: 0x04 */
+  __IO uint32_t ARG;            /*!< SDIO argument register,         Address offset: 0x08 */
+  __IO uint32_t CMD;            /*!< SDIO command register,          Address offset: 0x0C */
+  __I uint32_t  RESPCMD;        /*!< SDIO command response register, Address offset: 0x10 */
+  __I uint32_t  RESP1;          /*!< SDIO response 1 register,       Address offset: 0x14 */
+  __I uint32_t  RESP2;          /*!< SDIO response 2 register,       Address offset: 0x18 */
+  __I uint32_t  RESP3;          /*!< SDIO response 3 register,       Address offset: 0x1C */
+  __I uint32_t  RESP4;          /*!< SDIO response 4 register,       Address offset: 0x20 */
+  __IO uint32_t DTIMER;         /*!< SDIO data timer register,       Address offset: 0x24 */
+  __IO uint32_t DLEN;           /*!< SDIO data length register,      Address offset: 0x28 */
+  __IO uint32_t DCTRL;          /*!< SDIO data control register,     Address offset: 0x2C */
+  __I uint32_t  DCOUNT;         /*!< SDIO data counter register,     Address offset: 0x30 */
+  __I uint32_t  STA;            /*!< SDIO status register,           Address offset: 0x34 */
+  __IO uint32_t ICR;            /*!< SDIO interrupt clear register,  Address offset: 0x38 */
+  __IO uint32_t MASK;           /*!< SDIO mask register,             Address offset: 0x3C */
+  uint32_t      RESERVED0[2];   /*!< Reserved, 0x40-0x44                                  */
+  __I uint32_t  FIFOCNT;        /*!< SDIO FIFO counter register,     Address offset: 0x48 */
+  uint32_t      RESERVED1[13];  /*!< Reserved, 0x4C-0x7C                                  */
+  __IO uint32_t FIFO;           /*!< SDIO data FIFO register,        Address offset: 0x80 */
+} SDIO_TypeDef;
+
+/** 
+  * @brief Serial Peripheral Interface
+  */
+
+typedef struct
+{
+  __IO uint16_t CR1;        /*!< SPI control register 1 (not used in I2S mode),      Address offset: 0x00 */
+  uint16_t      RESERVED0;  /*!< Reserved, 0x02                                                           */
+  __IO uint16_t CR2;        /*!< SPI control register 2,                             Address offset: 0x04 */
+  uint16_t      RESERVED1;  /*!< Reserved, 0x06                                                           */
+  __IO uint16_t SR;         /*!< SPI status register,                                Address offset: 0x08 */
+  uint16_t      RESERVED2;  /*!< Reserved, 0x0A                                                           */
+  __IO uint16_t DR;         /*!< SPI data register,                                  Address offset: 0x0C */
+  uint16_t      RESERVED3;  /*!< Reserved, 0x0E                                                           */
+  __IO uint16_t CRCPR;      /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */
+  uint16_t      RESERVED4;  /*!< Reserved, 0x12                                                           */
+  __IO uint16_t RXCRCR;     /*!< SPI RX CRC register (not used in I2S mode),         Address offset: 0x14 */
+  uint16_t      RESERVED5;  /*!< Reserved, 0x16                                                           */
+  __IO uint16_t TXCRCR;     /*!< SPI TX CRC register (not used in I2S mode),         Address offset: 0x18 */
+  uint16_t      RESERVED6;  /*!< Reserved, 0x1A                                                           */
+  __IO uint16_t I2SCFGR;    /*!< SPI_I2S configuration register,                     Address offset: 0x1C */
+  uint16_t      RESERVED7;  /*!< Reserved, 0x1E                                                           */
+  __IO uint16_t I2SPR;      /*!< SPI_I2S prescaler register,                         Address offset: 0x20 */
+  uint16_t      RESERVED8;  /*!< Reserved, 0x22                                                           */
+} SPI_TypeDef;
+
+/** 
+  * @brief TIM
+  */
+
+typedef struct
+{
+  __IO uint16_t CR1;         /*!< TIM control register 1,              Address offset: 0x00 */
+  uint16_t      RESERVED0;   /*!< Reserved, 0x02                                            */
+  __IO uint16_t CR2;         /*!< TIM control register 2,              Address offset: 0x04 */
+  uint16_t      RESERVED1;   /*!< Reserved, 0x06                                            */
+  __IO uint16_t SMCR;        /*!< TIM slave mode control register,     Address offset: 0x08 */
+  uint16_t      RESERVED2;   /*!< Reserved, 0x0A                                            */
+  __IO uint16_t DIER;        /*!< TIM DMA/interrupt enable register,   Address offset: 0x0C */
+  uint16_t      RESERVED3;   /*!< Reserved, 0x0E                                            */
+  __IO uint16_t SR;          /*!< TIM status register,                 Address offset: 0x10 */
+  uint16_t      RESERVED4;   /*!< Reserved, 0x12                                            */
+  __IO uint16_t EGR;         /*!< TIM event generation register,       Address offset: 0x14 */
+  uint16_t      RESERVED5;   /*!< Reserved, 0x16                                            */
+  __IO uint16_t CCMR1;       /*!< TIM capture/compare mode register 1, Address offset: 0x18 */
+  uint16_t      RESERVED6;   /*!< Reserved, 0x1A                                            */
+  __IO uint16_t CCMR2;       /*!< TIM capture/compare mode register 2, Address offset: 0x1C */
+  uint16_t      RESERVED7;   /*!< Reserved, 0x1E                                            */
+  __IO uint16_t CCER;        /*!< TIM capture/compare enable register, Address offset: 0x20 */
+  uint16_t      RESERVED8;   /*!< Reserved, 0x22                                            */
+  __IO uint32_t CNT;         /*!< TIM counter register,                Address offset: 0x24 */
+  __IO uint16_t PSC;         /*!< TIM prescaler,                       Address offset: 0x28 */
+  uint16_t      RESERVED9;   /*!< Reserved, 0x2A                                            */
+  __IO uint32_t ARR;         /*!< TIM auto-reload register,            Address offset: 0x2C */
+  __IO uint16_t RCR;         /*!< TIM repetition counter register,     Address offset: 0x30 */
+  uint16_t      RESERVED10;  /*!< Reserved, 0x32                                            */
+  __IO uint32_t CCR1;        /*!< TIM capture/compare register 1,      Address offset: 0x34 */
+  __IO uint32_t CCR2;        /*!< TIM capture/compare register 2,      Address offset: 0x38 */
+  __IO uint32_t CCR3;        /*!< TIM capture/compare register 3,      Address offset: 0x3C */
+  __IO uint32_t CCR4;        /*!< TIM capture/compare register 4,      Address offset: 0x40 */
+  __IO uint16_t BDTR;        /*!< TIM break and dead-time register,    Address offset: 0x44 */
+  uint16_t      RESERVED11;  /*!< Reserved, 0x46                                            */
+  __IO uint16_t DCR;         /*!< TIM DMA control register,            Address offset: 0x48 */
+  uint16_t      RESERVED12;  /*!< Reserved, 0x4A                                            */
+  __IO uint16_t DMAR;        /*!< TIM DMA address for full transfer,   Address offset: 0x4C */
+  uint16_t      RESERVED13;  /*!< Reserved, 0x4E                                            */
+  __IO uint16_t OR;          /*!< TIM option register,                 Address offset: 0x50 */
+  uint16_t      RESERVED14;  /*!< Reserved, 0x52                                            */
+} TIM_TypeDef;
+
+/** 
+  * @brief Universal Synchronous Asynchronous Receiver Transmitter
+  */
+ 
+typedef struct
+{
+  __IO uint16_t SR;         /*!< USART Status register,                   Address offset: 0x00 */
+  uint16_t      RESERVED0;  /*!< Reserved, 0x02                                                */
+  __IO uint16_t DR;         /*!< USART Data register,                     Address offset: 0x04 */
+  uint16_t      RESERVED1;  /*!< Reserved, 0x06                                                */
+  __IO uint16_t BRR;        /*!< USART Baud rate register,                Address offset: 0x08 */
+  uint16_t      RESERVED2;  /*!< Reserved, 0x0A                                                */
+  __IO uint16_t CR1;        /*!< USART Control register 1,                Address offset: 0x0C */
+  uint16_t      RESERVED3;  /*!< Reserved, 0x0E                                                */
+  __IO uint16_t CR2;        /*!< USART Control register 2,                Address offset: 0x10 */
+  uint16_t      RESERVED4;  /*!< Reserved, 0x12                                                */
+  __IO uint16_t CR3;        /*!< USART Control register 3,                Address offset: 0x14 */
+  uint16_t      RESERVED5;  /*!< Reserved, 0x16                                                */
+  __IO uint16_t GTPR;       /*!< USART Guard time and prescaler register, Address offset: 0x18 */
+  uint16_t      RESERVED6;  /*!< Reserved, 0x1A                                                */
+} USART_TypeDef;
+
+/** 
+  * @brief Window WATCHDOG
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;   /*!< WWDG Control register,       Address offset: 0x00 */
+  __IO uint32_t CFR;  /*!< WWDG Configuration register, Address offset: 0x04 */
+  __IO uint32_t SR;   /*!< WWDG Status register,        Address offset: 0x08 */
+} WWDG_TypeDef;
+
+/** 
+  * @brief Crypto Processor
+  */
+
+typedef struct
+{
+  __IO uint32_t CR;         /*!< CRYP control register,                                    Address offset: 0x00 */
+  __IO uint32_t SR;         /*!< CRYP status register,                                     Address offset: 0x04 */
+  __IO uint32_t DR;         /*!< CRYP data input register,                                 Address offset: 0x08 */
+  __IO uint32_t DOUT;       /*!< CRYP data output register,                                Address offset: 0x0C */
+  __IO uint32_t DMACR;      /*!< CRYP DMA control register,                                Address offset: 0x10 */
+  __IO uint32_t IMSCR;      /*!< CRYP interrupt mask set/clear register,                   Address offset: 0x14 */
+  __IO uint32_t RISR;       /*!< CRYP raw interrupt status register,                       Address offset: 0x18 */
+  __IO uint32_t MISR;       /*!< CRYP masked interrupt status register,                    Address offset: 0x1C */
+  __IO uint32_t K0LR;       /*!< CRYP key left  register 0,                                Address offset: 0x20 */
+  __IO uint32_t K0RR;       /*!< CRYP key right register 0,                                Address offset: 0x24 */
+  __IO uint32_t K1LR;       /*!< CRYP key left  register 1,                                Address offset: 0x28 */
+  __IO uint32_t K1RR;       /*!< CRYP key right register 1,                                Address offset: 0x2C */
+  __IO uint32_t K2LR;       /*!< CRYP key left  register 2,                                Address offset: 0x30 */
+  __IO uint32_t K2RR;       /*!< CRYP key right register 2,                                Address offset: 0x34 */
+  __IO uint32_t K3LR;       /*!< CRYP key left  register 3,                                Address offset: 0x38 */
+  __IO uint32_t K3RR;       /*!< CRYP key right register 3,                                Address offset: 0x3C */
+  __IO uint32_t IV0LR;      /*!< CRYP initialization vector left-word  register 0,         Address offset: 0x40 */
+  __IO uint32_t IV0RR;      /*!< CRYP initialization vector right-word register 0,         Address offset: 0x44 */
+  __IO uint32_t IV1LR;      /*!< CRYP initialization vector left-word  register 1,         Address offset: 0x48 */
+  __IO uint32_t IV1RR;      /*!< CRYP initialization vector right-word register 1,         Address offset: 0x4C */
+  __IO uint32_t CSGCMCCM0R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 0,        Address offset: 0x50 */
+  __IO uint32_t CSGCMCCM1R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 1,        Address offset: 0x54 */
+  __IO uint32_t CSGCMCCM2R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 2,        Address offset: 0x58 */
+  __IO uint32_t CSGCMCCM3R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 3,        Address offset: 0x5C */
+  __IO uint32_t CSGCMCCM4R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 4,        Address offset: 0x60 */
+  __IO uint32_t CSGCMCCM5R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 5,        Address offset: 0x64 */
+  __IO uint32_t CSGCMCCM6R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 6,        Address offset: 0x68 */
+  __IO uint32_t CSGCMCCM7R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 7,        Address offset: 0x6C */
+  __IO uint32_t CSGCM0R;    /*!< CRYP GCM/GMAC context swap register 0,                    Address offset: 0x70 */
+  __IO uint32_t CSGCM1R;    /*!< CRYP GCM/GMAC context swap register 1,                    Address offset: 0x74 */
+  __IO uint32_t CSGCM2R;    /*!< CRYP GCM/GMAC context swap register 2,                    Address offset: 0x78 */
+  __IO uint32_t CSGCM3R;    /*!< CRYP GCM/GMAC context swap register 3,                    Address offset: 0x7C */
+  __IO uint32_t CSGCM4R;    /*!< CRYP GCM/GMAC context swap register 4,                    Address offset: 0x80 */
+  __IO uint32_t CSGCM5R;    /*!< CRYP GCM/GMAC context swap register 5,                    Address offset: 0x84 */
+  __IO uint32_t CSGCM6R;    /*!< CRYP GCM/GMAC context swap register 6,                    Address offset: 0x88 */
+  __IO uint32_t CSGCM7R;    /*!< CRYP GCM/GMAC context swap register 7,                    Address offset: 0x8C */
+} CRYP_TypeDef;
+
+/** 
+  * @brief HASH
+  */
+  
+typedef struct 
+{
+  __IO uint32_t CR;               /*!< HASH control register,          Address offset: 0x00        */
+  __IO uint32_t DIN;              /*!< HASH data input register,       Address offset: 0x04        */
+  __IO uint32_t STR;              /*!< HASH start register,            Address offset: 0x08        */
+  __IO uint32_t HR[5];            /*!< HASH digest registers,          Address offset: 0x0C-0x1C   */
+  __IO uint32_t IMR;              /*!< HASH interrupt enable register, Address offset: 0x20        */
+  __IO uint32_t SR;               /*!< HASH status register,           Address offset: 0x24        */
+       uint32_t RESERVED[52];     /*!< Reserved, 0x28-0xF4                                         */
+  __IO uint32_t CSR[54];          /*!< HASH context swap registers,    Address offset: 0x0F8-0x1CC */
+} HASH_TypeDef;
+
+/** 
+  * @brief HASH_DIGEST
+  */
+  
+typedef struct 
+{
+  __IO uint32_t HR[8];     /*!< HASH digest registers,          Address offset: 0x310-0x32C */ 
+} HASH_DIGEST_TypeDef;
+
+/** 
+  * @brief RNG
+  */
+  
+typedef struct 
+{
+  __IO uint32_t CR;  /*!< RNG control register, Address offset: 0x00 */
+  __IO uint32_t SR;  /*!< RNG status register,  Address offset: 0x04 */
+  __IO uint32_t DR;  /*!< RNG data register,    Address offset: 0x08 */
+} RNG_TypeDef;
+
+/**
+  * @}
+  */
+  
+/** @addtogroup Peripheral_memory_map
+  * @{
+  */
+#define FLASH_BASE            ((uint32_t)0x08000000) /*!< FLASH(up to 1 MB) base address in the alias region                         */
+#define CCMDATARAM_BASE       ((uint32_t)0x10000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the alias region  */
+#define SRAM1_BASE            ((uint32_t)0x20000000) /*!< SRAM1(112 KB) base address in the alias region                             */
+#define SRAM2_BASE            ((uint32_t)0x2001C000) /*!< SRAM2(16 KB) base address in the alias region                              */
+#define SRAM3_BASE            ((uint32_t)0x20020000) /*!< SRAM3(64 KB) base address in the alias region                              */
+#define PERIPH_BASE           ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region                                */
+#define BKPSRAM_BASE          ((uint32_t)0x40024000) /*!< Backup SRAM(4 KB) base address in the alias region                         */
+
+#if defined (STM32F40_41xxx)
+#define FSMC_R_BASE           ((uint32_t)0xA0000000) /*!< FSMC registers base address                                                */
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define FMC_R_BASE            ((uint32_t)0xA0000000) /*!< FMC registers base address                                                 */
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#define CCMDATARAM_BB_BASE    ((uint32_t)0x12000000) /*!< CCM(core coupled memory) data RAM(64 KB) base address in the bit-band region  */
+#define SRAM1_BB_BASE         ((uint32_t)0x22000000) /*!< SRAM1(112 KB) base address in the bit-band region                             */
+#define SRAM2_BB_BASE         ((uint32_t)0x2201C000) /*!< SRAM2(16 KB) base address in the bit-band region                              */
+#define SRAM3_BB_BASE         ((uint32_t)0x22400000) /*!< SRAM3(64 KB) base address in the bit-band region                              */
+#define PERIPH_BB_BASE        ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region                                */
+#define BKPSRAM_BB_BASE       ((uint32_t)0x42024000) /*!< Backup SRAM(4 KB) base address in the bit-band region                         */
+
+/* Legacy defines */
+#define SRAM_BASE             SRAM1_BASE
+#define SRAM_BB_BASE          SRAM1_BB_BASE
+
+
+/*!< Peripheral memory map */
+#define APB1PERIPH_BASE       PERIPH_BASE
+#define APB2PERIPH_BASE       (PERIPH_BASE + 0x00010000)
+#define AHB1PERIPH_BASE       (PERIPH_BASE + 0x00020000)
+#define AHB2PERIPH_BASE       (PERIPH_BASE + 0x10000000)
+
+/*!< APB1 peripherals */
+#define TIM2_BASE             (APB1PERIPH_BASE + 0x0000)
+#define TIM3_BASE             (APB1PERIPH_BASE + 0x0400)
+#define TIM4_BASE             (APB1PERIPH_BASE + 0x0800)
+#define TIM5_BASE             (APB1PERIPH_BASE + 0x0C00)
+#define TIM6_BASE             (APB1PERIPH_BASE + 0x1000)
+#define TIM7_BASE             (APB1PERIPH_BASE + 0x1400)
+#define TIM12_BASE            (APB1PERIPH_BASE + 0x1800)
+#define TIM13_BASE            (APB1PERIPH_BASE + 0x1C00)
+#define TIM14_BASE            (APB1PERIPH_BASE + 0x2000)
+#define RTC_BASE              (APB1PERIPH_BASE + 0x2800)
+#define WWDG_BASE             (APB1PERIPH_BASE + 0x2C00)
+#define IWDG_BASE             (APB1PERIPH_BASE + 0x3000)
+#define I2S2ext_BASE          (APB1PERIPH_BASE + 0x3400)
+#define SPI2_BASE             (APB1PERIPH_BASE + 0x3800)
+#define SPI3_BASE             (APB1PERIPH_BASE + 0x3C00)
+#define I2S3ext_BASE          (APB1PERIPH_BASE + 0x4000)
+#define USART2_BASE           (APB1PERIPH_BASE + 0x4400)
+#define USART3_BASE           (APB1PERIPH_BASE + 0x4800)
+#define UART4_BASE            (APB1PERIPH_BASE + 0x4C00)
+#define UART5_BASE            (APB1PERIPH_BASE + 0x5000)
+#define I2C1_BASE             (APB1PERIPH_BASE + 0x5400)
+#define I2C2_BASE             (APB1PERIPH_BASE + 0x5800)
+#define I2C3_BASE             (APB1PERIPH_BASE + 0x5C00)
+#define CAN1_BASE             (APB1PERIPH_BASE + 0x6400)
+#define CAN2_BASE             (APB1PERIPH_BASE + 0x6800)
+#define PWR_BASE              (APB1PERIPH_BASE + 0x7000)
+#define DAC_BASE              (APB1PERIPH_BASE + 0x7400)
+#define UART7_BASE            (APB1PERIPH_BASE + 0x7800)
+#define UART8_BASE            (APB1PERIPH_BASE + 0x7C00)
+
+/*!< APB2 peripherals */
+#define TIM1_BASE             (APB2PERIPH_BASE + 0x0000)
+#define TIM8_BASE             (APB2PERIPH_BASE + 0x0400)
+#define USART1_BASE           (APB2PERIPH_BASE + 0x1000)
+#define USART6_BASE           (APB2PERIPH_BASE + 0x1400)
+#define ADC1_BASE             (APB2PERIPH_BASE + 0x2000)
+#define ADC2_BASE             (APB2PERIPH_BASE + 0x2100)
+#define ADC3_BASE             (APB2PERIPH_BASE + 0x2200)
+#define ADC_BASE              (APB2PERIPH_BASE + 0x2300)
+#define SDIO_BASE             (APB2PERIPH_BASE + 0x2C00)
+#define SPI1_BASE             (APB2PERIPH_BASE + 0x3000)
+#define SPI4_BASE             (APB2PERIPH_BASE + 0x3400)
+#define SYSCFG_BASE           (APB2PERIPH_BASE + 0x3800)
+#define EXTI_BASE             (APB2PERIPH_BASE + 0x3C00)
+#define TIM9_BASE             (APB2PERIPH_BASE + 0x4000)
+#define TIM10_BASE            (APB2PERIPH_BASE + 0x4400)
+#define TIM11_BASE            (APB2PERIPH_BASE + 0x4800)
+#define SPI5_BASE             (APB2PERIPH_BASE + 0x5000)
+#define SPI6_BASE             (APB2PERIPH_BASE + 0x5400)
+#define SAI1_BASE             (APB2PERIPH_BASE + 0x5800)
+#define SAI1_Block_A_BASE     (SAI1_BASE + 0x004)
+#define SAI1_Block_B_BASE     (SAI1_BASE + 0x024)
+#define LTDC_BASE             (APB2PERIPH_BASE + 0x6800)
+#define LTDC_Layer1_BASE      (LTDC_BASE + 0x84)
+#define LTDC_Layer2_BASE      (LTDC_BASE + 0x104) 
+
+/*!< AHB1 peripherals */
+#define GPIOA_BASE            (AHB1PERIPH_BASE + 0x0000)
+#define GPIOB_BASE            (AHB1PERIPH_BASE + 0x0400)
+#define GPIOC_BASE            (AHB1PERIPH_BASE + 0x0800)
+#define GPIOD_BASE            (AHB1PERIPH_BASE + 0x0C00)
+#define GPIOE_BASE            (AHB1PERIPH_BASE + 0x1000)
+#define GPIOF_BASE            (AHB1PERIPH_BASE + 0x1400)
+#define GPIOG_BASE            (AHB1PERIPH_BASE + 0x1800)
+#define GPIOH_BASE            (AHB1PERIPH_BASE + 0x1C00)
+#define GPIOI_BASE            (AHB1PERIPH_BASE + 0x2000)
+#define GPIOJ_BASE            (AHB1PERIPH_BASE + 0x2400)
+#define GPIOK_BASE            (AHB1PERIPH_BASE + 0x2800)
+#define CRC_BASE              (AHB1PERIPH_BASE + 0x3000)
+#define RCC_BASE              (AHB1PERIPH_BASE + 0x3800)
+#define FLASH_R_BASE          (AHB1PERIPH_BASE + 0x3C00)
+#define DMA1_BASE             (AHB1PERIPH_BASE + 0x6000)
+#define DMA1_Stream0_BASE     (DMA1_BASE + 0x010)
+#define DMA1_Stream1_BASE     (DMA1_BASE + 0x028)
+#define DMA1_Stream2_BASE     (DMA1_BASE + 0x040)
+#define DMA1_Stream3_BASE     (DMA1_BASE + 0x058)
+#define DMA1_Stream4_BASE     (DMA1_BASE + 0x070)
+#define DMA1_Stream5_BASE     (DMA1_BASE + 0x088)
+#define DMA1_Stream6_BASE     (DMA1_BASE + 0x0A0)
+#define DMA1_Stream7_BASE     (DMA1_BASE + 0x0B8)
+#define DMA2_BASE             (AHB1PERIPH_BASE + 0x6400)
+#define DMA2_Stream0_BASE     (DMA2_BASE + 0x010)
+#define DMA2_Stream1_BASE     (DMA2_BASE + 0x028)
+#define DMA2_Stream2_BASE     (DMA2_BASE + 0x040)
+#define DMA2_Stream3_BASE     (DMA2_BASE + 0x058)
+#define DMA2_Stream4_BASE     (DMA2_BASE + 0x070)
+#define DMA2_Stream5_BASE     (DMA2_BASE + 0x088)
+#define DMA2_Stream6_BASE     (DMA2_BASE + 0x0A0)
+#define DMA2_Stream7_BASE     (DMA2_BASE + 0x0B8)
+#define ETH_BASE              (AHB1PERIPH_BASE + 0x8000)
+#define ETH_MAC_BASE          (ETH_BASE)
+#define ETH_MMC_BASE          (ETH_BASE + 0x0100)
+#define ETH_PTP_BASE          (ETH_BASE + 0x0700)
+#define ETH_DMA_BASE          (ETH_BASE + 0x1000)
+#define DMA2D_BASE            (AHB1PERIPH_BASE + 0xB000)
+
+/*!< AHB2 peripherals */
+#define DCMI_BASE             (AHB2PERIPH_BASE + 0x50000)
+#define CRYP_BASE             (AHB2PERIPH_BASE + 0x60000)
+#define HASH_BASE             (AHB2PERIPH_BASE + 0x60400)
+#define HASH_DIGEST_BASE      (AHB2PERIPH_BASE + 0x60710)
+#define RNG_BASE              (AHB2PERIPH_BASE + 0x60800)
+
+#if defined (STM32F40_41xxx)
+/*!< FSMC Bankx registers base address */
+#define FSMC_Bank1_R_BASE     (FSMC_R_BASE + 0x0000)
+#define FSMC_Bank1E_R_BASE    (FSMC_R_BASE + 0x0104)
+#define FSMC_Bank2_R_BASE     (FSMC_R_BASE + 0x0060)
+#define FSMC_Bank3_R_BASE     (FSMC_R_BASE + 0x0080)
+#define FSMC_Bank4_R_BASE     (FSMC_R_BASE + 0x00A0)
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+/*!< FMC Bankx registers base address */
+#define FMC_Bank1_R_BASE      (FMC_R_BASE + 0x0000)
+#define FMC_Bank1E_R_BASE     (FMC_R_BASE + 0x0104)
+#define FMC_Bank2_R_BASE      (FMC_R_BASE + 0x0060)
+#define FMC_Bank3_R_BASE      (FMC_R_BASE + 0x0080)
+#define FMC_Bank4_R_BASE      (FMC_R_BASE + 0x00A0)
+#define FMC_Bank5_6_R_BASE    (FMC_R_BASE + 0x0140)
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+/* Debug MCU registers base address */
+#define DBGMCU_BASE           ((uint32_t )0xE0042000)
+
+/**
+  * @}
+  */
+  
+/** @addtogroup Peripheral_declaration
+  * @{
+  */  
+#define TIM2                ((TIM_TypeDef *) TIM2_BASE)
+#define TIM3                ((TIM_TypeDef *) TIM3_BASE)
+#define TIM4                ((TIM_TypeDef *) TIM4_BASE)
+#define TIM5                ((TIM_TypeDef *) TIM5_BASE)
+#define TIM6                ((TIM_TypeDef *) TIM6_BASE)
+#define TIM7                ((TIM_TypeDef *) TIM7_BASE)
+#define TIM12               ((TIM_TypeDef *) TIM12_BASE)
+#define TIM13               ((TIM_TypeDef *) TIM13_BASE)
+#define TIM14               ((TIM_TypeDef *) TIM14_BASE)
+#define RTC                 ((RTC_TypeDef *) RTC_BASE)
+#define WWDG                ((WWDG_TypeDef *) WWDG_BASE)
+#define IWDG                ((IWDG_TypeDef *) IWDG_BASE)
+#define I2S2ext             ((SPI_TypeDef *) I2S2ext_BASE)
+#define SPI2                ((SPI_TypeDef *) SPI2_BASE)
+#define SPI3                ((SPI_TypeDef *) SPI3_BASE)
+#define I2S3ext             ((SPI_TypeDef *) I2S3ext_BASE)
+#define USART2              ((USART_TypeDef *) USART2_BASE)
+#define USART3              ((USART_TypeDef *) USART3_BASE)
+#define UART4               ((USART_TypeDef *) UART4_BASE)
+#define UART5               ((USART_TypeDef *) UART5_BASE)
+#define I2C1                ((I2C_TypeDef *) I2C1_BASE)
+#define I2C2                ((I2C_TypeDef *) I2C2_BASE)
+#define I2C3                ((I2C_TypeDef *) I2C3_BASE)
+#define CAN1                ((CAN_TypeDef *) CAN1_BASE)
+#define CAN2                ((CAN_TypeDef *) CAN2_BASE)
+#define PWR                 ((PWR_TypeDef *) PWR_BASE)
+#define DAC                 ((DAC_TypeDef *) DAC_BASE)
+#define UART7               ((USART_TypeDef *) UART7_BASE)
+#define UART8               ((USART_TypeDef *) UART8_BASE)
+#define TIM1                ((TIM_TypeDef *) TIM1_BASE)
+#define TIM8                ((TIM_TypeDef *) TIM8_BASE)
+#define USART1              ((USART_TypeDef *) USART1_BASE)
+#define USART6              ((USART_TypeDef *) USART6_BASE)
+#define ADC                 ((ADC_Common_TypeDef *) ADC_BASE)
+#define ADC1                ((ADC_TypeDef *) ADC1_BASE)
+#define ADC2                ((ADC_TypeDef *) ADC2_BASE)
+#define ADC3                ((ADC_TypeDef *) ADC3_BASE)
+#define SDIO                ((SDIO_TypeDef *) SDIO_BASE)
+#define SPI1                ((SPI_TypeDef *) SPI1_BASE) 
+#define SPI4                ((SPI_TypeDef *) SPI4_BASE)
+#define SYSCFG              ((SYSCFG_TypeDef *) SYSCFG_BASE)
+#define EXTI                ((EXTI_TypeDef *) EXTI_BASE)
+#define TIM9                ((TIM_TypeDef *) TIM9_BASE)
+#define TIM10               ((TIM_TypeDef *) TIM10_BASE)
+#define TIM11               ((TIM_TypeDef *) TIM11_BASE)
+#define SPI5                ((SPI_TypeDef *) SPI5_BASE)
+#define SPI6                ((SPI_TypeDef *) SPI6_BASE)
+#define SAI1                ((SAI_TypeDef *) SAI1_BASE)
+#define SAI1_Block_A        ((SAI_Block_TypeDef *)SAI1_Block_A_BASE)
+#define SAI1_Block_B        ((SAI_Block_TypeDef *)SAI1_Block_B_BASE)
+#define LTDC                ((LTDC_TypeDef *)LTDC_BASE)
+#define LTDC_Layer1         ((LTDC_Layer_TypeDef *)LTDC_Layer1_BASE)
+#define LTDC_Layer2         ((LTDC_Layer_TypeDef *)LTDC_Layer2_BASE)
+#define GPIOA               ((GPIO_TypeDef *) GPIOA_BASE)
+#define GPIOB               ((GPIO_TypeDef *) GPIOB_BASE)
+#define GPIOC               ((GPIO_TypeDef *) GPIOC_BASE)
+#define GPIOD               ((GPIO_TypeDef *) GPIOD_BASE)
+#define GPIOE               ((GPIO_TypeDef *) GPIOE_BASE)
+#define GPIOF               ((GPIO_TypeDef *) GPIOF_BASE)
+#define GPIOG               ((GPIO_TypeDef *) GPIOG_BASE)
+#define GPIOH               ((GPIO_TypeDef *) GPIOH_BASE)
+#define GPIOI               ((GPIO_TypeDef *) GPIOI_BASE)
+#define GPIOJ               ((GPIO_TypeDef *) GPIOJ_BASE)
+#define GPIOK               ((GPIO_TypeDef *) GPIOK_BASE)
+#define CRC                 ((CRC_TypeDef *) CRC_BASE)
+#define RCC                 ((RCC_TypeDef *) RCC_BASE)
+#define FLASH               ((FLASH_TypeDef *) FLASH_R_BASE)
+#define DMA1                ((DMA_TypeDef *) DMA1_BASE)
+#define DMA1_Stream0        ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE)
+#define DMA1_Stream1        ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE)
+#define DMA1_Stream2        ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE)
+#define DMA1_Stream3        ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE)
+#define DMA1_Stream4        ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE)
+#define DMA1_Stream5        ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE)
+#define DMA1_Stream6        ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE)
+#define DMA1_Stream7        ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE)
+#define DMA2                ((DMA_TypeDef *) DMA2_BASE)
+#define DMA2_Stream0        ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE)
+#define DMA2_Stream1        ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE)
+#define DMA2_Stream2        ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE)
+#define DMA2_Stream3        ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE)
+#define DMA2_Stream4        ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE)
+#define DMA2_Stream5        ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE)
+#define DMA2_Stream6        ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE)
+#define DMA2_Stream7        ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE)
+#define ETH                 ((ETH_TypeDef *) ETH_BASE)  
+#define DMA2D               ((DMA2D_TypeDef *)DMA2D_BASE)
+#define DCMI                ((DCMI_TypeDef *) DCMI_BASE)
+#define CRYP                ((CRYP_TypeDef *) CRYP_BASE)
+#define HASH                ((HASH_TypeDef *) HASH_BASE)
+#define HASH_DIGEST         ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE)
+#define RNG                 ((RNG_TypeDef *) RNG_BASE)
+
+#if defined (STM32F40_41xxx)
+#define FSMC_Bank1          ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE)
+#define FSMC_Bank1E         ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE)
+#define FSMC_Bank2          ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE)
+#define FSMC_Bank3          ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE)
+#define FSMC_Bank4          ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE)
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define FMC_Bank1           ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE)
+#define FMC_Bank1E          ((FMC_Bank1E_TypeDef *) FMC_Bank1E_R_BASE)
+#define FMC_Bank2           ((FMC_Bank2_TypeDef *) FMC_Bank2_R_BASE)
+#define FMC_Bank3           ((FMC_Bank3_TypeDef *) FMC_Bank3_R_BASE)
+#define FMC_Bank4           ((FMC_Bank4_TypeDef *) FMC_Bank4_R_BASE)
+#define FMC_Bank5_6         ((FMC_Bank5_6_TypeDef *) FMC_Bank5_6_R_BASE)
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#define DBGMCU              ((DBGMCU_TypeDef *) DBGMCU_BASE)
+
+/**
+  * @}
+  */
+
+/** @addtogroup Exported_constants
+  * @{
+  */
+  
+  /** @addtogroup Peripheral_Registers_Bits_Definition
+  * @{
+  */
+    
+/******************************************************************************/
+/*                         Peripheral Registers_Bits_Definition               */
+/******************************************************************************/
+
+/******************************************************************************/
+/*                                                                            */
+/*                        Analog to Digital Converter                         */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bit definition for ADC_SR register  ********************/
+#define  ADC_SR_AWD                          ((uint8_t)0x01)               /*!<Analog watchdog flag               */
+#define  ADC_SR_EOC                          ((uint8_t)0x02)               /*!<End of conversion                  */
+#define  ADC_SR_JEOC                         ((uint8_t)0x04)               /*!<Injected channel end of conversion */
+#define  ADC_SR_JSTRT                        ((uint8_t)0x08)               /*!<Injected channel Start flag        */
+#define  ADC_SR_STRT                         ((uint8_t)0x10)               /*!<Regular channel Start flag         */
+#define  ADC_SR_OVR                          ((uint8_t)0x20)               /*!<Overrun flag                       */
+
+/*******************  Bit definition for ADC_CR1 register  ********************/
+#define  ADC_CR1_AWDCH                       ((uint32_t)0x0000001F)        /*!<AWDCH[4:0] bits (Analog watchdog channel select bits) */
+#define  ADC_CR1_AWDCH_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_CR1_AWDCH_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_CR1_AWDCH_2                     ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_CR1_AWDCH_3                     ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_CR1_AWDCH_4                     ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  ADC_CR1_EOCIE                       ((uint32_t)0x00000020)        /*!<Interrupt enable for EOC                              */
+#define  ADC_CR1_AWDIE                       ((uint32_t)0x00000040)        /*!<AAnalog Watchdog interrupt enable                     */
+#define  ADC_CR1_JEOCIE                      ((uint32_t)0x00000080)        /*!<Interrupt enable for injected channels                */
+#define  ADC_CR1_SCAN                        ((uint32_t)0x00000100)        /*!<Scan mode                                             */
+#define  ADC_CR1_AWDSGL                      ((uint32_t)0x00000200)        /*!<Enable the watchdog on a single channel in scan mode  */
+#define  ADC_CR1_JAUTO                       ((uint32_t)0x00000400)        /*!<Automatic injected group conversion                   */
+#define  ADC_CR1_DISCEN                      ((uint32_t)0x00000800)        /*!<Discontinuous mode on regular channels                */
+#define  ADC_CR1_JDISCEN                     ((uint32_t)0x00001000)        /*!<Discontinuous mode on injected channels               */
+#define  ADC_CR1_DISCNUM                     ((uint32_t)0x0000E000)        /*!<DISCNUM[2:0] bits (Discontinuous mode channel count)  */
+#define  ADC_CR1_DISCNUM_0                   ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  ADC_CR1_DISCNUM_1                   ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  ADC_CR1_DISCNUM_2                   ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  ADC_CR1_JAWDEN                      ((uint32_t)0x00400000)        /*!<Analog watchdog enable on injected channels           */
+#define  ADC_CR1_AWDEN                       ((uint32_t)0x00800000)        /*!<Analog watchdog enable on regular channels            */
+#define  ADC_CR1_RES                         ((uint32_t)0x03000000)        /*!<RES[2:0] bits (Resolution)                            */
+#define  ADC_CR1_RES_0                       ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  ADC_CR1_RES_1                       ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  ADC_CR1_OVRIE                       ((uint32_t)0x04000000)         /*!<overrun interrupt enable                              */
+  
+/*******************  Bit definition for ADC_CR2 register  ********************/
+#define  ADC_CR2_ADON                        ((uint32_t)0x00000001)        /*!<A/D Converter ON / OFF             */
+#define  ADC_CR2_CONT                        ((uint32_t)0x00000002)        /*!<Continuous Conversion              */
+#define  ADC_CR2_DMA                         ((uint32_t)0x00000100)        /*!<Direct Memory access mode          */
+#define  ADC_CR2_DDS                         ((uint32_t)0x00000200)        /*!<DMA disable selection (Single ADC) */
+#define  ADC_CR2_EOCS                        ((uint32_t)0x00000400)        /*!<End of conversion selection        */
+#define  ADC_CR2_ALIGN                       ((uint32_t)0x00000800)        /*!<Data Alignment                     */
+#define  ADC_CR2_JEXTSEL                     ((uint32_t)0x000F0000)        /*!<JEXTSEL[3:0] bits (External event select for injected group) */
+#define  ADC_CR2_JEXTSEL_0                   ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  ADC_CR2_JEXTSEL_1                   ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  ADC_CR2_JEXTSEL_2                   ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  ADC_CR2_JEXTSEL_3                   ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  ADC_CR2_JEXTEN                      ((uint32_t)0x00300000)        /*!<JEXTEN[1:0] bits (External Trigger Conversion mode for injected channelsp) */
+#define  ADC_CR2_JEXTEN_0                    ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_CR2_JEXTEN_1                    ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  ADC_CR2_JSWSTART                    ((uint32_t)0x00400000)        /*!<Start Conversion of injected channels */
+#define  ADC_CR2_EXTSEL                      ((uint32_t)0x0F000000)        /*!<EXTSEL[3:0] bits (External Event Select for regular group) */
+#define  ADC_CR2_EXTSEL_0                    ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  ADC_CR2_EXTSEL_1                    ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  ADC_CR2_EXTSEL_2                    ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  ADC_CR2_EXTSEL_3                    ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  ADC_CR2_EXTEN                       ((uint32_t)0x30000000)        /*!<EXTEN[1:0] bits (External Trigger Conversion mode for regular channelsp) */
+#define  ADC_CR2_EXTEN_0                     ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  ADC_CR2_EXTEN_1                     ((uint32_t)0x20000000)        /*!<Bit 1 */
+#define  ADC_CR2_SWSTART                     ((uint32_t)0x40000000)        /*!<Start Conversion of regular channels */
+
+/******************  Bit definition for ADC_SMPR1 register  *******************/
+#define  ADC_SMPR1_SMP10                     ((uint32_t)0x00000007)        /*!<SMP10[2:0] bits (Channel 10 Sample time selection) */
+#define  ADC_SMPR1_SMP10_0                   ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP10_1                   ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP10_2                   ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP11                     ((uint32_t)0x00000038)        /*!<SMP11[2:0] bits (Channel 11 Sample time selection) */
+#define  ADC_SMPR1_SMP11_0                   ((uint32_t)0x00000008)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP11_1                   ((uint32_t)0x00000010)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP11_2                   ((uint32_t)0x00000020)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP12                     ((uint32_t)0x000001C0)        /*!<SMP12[2:0] bits (Channel 12 Sample time selection) */
+#define  ADC_SMPR1_SMP12_0                   ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP12_1                   ((uint32_t)0x00000080)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP12_2                   ((uint32_t)0x00000100)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP13                     ((uint32_t)0x00000E00)        /*!<SMP13[2:0] bits (Channel 13 Sample time selection) */
+#define  ADC_SMPR1_SMP13_0                   ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP13_1                   ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP13_2                   ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP14                     ((uint32_t)0x00007000)        /*!<SMP14[2:0] bits (Channel 14 Sample time selection) */
+#define  ADC_SMPR1_SMP14_0                   ((uint32_t)0x00001000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP14_1                   ((uint32_t)0x00002000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP14_2                   ((uint32_t)0x00004000)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP15                     ((uint32_t)0x00038000)        /*!<SMP15[2:0] bits (Channel 15 Sample time selection) */
+#define  ADC_SMPR1_SMP15_0                   ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP15_1                   ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP15_2                   ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP16                     ((uint32_t)0x001C0000)        /*!<SMP16[2:0] bits (Channel 16 Sample time selection) */
+#define  ADC_SMPR1_SMP16_0                   ((uint32_t)0x00040000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP16_1                   ((uint32_t)0x00080000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP16_2                   ((uint32_t)0x00100000)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP17                     ((uint32_t)0x00E00000)        /*!<SMP17[2:0] bits (Channel 17 Sample time selection) */
+#define  ADC_SMPR1_SMP17_0                   ((uint32_t)0x00200000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP17_1                   ((uint32_t)0x00400000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP17_2                   ((uint32_t)0x00800000)        /*!<Bit 2 */
+#define  ADC_SMPR1_SMP18                     ((uint32_t)0x07000000)        /*!<SMP18[2:0] bits (Channel 18 Sample time selection) */
+#define  ADC_SMPR1_SMP18_0                   ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  ADC_SMPR1_SMP18_1                   ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  ADC_SMPR1_SMP18_2                   ((uint32_t)0x04000000)        /*!<Bit 2 */
+
+/******************  Bit definition for ADC_SMPR2 register  *******************/
+#define  ADC_SMPR2_SMP0                      ((uint32_t)0x00000007)        /*!<SMP0[2:0] bits (Channel 0 Sample time selection) */
+#define  ADC_SMPR2_SMP0_0                    ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP0_1                    ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP0_2                    ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP1                      ((uint32_t)0x00000038)        /*!<SMP1[2:0] bits (Channel 1 Sample time selection) */
+#define  ADC_SMPR2_SMP1_0                    ((uint32_t)0x00000008)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP1_1                    ((uint32_t)0x00000010)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP1_2                    ((uint32_t)0x00000020)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP2                      ((uint32_t)0x000001C0)        /*!<SMP2[2:0] bits (Channel 2 Sample time selection) */
+#define  ADC_SMPR2_SMP2_0                    ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP2_1                    ((uint32_t)0x00000080)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP2_2                    ((uint32_t)0x00000100)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP3                      ((uint32_t)0x00000E00)        /*!<SMP3[2:0] bits (Channel 3 Sample time selection) */
+#define  ADC_SMPR2_SMP3_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP3_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP3_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP4                      ((uint32_t)0x00007000)        /*!<SMP4[2:0] bits (Channel 4 Sample time selection) */
+#define  ADC_SMPR2_SMP4_0                    ((uint32_t)0x00001000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP4_1                    ((uint32_t)0x00002000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP4_2                    ((uint32_t)0x00004000)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP5                      ((uint32_t)0x00038000)        /*!<SMP5[2:0] bits (Channel 5 Sample time selection) */
+#define  ADC_SMPR2_SMP5_0                    ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP5_1                    ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP5_2                    ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP6                      ((uint32_t)0x001C0000)        /*!<SMP6[2:0] bits (Channel 6 Sample time selection) */
+#define  ADC_SMPR2_SMP6_0                    ((uint32_t)0x00040000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP6_1                    ((uint32_t)0x00080000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP6_2                    ((uint32_t)0x00100000)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP7                      ((uint32_t)0x00E00000)        /*!<SMP7[2:0] bits (Channel 7 Sample time selection) */
+#define  ADC_SMPR2_SMP7_0                    ((uint32_t)0x00200000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP7_1                    ((uint32_t)0x00400000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP7_2                    ((uint32_t)0x00800000)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP8                      ((uint32_t)0x07000000)        /*!<SMP8[2:0] bits (Channel 8 Sample time selection) */
+#define  ADC_SMPR2_SMP8_0                    ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP8_1                    ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP8_2                    ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  ADC_SMPR2_SMP9                      ((uint32_t)0x38000000)        /*!<SMP9[2:0] bits (Channel 9 Sample time selection) */
+#define  ADC_SMPR2_SMP9_0                    ((uint32_t)0x08000000)        /*!<Bit 0 */
+#define  ADC_SMPR2_SMP9_1                    ((uint32_t)0x10000000)        /*!<Bit 1 */
+#define  ADC_SMPR2_SMP9_2                    ((uint32_t)0x20000000)        /*!<Bit 2 */
+
+/******************  Bit definition for ADC_JOFR1 register  *******************/
+#define  ADC_JOFR1_JOFFSET1                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 1 */
+
+/******************  Bit definition for ADC_JOFR2 register  *******************/
+#define  ADC_JOFR2_JOFFSET2                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 2 */
+
+/******************  Bit definition for ADC_JOFR3 register  *******************/
+#define  ADC_JOFR3_JOFFSET3                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 3 */
+
+/******************  Bit definition for ADC_JOFR4 register  *******************/
+#define  ADC_JOFR4_JOFFSET4                  ((uint16_t)0x0FFF)            /*!<Data offset for injected channel 4 */
+
+/*******************  Bit definition for ADC_HTR register  ********************/
+#define  ADC_HTR_HT                          ((uint16_t)0x0FFF)            /*!<Analog watchdog high threshold */
+
+/*******************  Bit definition for ADC_LTR register  ********************/
+#define  ADC_LTR_LT                          ((uint16_t)0x0FFF)            /*!<Analog watchdog low threshold */
+
+/*******************  Bit definition for ADC_SQR1 register  *******************/
+#define  ADC_SQR1_SQ13                       ((uint32_t)0x0000001F)        /*!<SQ13[4:0] bits (13th conversion in regular sequence) */
+#define  ADC_SQR1_SQ13_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ13_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ13_2                     ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ13_3                     ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ13_4                     ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  ADC_SQR1_SQ14                       ((uint32_t)0x000003E0)        /*!<SQ14[4:0] bits (14th conversion in regular sequence) */
+#define  ADC_SQR1_SQ14_0                     ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ14_1                     ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ14_2                     ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ14_3                     ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ14_4                     ((uint32_t)0x00000200)        /*!<Bit 4 */
+#define  ADC_SQR1_SQ15                       ((uint32_t)0x00007C00)        /*!<SQ15[4:0] bits (15th conversion in regular sequence) */
+#define  ADC_SQR1_SQ15_0                     ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ15_1                     ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ15_2                     ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ15_3                     ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ15_4                     ((uint32_t)0x00004000)        /*!<Bit 4 */
+#define  ADC_SQR1_SQ16                       ((uint32_t)0x000F8000)        /*!<SQ16[4:0] bits (16th conversion in regular sequence) */
+#define  ADC_SQR1_SQ16_0                     ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SQR1_SQ16_1                     ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SQR1_SQ16_2                     ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SQR1_SQ16_3                     ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_SQR1_SQ16_4                     ((uint32_t)0x00080000)        /*!<Bit 4 */
+#define  ADC_SQR1_L                          ((uint32_t)0x00F00000)        /*!<L[3:0] bits (Regular channel sequence length) */
+#define  ADC_SQR1_L_0                        ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_SQR1_L_1                        ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  ADC_SQR1_L_2                        ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  ADC_SQR1_L_3                        ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+/*******************  Bit definition for ADC_SQR2 register  *******************/
+#define  ADC_SQR2_SQ7                        ((uint32_t)0x0000001F)        /*!<SQ7[4:0] bits (7th conversion in regular sequence) */
+#define  ADC_SQR2_SQ7_0                      ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ7_1                      ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ7_2                      ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ7_3                      ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ7_4                      ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  ADC_SQR2_SQ8                        ((uint32_t)0x000003E0)        /*!<SQ8[4:0] bits (8th conversion in regular sequence) */
+#define  ADC_SQR2_SQ8_0                      ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ8_1                      ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ8_2                      ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ8_3                      ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ8_4                      ((uint32_t)0x00000200)        /*!<Bit 4 */
+#define  ADC_SQR2_SQ9                        ((uint32_t)0x00007C00)        /*!<SQ9[4:0] bits (9th conversion in regular sequence) */
+#define  ADC_SQR2_SQ9_0                      ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ9_1                      ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ9_2                      ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ9_3                      ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ9_4                      ((uint32_t)0x00004000)        /*!<Bit 4 */
+#define  ADC_SQR2_SQ10                       ((uint32_t)0x000F8000)        /*!<SQ10[4:0] bits (10th conversion in regular sequence) */
+#define  ADC_SQR2_SQ10_0                     ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ10_1                     ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ10_2                     ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ10_3                     ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ10_4                     ((uint32_t)0x00080000)        /*!<Bit 4 */
+#define  ADC_SQR2_SQ11                       ((uint32_t)0x01F00000)        /*!<SQ11[4:0] bits (11th conversion in regular sequence) */
+#define  ADC_SQR2_SQ11_0                     ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ11_1                     ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ11_2                     ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ11_3                     ((uint32_t)0x00800000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ11_4                     ((uint32_t)0x01000000)        /*!<Bit 4 */
+#define  ADC_SQR2_SQ12                       ((uint32_t)0x3E000000)        /*!<SQ12[4:0] bits (12th conversion in regular sequence) */
+#define  ADC_SQR2_SQ12_0                     ((uint32_t)0x02000000)        /*!<Bit 0 */
+#define  ADC_SQR2_SQ12_1                     ((uint32_t)0x04000000)        /*!<Bit 1 */
+#define  ADC_SQR2_SQ12_2                     ((uint32_t)0x08000000)        /*!<Bit 2 */
+#define  ADC_SQR2_SQ12_3                     ((uint32_t)0x10000000)        /*!<Bit 3 */
+#define  ADC_SQR2_SQ12_4                     ((uint32_t)0x20000000)        /*!<Bit 4 */
+
+/*******************  Bit definition for ADC_SQR3 register  *******************/
+#define  ADC_SQR3_SQ1                        ((uint32_t)0x0000001F)        /*!<SQ1[4:0] bits (1st conversion in regular sequence) */
+#define  ADC_SQR3_SQ1_0                      ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ1_1                      ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ1_2                      ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ1_3                      ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ1_4                      ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  ADC_SQR3_SQ2                        ((uint32_t)0x000003E0)        /*!<SQ2[4:0] bits (2nd conversion in regular sequence) */
+#define  ADC_SQR3_SQ2_0                      ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ2_1                      ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ2_2                      ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ2_3                      ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ2_4                      ((uint32_t)0x00000200)        /*!<Bit 4 */
+#define  ADC_SQR3_SQ3                        ((uint32_t)0x00007C00)        /*!<SQ3[4:0] bits (3rd conversion in regular sequence) */
+#define  ADC_SQR3_SQ3_0                      ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ3_1                      ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ3_2                      ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ3_3                      ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ3_4                      ((uint32_t)0x00004000)        /*!<Bit 4 */
+#define  ADC_SQR3_SQ4                        ((uint32_t)0x000F8000)        /*!<SQ4[4:0] bits (4th conversion in regular sequence) */
+#define  ADC_SQR3_SQ4_0                      ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ4_1                      ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ4_2                      ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ4_3                      ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ4_4                      ((uint32_t)0x00080000)        /*!<Bit 4 */
+#define  ADC_SQR3_SQ5                        ((uint32_t)0x01F00000)        /*!<SQ5[4:0] bits (5th conversion in regular sequence) */
+#define  ADC_SQR3_SQ5_0                      ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ5_1                      ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ5_2                      ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ5_3                      ((uint32_t)0x00800000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ5_4                      ((uint32_t)0x01000000)        /*!<Bit 4 */
+#define  ADC_SQR3_SQ6                        ((uint32_t)0x3E000000)        /*!<SQ6[4:0] bits (6th conversion in regular sequence) */
+#define  ADC_SQR3_SQ6_0                      ((uint32_t)0x02000000)        /*!<Bit 0 */
+#define  ADC_SQR3_SQ6_1                      ((uint32_t)0x04000000)        /*!<Bit 1 */
+#define  ADC_SQR3_SQ6_2                      ((uint32_t)0x08000000)        /*!<Bit 2 */
+#define  ADC_SQR3_SQ6_3                      ((uint32_t)0x10000000)        /*!<Bit 3 */
+#define  ADC_SQR3_SQ6_4                      ((uint32_t)0x20000000)        /*!<Bit 4 */
+
+/*******************  Bit definition for ADC_JSQR register  *******************/
+#define  ADC_JSQR_JSQ1                       ((uint32_t)0x0000001F)        /*!<JSQ1[4:0] bits (1st conversion in injected sequence) */  
+#define  ADC_JSQR_JSQ1_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ1_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ1_2                     ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ1_3                     ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ1_4                     ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  ADC_JSQR_JSQ2                       ((uint32_t)0x000003E0)        /*!<JSQ2[4:0] bits (2nd conversion in injected sequence) */
+#define  ADC_JSQR_JSQ2_0                     ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ2_1                     ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ2_2                     ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ2_3                     ((uint32_t)0x00000100)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ2_4                     ((uint32_t)0x00000200)        /*!<Bit 4 */
+#define  ADC_JSQR_JSQ3                       ((uint32_t)0x00007C00)        /*!<JSQ3[4:0] bits (3rd conversion in injected sequence) */
+#define  ADC_JSQR_JSQ3_0                     ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ3_1                     ((uint32_t)0x00000800)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ3_2                     ((uint32_t)0x00001000)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ3_3                     ((uint32_t)0x00002000)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ3_4                     ((uint32_t)0x00004000)        /*!<Bit 4 */
+#define  ADC_JSQR_JSQ4                       ((uint32_t)0x000F8000)        /*!<JSQ4[4:0] bits (4th conversion in injected sequence) */
+#define  ADC_JSQR_JSQ4_0                     ((uint32_t)0x00008000)        /*!<Bit 0 */
+#define  ADC_JSQR_JSQ4_1                     ((uint32_t)0x00010000)        /*!<Bit 1 */
+#define  ADC_JSQR_JSQ4_2                     ((uint32_t)0x00020000)        /*!<Bit 2 */
+#define  ADC_JSQR_JSQ4_3                     ((uint32_t)0x00040000)        /*!<Bit 3 */
+#define  ADC_JSQR_JSQ4_4                     ((uint32_t)0x00080000)        /*!<Bit 4 */
+#define  ADC_JSQR_JL                         ((uint32_t)0x00300000)        /*!<JL[1:0] bits (Injected Sequence length) */
+#define  ADC_JSQR_JL_0                       ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  ADC_JSQR_JL_1                       ((uint32_t)0x00200000)        /*!<Bit 1 */
+
+/*******************  Bit definition for ADC_JDR1 register  *******************/
+#define  ADC_JDR1_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/*******************  Bit definition for ADC_JDR2 register  *******************/
+#define  ADC_JDR2_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/*******************  Bit definition for ADC_JDR3 register  *******************/
+#define  ADC_JDR3_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/*******************  Bit definition for ADC_JDR4 register  *******************/
+#define  ADC_JDR4_JDATA                      ((uint16_t)0xFFFF)            /*!<Injected data */
+
+/********************  Bit definition for ADC_DR register  ********************/
+#define  ADC_DR_DATA                         ((uint32_t)0x0000FFFF)        /*!<Regular data */
+#define  ADC_DR_ADC2DATA                     ((uint32_t)0xFFFF0000)        /*!<ADC2 data */
+
+/*******************  Bit definition for ADC_CSR register  ********************/
+#define  ADC_CSR_AWD1                        ((uint32_t)0x00000001)        /*!<ADC1 Analog watchdog flag */
+#define  ADC_CSR_EOC1                        ((uint32_t)0x00000002)        /*!<ADC1 End of conversion */
+#define  ADC_CSR_JEOC1                       ((uint32_t)0x00000004)        /*!<ADC1 Injected channel end of conversion */
+#define  ADC_CSR_JSTRT1                      ((uint32_t)0x00000008)        /*!<ADC1 Injected channel Start flag */
+#define  ADC_CSR_STRT1                       ((uint32_t)0x00000010)        /*!<ADC1 Regular channel Start flag */
+#define  ADC_CSR_DOVR1                       ((uint32_t)0x00000020)        /*!<ADC1 DMA overrun  flag */
+#define  ADC_CSR_AWD2                        ((uint32_t)0x00000100)        /*!<ADC2 Analog watchdog flag */
+#define  ADC_CSR_EOC2                        ((uint32_t)0x00000200)        /*!<ADC2 End of conversion */
+#define  ADC_CSR_JEOC2                       ((uint32_t)0x00000400)        /*!<ADC2 Injected channel end of conversion */
+#define  ADC_CSR_JSTRT2                      ((uint32_t)0x00000800)        /*!<ADC2 Injected channel Start flag */
+#define  ADC_CSR_STRT2                       ((uint32_t)0x00001000)        /*!<ADC2 Regular channel Start flag */
+#define  ADC_CSR_DOVR2                       ((uint32_t)0x00002000)        /*!<ADC2 DMA overrun  flag */
+#define  ADC_CSR_AWD3                        ((uint32_t)0x00010000)        /*!<ADC3 Analog watchdog flag */
+#define  ADC_CSR_EOC3                        ((uint32_t)0x00020000)        /*!<ADC3 End of conversion */
+#define  ADC_CSR_JEOC3                       ((uint32_t)0x00040000)        /*!<ADC3 Injected channel end of conversion */
+#define  ADC_CSR_JSTRT3                      ((uint32_t)0x00080000)        /*!<ADC3 Injected channel Start flag */
+#define  ADC_CSR_STRT3                       ((uint32_t)0x00100000)        /*!<ADC3 Regular channel Start flag */
+#define  ADC_CSR_DOVR3                       ((uint32_t)0x00200000)        /*!<ADC3 DMA overrun  flag */
+
+/*******************  Bit definition for ADC_CCR register  ********************/
+#define  ADC_CCR_MULTI                       ((uint32_t)0x0000001F)        /*!<MULTI[4:0] bits (Multi-ADC mode selection) */  
+#define  ADC_CCR_MULTI_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  ADC_CCR_MULTI_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  ADC_CCR_MULTI_2                     ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  ADC_CCR_MULTI_3                     ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  ADC_CCR_MULTI_4                     ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  ADC_CCR_DELAY                       ((uint32_t)0x00000F00)        /*!<DELAY[3:0] bits (Delay between 2 sampling phases) */  
+#define  ADC_CCR_DELAY_0                     ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  ADC_CCR_DELAY_1                     ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  ADC_CCR_DELAY_2                     ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  ADC_CCR_DELAY_3                     ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  ADC_CCR_DDS                         ((uint32_t)0x00002000)        /*!<DMA disable selection (Multi-ADC mode) */
+#define  ADC_CCR_DMA                         ((uint32_t)0x0000C000)        /*!<DMA[1:0] bits (Direct Memory Access mode for multimode) */  
+#define  ADC_CCR_DMA_0                       ((uint32_t)0x00004000)        /*!<Bit 0 */
+#define  ADC_CCR_DMA_1                       ((uint32_t)0x00008000)        /*!<Bit 1 */
+#define  ADC_CCR_ADCPRE                      ((uint32_t)0x00030000)        /*!<ADCPRE[1:0] bits (ADC prescaler) */  
+#define  ADC_CCR_ADCPRE_0                    ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  ADC_CCR_ADCPRE_1                    ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  ADC_CCR_VBATE                       ((uint32_t)0x00400000)        /*!<VBAT Enable */
+#define  ADC_CCR_TSVREFE                     ((uint32_t)0x00800000)        /*!<Temperature Sensor and VREFINT Enable */
+
+/*******************  Bit definition for ADC_CDR register  ********************/
+#define  ADC_CDR_DATA1                      ((uint32_t)0x0000FFFF)         /*!<1st data of a pair of regular conversions */
+#define  ADC_CDR_DATA2                      ((uint32_t)0xFFFF0000)         /*!<2nd data of a pair of regular conversions */
+
+/******************************************************************************/
+/*                                                                            */
+/*                         Controller Area Network                            */
+/*                                                                            */
+/******************************************************************************/
+/*!<CAN control and status registers */
+/*******************  Bit definition for CAN_MCR register  ********************/
+#define  CAN_MCR_INRQ                        ((uint16_t)0x0001)            /*!<Initialization Request */
+#define  CAN_MCR_SLEEP                       ((uint16_t)0x0002)            /*!<Sleep Mode Request */
+#define  CAN_MCR_TXFP                        ((uint16_t)0x0004)            /*!<Transmit FIFO Priority */
+#define  CAN_MCR_RFLM                        ((uint16_t)0x0008)            /*!<Receive FIFO Locked Mode */
+#define  CAN_MCR_NART                        ((uint16_t)0x0010)            /*!<No Automatic Retransmission */
+#define  CAN_MCR_AWUM                        ((uint16_t)0x0020)            /*!<Automatic Wakeup Mode */
+#define  CAN_MCR_ABOM                        ((uint16_t)0x0040)            /*!<Automatic Bus-Off Management */
+#define  CAN_MCR_TTCM                        ((uint16_t)0x0080)            /*!<Time Triggered Communication Mode */
+#define  CAN_MCR_RESET                       ((uint16_t)0x8000)            /*!<bxCAN software master reset */
+
+/*******************  Bit definition for CAN_MSR register  ********************/
+#define  CAN_MSR_INAK                        ((uint16_t)0x0001)            /*!<Initialization Acknowledge */
+#define  CAN_MSR_SLAK                        ((uint16_t)0x0002)            /*!<Sleep Acknowledge */
+#define  CAN_MSR_ERRI                        ((uint16_t)0x0004)            /*!<Error Interrupt */
+#define  CAN_MSR_WKUI                        ((uint16_t)0x0008)            /*!<Wakeup Interrupt */
+#define  CAN_MSR_SLAKI                       ((uint16_t)0x0010)            /*!<Sleep Acknowledge Interrupt */
+#define  CAN_MSR_TXM                         ((uint16_t)0x0100)            /*!<Transmit Mode */
+#define  CAN_MSR_RXM                         ((uint16_t)0x0200)            /*!<Receive Mode */
+#define  CAN_MSR_SAMP                        ((uint16_t)0x0400)            /*!<Last Sample Point */
+#define  CAN_MSR_RX                          ((uint16_t)0x0800)            /*!<CAN Rx Signal */
+
+/*******************  Bit definition for CAN_TSR register  ********************/
+#define  CAN_TSR_RQCP0                       ((uint32_t)0x00000001)        /*!<Request Completed Mailbox0 */
+#define  CAN_TSR_TXOK0                       ((uint32_t)0x00000002)        /*!<Transmission OK of Mailbox0 */
+#define  CAN_TSR_ALST0                       ((uint32_t)0x00000004)        /*!<Arbitration Lost for Mailbox0 */
+#define  CAN_TSR_TERR0                       ((uint32_t)0x00000008)        /*!<Transmission Error of Mailbox0 */
+#define  CAN_TSR_ABRQ0                       ((uint32_t)0x00000080)        /*!<Abort Request for Mailbox0 */
+#define  CAN_TSR_RQCP1                       ((uint32_t)0x00000100)        /*!<Request Completed Mailbox1 */
+#define  CAN_TSR_TXOK1                       ((uint32_t)0x00000200)        /*!<Transmission OK of Mailbox1 */
+#define  CAN_TSR_ALST1                       ((uint32_t)0x00000400)        /*!<Arbitration Lost for Mailbox1 */
+#define  CAN_TSR_TERR1                       ((uint32_t)0x00000800)        /*!<Transmission Error of Mailbox1 */
+#define  CAN_TSR_ABRQ1                       ((uint32_t)0x00008000)        /*!<Abort Request for Mailbox 1 */
+#define  CAN_TSR_RQCP2                       ((uint32_t)0x00010000)        /*!<Request Completed Mailbox2 */
+#define  CAN_TSR_TXOK2                       ((uint32_t)0x00020000)        /*!<Transmission OK of Mailbox 2 */
+#define  CAN_TSR_ALST2                       ((uint32_t)0x00040000)        /*!<Arbitration Lost for mailbox 2 */
+#define  CAN_TSR_TERR2                       ((uint32_t)0x00080000)        /*!<Transmission Error of Mailbox 2 */
+#define  CAN_TSR_ABRQ2                       ((uint32_t)0x00800000)        /*!<Abort Request for Mailbox 2 */
+#define  CAN_TSR_CODE                        ((uint32_t)0x03000000)        /*!<Mailbox Code */
+
+#define  CAN_TSR_TME                         ((uint32_t)0x1C000000)        /*!<TME[2:0] bits */
+#define  CAN_TSR_TME0                        ((uint32_t)0x04000000)        /*!<Transmit Mailbox 0 Empty */
+#define  CAN_TSR_TME1                        ((uint32_t)0x08000000)        /*!<Transmit Mailbox 1 Empty */
+#define  CAN_TSR_TME2                        ((uint32_t)0x10000000)        /*!<Transmit Mailbox 2 Empty */
+
+#define  CAN_TSR_LOW                         ((uint32_t)0xE0000000)        /*!<LOW[2:0] bits */
+#define  CAN_TSR_LOW0                        ((uint32_t)0x20000000)        /*!<Lowest Priority Flag for Mailbox 0 */
+#define  CAN_TSR_LOW1                        ((uint32_t)0x40000000)        /*!<Lowest Priority Flag for Mailbox 1 */
+#define  CAN_TSR_LOW2                        ((uint32_t)0x80000000)        /*!<Lowest Priority Flag for Mailbox 2 */
+
+/*******************  Bit definition for CAN_RF0R register  *******************/
+#define  CAN_RF0R_FMP0                       ((uint8_t)0x03)               /*!<FIFO 0 Message Pending */
+#define  CAN_RF0R_FULL0                      ((uint8_t)0x08)               /*!<FIFO 0 Full */
+#define  CAN_RF0R_FOVR0                      ((uint8_t)0x10)               /*!<FIFO 0 Overrun */
+#define  CAN_RF0R_RFOM0                      ((uint8_t)0x20)               /*!<Release FIFO 0 Output Mailbox */
+
+/*******************  Bit definition for CAN_RF1R register  *******************/
+#define  CAN_RF1R_FMP1                       ((uint8_t)0x03)               /*!<FIFO 1 Message Pending */
+#define  CAN_RF1R_FULL1                      ((uint8_t)0x08)               /*!<FIFO 1 Full */
+#define  CAN_RF1R_FOVR1                      ((uint8_t)0x10)               /*!<FIFO 1 Overrun */
+#define  CAN_RF1R_RFOM1                      ((uint8_t)0x20)               /*!<Release FIFO 1 Output Mailbox */
+
+/********************  Bit definition for CAN_IER register  *******************/
+#define  CAN_IER_TMEIE                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Empty Interrupt Enable */
+#define  CAN_IER_FMPIE0                      ((uint32_t)0x00000002)        /*!<FIFO Message Pending Interrupt Enable */
+#define  CAN_IER_FFIE0                       ((uint32_t)0x00000004)        /*!<FIFO Full Interrupt Enable */
+#define  CAN_IER_FOVIE0                      ((uint32_t)0x00000008)        /*!<FIFO Overrun Interrupt Enable */
+#define  CAN_IER_FMPIE1                      ((uint32_t)0x00000010)        /*!<FIFO Message Pending Interrupt Enable */
+#define  CAN_IER_FFIE1                       ((uint32_t)0x00000020)        /*!<FIFO Full Interrupt Enable */
+#define  CAN_IER_FOVIE1                      ((uint32_t)0x00000040)        /*!<FIFO Overrun Interrupt Enable */
+#define  CAN_IER_EWGIE                       ((uint32_t)0x00000100)        /*!<Error Warning Interrupt Enable */
+#define  CAN_IER_EPVIE                       ((uint32_t)0x00000200)        /*!<Error Passive Interrupt Enable */
+#define  CAN_IER_BOFIE                       ((uint32_t)0x00000400)        /*!<Bus-Off Interrupt Enable */
+#define  CAN_IER_LECIE                       ((uint32_t)0x00000800)        /*!<Last Error Code Interrupt Enable */
+#define  CAN_IER_ERRIE                       ((uint32_t)0x00008000)        /*!<Error Interrupt Enable */
+#define  CAN_IER_WKUIE                       ((uint32_t)0x00010000)        /*!<Wakeup Interrupt Enable */
+#define  CAN_IER_SLKIE                       ((uint32_t)0x00020000)        /*!<Sleep Interrupt Enable */
+
+/********************  Bit definition for CAN_ESR register  *******************/
+#define  CAN_ESR_EWGF                        ((uint32_t)0x00000001)        /*!<Error Warning Flag */
+#define  CAN_ESR_EPVF                        ((uint32_t)0x00000002)        /*!<Error Passive Flag */
+#define  CAN_ESR_BOFF                        ((uint32_t)0x00000004)        /*!<Bus-Off Flag */
+
+#define  CAN_ESR_LEC                         ((uint32_t)0x00000070)        /*!<LEC[2:0] bits (Last Error Code) */
+#define  CAN_ESR_LEC_0                       ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  CAN_ESR_LEC_1                       ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  CAN_ESR_LEC_2                       ((uint32_t)0x00000040)        /*!<Bit 2 */
+
+#define  CAN_ESR_TEC                         ((uint32_t)0x00FF0000)        /*!<Least significant byte of the 9-bit Transmit Error Counter */
+#define  CAN_ESR_REC                         ((uint32_t)0xFF000000)        /*!<Receive Error Counter */
+
+/*******************  Bit definition for CAN_BTR register  ********************/
+#define  CAN_BTR_BRP                         ((uint32_t)0x000003FF)        /*!<Baud Rate Prescaler */
+#define  CAN_BTR_TS1                         ((uint32_t)0x000F0000)        /*!<Time Segment 1 */
+#define  CAN_BTR_TS2                         ((uint32_t)0x00700000)        /*!<Time Segment 2 */
+#define  CAN_BTR_SJW                         ((uint32_t)0x03000000)        /*!<Resynchronization Jump Width */
+#define  CAN_BTR_LBKM                        ((uint32_t)0x40000000)        /*!<Loop Back Mode (Debug) */
+#define  CAN_BTR_SILM                        ((uint32_t)0x80000000)        /*!<Silent Mode */
+
+/*!<Mailbox registers */
+/******************  Bit definition for CAN_TI0R register  ********************/
+#define  CAN_TI0R_TXRQ                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Request */
+#define  CAN_TI0R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_TI0R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_TI0R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended Identifier */
+#define  CAN_TI0R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/******************  Bit definition for CAN_TDT0R register  *******************/
+#define  CAN_TDT0R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_TDT0R_TGT                       ((uint32_t)0x00000100)        /*!<Transmit Global Time */
+#define  CAN_TDT0R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/******************  Bit definition for CAN_TDL0R register  *******************/
+#define  CAN_TDL0R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_TDL0R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_TDL0R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_TDL0R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/******************  Bit definition for CAN_TDH0R register  *******************/
+#define  CAN_TDH0R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_TDH0R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_TDH0R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_TDH0R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_TI1R register  *******************/
+#define  CAN_TI1R_TXRQ                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Request */
+#define  CAN_TI1R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_TI1R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_TI1R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended Identifier */
+#define  CAN_TI1R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_TDT1R register  ******************/
+#define  CAN_TDT1R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_TDT1R_TGT                       ((uint32_t)0x00000100)        /*!<Transmit Global Time */
+#define  CAN_TDT1R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_TDL1R register  ******************/
+#define  CAN_TDL1R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_TDL1R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_TDL1R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_TDL1R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_TDH1R register  ******************/
+#define  CAN_TDH1R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_TDH1R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_TDH1R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_TDH1R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_TI2R register  *******************/
+#define  CAN_TI2R_TXRQ                       ((uint32_t)0x00000001)        /*!<Transmit Mailbox Request */
+#define  CAN_TI2R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_TI2R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_TI2R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended identifier */
+#define  CAN_TI2R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_TDT2R register  ******************/  
+#define  CAN_TDT2R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_TDT2R_TGT                       ((uint32_t)0x00000100)        /*!<Transmit Global Time */
+#define  CAN_TDT2R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_TDL2R register  ******************/
+#define  CAN_TDL2R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_TDL2R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_TDL2R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_TDL2R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_TDH2R register  ******************/
+#define  CAN_TDH2R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_TDH2R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_TDH2R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_TDH2R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_RI0R register  *******************/
+#define  CAN_RI0R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_RI0R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_RI0R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended Identifier */
+#define  CAN_RI0R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_RDT0R register  ******************/
+#define  CAN_RDT0R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_RDT0R_FMI                       ((uint32_t)0x0000FF00)        /*!<Filter Match Index */
+#define  CAN_RDT0R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_RDL0R register  ******************/
+#define  CAN_RDL0R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_RDL0R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_RDL0R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_RDL0R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_RDH0R register  ******************/
+#define  CAN_RDH0R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_RDH0R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_RDH0R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_RDH0R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*******************  Bit definition for CAN_RI1R register  *******************/
+#define  CAN_RI1R_RTR                        ((uint32_t)0x00000002)        /*!<Remote Transmission Request */
+#define  CAN_RI1R_IDE                        ((uint32_t)0x00000004)        /*!<Identifier Extension */
+#define  CAN_RI1R_EXID                       ((uint32_t)0x001FFFF8)        /*!<Extended identifier */
+#define  CAN_RI1R_STID                       ((uint32_t)0xFFE00000)        /*!<Standard Identifier or Extended Identifier */
+
+/*******************  Bit definition for CAN_RDT1R register  ******************/
+#define  CAN_RDT1R_DLC                       ((uint32_t)0x0000000F)        /*!<Data Length Code */
+#define  CAN_RDT1R_FMI                       ((uint32_t)0x0000FF00)        /*!<Filter Match Index */
+#define  CAN_RDT1R_TIME                      ((uint32_t)0xFFFF0000)        /*!<Message Time Stamp */
+
+/*******************  Bit definition for CAN_RDL1R register  ******************/
+#define  CAN_RDL1R_DATA0                     ((uint32_t)0x000000FF)        /*!<Data byte 0 */
+#define  CAN_RDL1R_DATA1                     ((uint32_t)0x0000FF00)        /*!<Data byte 1 */
+#define  CAN_RDL1R_DATA2                     ((uint32_t)0x00FF0000)        /*!<Data byte 2 */
+#define  CAN_RDL1R_DATA3                     ((uint32_t)0xFF000000)        /*!<Data byte 3 */
+
+/*******************  Bit definition for CAN_RDH1R register  ******************/
+#define  CAN_RDH1R_DATA4                     ((uint32_t)0x000000FF)        /*!<Data byte 4 */
+#define  CAN_RDH1R_DATA5                     ((uint32_t)0x0000FF00)        /*!<Data byte 5 */
+#define  CAN_RDH1R_DATA6                     ((uint32_t)0x00FF0000)        /*!<Data byte 6 */
+#define  CAN_RDH1R_DATA7                     ((uint32_t)0xFF000000)        /*!<Data byte 7 */
+
+/*!<CAN filter registers */
+/*******************  Bit definition for CAN_FMR register  ********************/
+#define  CAN_FMR_FINIT                       ((uint8_t)0x01)               /*!<Filter Init Mode */
+
+/*******************  Bit definition for CAN_FM1R register  *******************/
+#define  CAN_FM1R_FBM                        ((uint16_t)0x3FFF)            /*!<Filter Mode */
+#define  CAN_FM1R_FBM0                       ((uint16_t)0x0001)            /*!<Filter Init Mode bit 0 */
+#define  CAN_FM1R_FBM1                       ((uint16_t)0x0002)            /*!<Filter Init Mode bit 1 */
+#define  CAN_FM1R_FBM2                       ((uint16_t)0x0004)            /*!<Filter Init Mode bit 2 */
+#define  CAN_FM1R_FBM3                       ((uint16_t)0x0008)            /*!<Filter Init Mode bit 3 */
+#define  CAN_FM1R_FBM4                       ((uint16_t)0x0010)            /*!<Filter Init Mode bit 4 */
+#define  CAN_FM1R_FBM5                       ((uint16_t)0x0020)            /*!<Filter Init Mode bit 5 */
+#define  CAN_FM1R_FBM6                       ((uint16_t)0x0040)            /*!<Filter Init Mode bit 6 */
+#define  CAN_FM1R_FBM7                       ((uint16_t)0x0080)            /*!<Filter Init Mode bit 7 */
+#define  CAN_FM1R_FBM8                       ((uint16_t)0x0100)            /*!<Filter Init Mode bit 8 */
+#define  CAN_FM1R_FBM9                       ((uint16_t)0x0200)            /*!<Filter Init Mode bit 9 */
+#define  CAN_FM1R_FBM10                      ((uint16_t)0x0400)            /*!<Filter Init Mode bit 10 */
+#define  CAN_FM1R_FBM11                      ((uint16_t)0x0800)            /*!<Filter Init Mode bit 11 */
+#define  CAN_FM1R_FBM12                      ((uint16_t)0x1000)            /*!<Filter Init Mode bit 12 */
+#define  CAN_FM1R_FBM13                      ((uint16_t)0x2000)            /*!<Filter Init Mode bit 13 */
+
+/*******************  Bit definition for CAN_FS1R register  *******************/
+#define  CAN_FS1R_FSC                        ((uint16_t)0x3FFF)            /*!<Filter Scale Configuration */
+#define  CAN_FS1R_FSC0                       ((uint16_t)0x0001)            /*!<Filter Scale Configuration bit 0 */
+#define  CAN_FS1R_FSC1                       ((uint16_t)0x0002)            /*!<Filter Scale Configuration bit 1 */
+#define  CAN_FS1R_FSC2                       ((uint16_t)0x0004)            /*!<Filter Scale Configuration bit 2 */
+#define  CAN_FS1R_FSC3                       ((uint16_t)0x0008)            /*!<Filter Scale Configuration bit 3 */
+#define  CAN_FS1R_FSC4                       ((uint16_t)0x0010)            /*!<Filter Scale Configuration bit 4 */
+#define  CAN_FS1R_FSC5                       ((uint16_t)0x0020)            /*!<Filter Scale Configuration bit 5 */
+#define  CAN_FS1R_FSC6                       ((uint16_t)0x0040)            /*!<Filter Scale Configuration bit 6 */
+#define  CAN_FS1R_FSC7                       ((uint16_t)0x0080)            /*!<Filter Scale Configuration bit 7 */
+#define  CAN_FS1R_FSC8                       ((uint16_t)0x0100)            /*!<Filter Scale Configuration bit 8 */
+#define  CAN_FS1R_FSC9                       ((uint16_t)0x0200)            /*!<Filter Scale Configuration bit 9 */
+#define  CAN_FS1R_FSC10                      ((uint16_t)0x0400)            /*!<Filter Scale Configuration bit 10 */
+#define  CAN_FS1R_FSC11                      ((uint16_t)0x0800)            /*!<Filter Scale Configuration bit 11 */
+#define  CAN_FS1R_FSC12                      ((uint16_t)0x1000)            /*!<Filter Scale Configuration bit 12 */
+#define  CAN_FS1R_FSC13                      ((uint16_t)0x2000)            /*!<Filter Scale Configuration bit 13 */
+
+/******************  Bit definition for CAN_FFA1R register  *******************/
+#define  CAN_FFA1R_FFA                       ((uint16_t)0x3FFF)            /*!<Filter FIFO Assignment */
+#define  CAN_FFA1R_FFA0                      ((uint16_t)0x0001)            /*!<Filter FIFO Assignment for Filter 0 */
+#define  CAN_FFA1R_FFA1                      ((uint16_t)0x0002)            /*!<Filter FIFO Assignment for Filter 1 */
+#define  CAN_FFA1R_FFA2                      ((uint16_t)0x0004)            /*!<Filter FIFO Assignment for Filter 2 */
+#define  CAN_FFA1R_FFA3                      ((uint16_t)0x0008)            /*!<Filter FIFO Assignment for Filter 3 */
+#define  CAN_FFA1R_FFA4                      ((uint16_t)0x0010)            /*!<Filter FIFO Assignment for Filter 4 */
+#define  CAN_FFA1R_FFA5                      ((uint16_t)0x0020)            /*!<Filter FIFO Assignment for Filter 5 */
+#define  CAN_FFA1R_FFA6                      ((uint16_t)0x0040)            /*!<Filter FIFO Assignment for Filter 6 */
+#define  CAN_FFA1R_FFA7                      ((uint16_t)0x0080)            /*!<Filter FIFO Assignment for Filter 7 */
+#define  CAN_FFA1R_FFA8                      ((uint16_t)0x0100)            /*!<Filter FIFO Assignment for Filter 8 */
+#define  CAN_FFA1R_FFA9                      ((uint16_t)0x0200)            /*!<Filter FIFO Assignment for Filter 9 */
+#define  CAN_FFA1R_FFA10                     ((uint16_t)0x0400)            /*!<Filter FIFO Assignment for Filter 10 */
+#define  CAN_FFA1R_FFA11                     ((uint16_t)0x0800)            /*!<Filter FIFO Assignment for Filter 11 */
+#define  CAN_FFA1R_FFA12                     ((uint16_t)0x1000)            /*!<Filter FIFO Assignment for Filter 12 */
+#define  CAN_FFA1R_FFA13                     ((uint16_t)0x2000)            /*!<Filter FIFO Assignment for Filter 13 */
+
+/*******************  Bit definition for CAN_FA1R register  *******************/
+#define  CAN_FA1R_FACT                       ((uint16_t)0x3FFF)            /*!<Filter Active */
+#define  CAN_FA1R_FACT0                      ((uint16_t)0x0001)            /*!<Filter 0 Active */
+#define  CAN_FA1R_FACT1                      ((uint16_t)0x0002)            /*!<Filter 1 Active */
+#define  CAN_FA1R_FACT2                      ((uint16_t)0x0004)            /*!<Filter 2 Active */
+#define  CAN_FA1R_FACT3                      ((uint16_t)0x0008)            /*!<Filter 3 Active */
+#define  CAN_FA1R_FACT4                      ((uint16_t)0x0010)            /*!<Filter 4 Active */
+#define  CAN_FA1R_FACT5                      ((uint16_t)0x0020)            /*!<Filter 5 Active */
+#define  CAN_FA1R_FACT6                      ((uint16_t)0x0040)            /*!<Filter 6 Active */
+#define  CAN_FA1R_FACT7                      ((uint16_t)0x0080)            /*!<Filter 7 Active */
+#define  CAN_FA1R_FACT8                      ((uint16_t)0x0100)            /*!<Filter 8 Active */
+#define  CAN_FA1R_FACT9                      ((uint16_t)0x0200)            /*!<Filter 9 Active */
+#define  CAN_FA1R_FACT10                     ((uint16_t)0x0400)            /*!<Filter 10 Active */
+#define  CAN_FA1R_FACT11                     ((uint16_t)0x0800)            /*!<Filter 11 Active */
+#define  CAN_FA1R_FACT12                     ((uint16_t)0x1000)            /*!<Filter 12 Active */
+#define  CAN_FA1R_FACT13                     ((uint16_t)0x2000)            /*!<Filter 13 Active */
+
+/*******************  Bit definition for CAN_F0R1 register  *******************/
+#define  CAN_F0R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F0R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F0R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F0R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F0R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F0R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F0R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F0R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F0R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F0R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F0R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F0R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F0R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F0R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F0R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F0R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F0R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F0R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F0R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F0R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F0R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F0R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F0R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F0R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F0R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F0R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F0R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F0R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F0R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F0R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F0R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F0R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F1R1 register  *******************/
+#define  CAN_F1R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F1R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F1R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F1R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F1R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F1R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F1R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F1R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F1R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F1R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F1R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F1R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F1R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F1R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F1R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F1R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F1R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F1R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F1R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F1R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F1R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F1R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F1R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F1R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F1R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F1R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F1R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F1R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F1R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F1R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F1R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F1R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F2R1 register  *******************/
+#define  CAN_F2R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F2R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F2R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F2R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F2R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F2R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F2R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F2R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F2R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F2R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F2R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F2R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F2R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F2R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F2R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F2R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F2R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F2R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F2R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F2R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F2R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F2R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F2R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F2R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F2R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F2R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F2R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F2R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F2R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F2R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F2R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F2R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F3R1 register  *******************/
+#define  CAN_F3R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F3R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F3R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F3R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F3R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F3R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F3R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F3R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F3R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F3R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F3R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F3R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F3R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F3R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F3R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F3R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F3R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F3R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F3R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F3R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F3R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F3R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F3R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F3R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F3R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F3R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F3R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F3R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F3R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F3R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F3R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F3R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F4R1 register  *******************/
+#define  CAN_F4R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F4R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F4R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F4R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F4R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F4R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F4R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F4R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F4R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F4R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F4R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F4R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F4R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F4R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F4R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F4R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F4R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F4R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F4R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F4R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F4R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F4R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F4R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F4R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F4R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F4R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F4R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F4R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F4R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F4R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F4R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F4R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F5R1 register  *******************/
+#define  CAN_F5R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F5R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F5R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F5R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F5R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F5R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F5R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F5R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F5R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F5R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F5R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F5R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F5R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F5R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F5R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F5R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F5R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F5R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F5R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F5R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F5R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F5R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F5R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F5R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F5R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F5R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F5R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F5R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F5R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F5R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F5R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F5R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F6R1 register  *******************/
+#define  CAN_F6R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F6R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F6R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F6R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F6R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F6R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F6R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F6R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F6R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F6R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F6R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F6R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F6R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F6R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F6R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F6R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F6R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F6R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F6R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F6R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F6R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F6R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F6R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F6R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F6R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F6R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F6R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F6R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F6R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F6R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F6R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F6R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F7R1 register  *******************/
+#define  CAN_F7R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F7R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F7R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F7R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F7R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F7R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F7R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F7R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F7R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F7R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F7R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F7R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F7R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F7R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F7R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F7R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F7R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F7R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F7R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F7R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F7R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F7R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F7R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F7R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F7R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F7R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F7R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F7R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F7R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F7R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F7R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F7R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F8R1 register  *******************/
+#define  CAN_F8R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F8R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F8R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F8R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F8R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F8R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F8R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F8R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F8R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F8R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F8R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F8R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F8R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F8R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F8R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F8R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F8R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F8R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F8R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F8R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F8R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F8R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F8R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F8R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F8R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F8R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F8R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F8R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F8R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F8R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F8R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F8R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F9R1 register  *******************/
+#define  CAN_F9R1_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F9R1_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F9R1_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F9R1_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F9R1_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F9R1_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F9R1_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F9R1_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F9R1_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F9R1_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F9R1_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F9R1_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F9R1_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F9R1_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F9R1_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F9R1_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F9R1_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F9R1_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F9R1_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F9R1_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F9R1_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F9R1_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F9R1_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F9R1_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F9R1_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F9R1_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F9R1_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F9R1_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F9R1_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F9R1_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F9R1_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F9R1_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F10R1 register  ******************/
+#define  CAN_F10R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F10R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F10R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F10R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F10R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F10R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F10R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F10R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F10R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F10R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F10R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F10R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F10R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F10R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F10R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F10R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F10R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F10R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F10R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F10R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F10R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F10R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F10R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F10R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F10R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F10R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F10R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F10R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F10R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F10R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F10R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F10R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F11R1 register  ******************/
+#define  CAN_F11R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F11R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F11R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F11R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F11R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F11R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F11R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F11R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F11R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F11R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F11R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F11R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F11R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F11R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F11R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F11R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F11R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F11R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F11R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F11R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F11R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F11R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F11R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F11R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F11R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F11R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F11R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F11R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F11R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F11R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F11R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F11R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F12R1 register  ******************/
+#define  CAN_F12R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F12R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F12R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F12R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F12R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F12R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F12R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F12R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F12R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F12R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F12R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F12R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F12R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F12R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F12R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F12R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F12R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F12R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F12R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F12R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F12R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F12R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F12R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F12R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F12R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F12R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F12R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F12R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F12R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F12R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F12R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F12R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F13R1 register  ******************/
+#define  CAN_F13R1_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F13R1_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F13R1_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F13R1_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F13R1_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F13R1_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F13R1_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F13R1_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F13R1_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F13R1_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F13R1_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F13R1_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F13R1_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F13R1_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F13R1_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F13R1_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F13R1_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F13R1_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F13R1_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F13R1_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F13R1_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F13R1_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F13R1_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F13R1_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F13R1_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F13R1_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F13R1_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F13R1_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F13R1_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F13R1_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F13R1_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F13R1_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F0R2 register  *******************/
+#define  CAN_F0R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F0R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F0R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F0R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F0R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F0R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F0R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F0R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F0R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F0R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F0R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F0R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F0R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F0R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F0R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F0R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F0R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F0R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F0R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F0R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F0R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F0R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F0R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F0R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F0R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F0R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F0R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F0R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F0R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F0R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F0R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F0R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F1R2 register  *******************/
+#define  CAN_F1R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F1R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F1R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F1R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F1R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F1R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F1R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F1R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F1R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F1R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F1R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F1R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F1R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F1R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F1R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F1R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F1R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F1R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F1R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F1R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F1R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F1R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F1R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F1R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F1R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F1R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F1R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F1R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F1R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F1R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F1R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F1R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F2R2 register  *******************/
+#define  CAN_F2R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F2R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F2R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F2R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F2R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F2R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F2R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F2R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F2R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F2R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F2R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F2R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F2R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F2R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F2R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F2R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F2R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F2R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F2R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F2R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F2R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F2R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F2R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F2R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F2R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F2R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F2R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F2R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F2R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F2R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F2R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F2R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F3R2 register  *******************/
+#define  CAN_F3R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F3R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F3R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F3R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F3R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F3R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F3R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F3R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F3R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F3R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F3R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F3R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F3R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F3R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F3R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F3R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F3R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F3R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F3R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F3R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F3R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F3R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F3R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F3R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F3R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F3R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F3R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F3R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F3R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F3R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F3R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F3R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F4R2 register  *******************/
+#define  CAN_F4R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F4R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F4R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F4R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F4R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F4R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F4R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F4R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F4R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F4R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F4R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F4R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F4R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F4R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F4R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F4R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F4R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F4R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F4R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F4R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F4R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F4R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F4R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F4R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F4R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F4R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F4R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F4R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F4R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F4R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F4R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F4R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F5R2 register  *******************/
+#define  CAN_F5R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F5R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F5R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F5R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F5R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F5R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F5R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F5R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F5R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F5R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F5R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F5R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F5R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F5R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F5R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F5R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F5R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F5R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F5R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F5R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F5R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F5R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F5R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F5R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F5R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F5R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F5R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F5R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F5R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F5R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F5R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F5R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F6R2 register  *******************/
+#define  CAN_F6R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F6R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F6R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F6R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F6R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F6R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F6R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F6R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F6R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F6R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F6R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F6R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F6R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F6R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F6R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F6R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F6R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F6R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F6R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F6R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F6R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F6R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F6R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F6R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F6R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F6R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F6R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F6R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F6R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F6R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F6R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F6R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F7R2 register  *******************/
+#define  CAN_F7R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F7R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F7R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F7R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F7R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F7R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F7R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F7R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F7R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F7R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F7R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F7R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F7R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F7R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F7R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F7R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F7R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F7R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F7R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F7R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F7R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F7R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F7R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F7R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F7R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F7R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F7R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F7R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F7R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F7R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F7R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F7R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F8R2 register  *******************/
+#define  CAN_F8R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F8R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F8R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F8R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F8R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F8R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F8R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F8R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F8R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F8R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F8R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F8R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F8R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F8R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F8R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F8R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F8R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F8R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F8R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F8R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F8R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F8R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F8R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F8R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F8R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F8R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F8R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F8R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F8R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F8R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F8R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F8R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F9R2 register  *******************/
+#define  CAN_F9R2_FB0                        ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F9R2_FB1                        ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F9R2_FB2                        ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F9R2_FB3                        ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F9R2_FB4                        ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F9R2_FB5                        ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F9R2_FB6                        ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F9R2_FB7                        ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F9R2_FB8                        ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F9R2_FB9                        ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F9R2_FB10                       ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F9R2_FB11                       ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F9R2_FB12                       ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F9R2_FB13                       ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F9R2_FB14                       ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F9R2_FB15                       ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F9R2_FB16                       ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F9R2_FB17                       ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F9R2_FB18                       ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F9R2_FB19                       ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F9R2_FB20                       ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F9R2_FB21                       ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F9R2_FB22                       ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F9R2_FB23                       ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F9R2_FB24                       ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F9R2_FB25                       ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F9R2_FB26                       ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F9R2_FB27                       ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F9R2_FB28                       ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F9R2_FB29                       ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F9R2_FB30                       ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F9R2_FB31                       ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F10R2 register  ******************/
+#define  CAN_F10R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F10R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F10R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F10R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F10R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F10R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F10R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F10R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F10R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F10R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F10R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F10R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F10R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F10R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F10R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F10R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F10R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F10R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F10R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F10R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F10R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F10R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F10R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F10R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F10R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F10R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F10R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F10R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F10R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F10R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F10R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F10R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F11R2 register  ******************/
+#define  CAN_F11R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F11R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F11R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F11R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F11R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F11R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F11R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F11R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F11R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F11R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F11R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F11R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F11R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F11R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F11R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F11R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F11R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F11R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F11R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F11R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F11R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F11R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F11R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F11R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F11R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F11R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F11R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F11R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F11R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F11R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F11R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F11R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F12R2 register  ******************/
+#define  CAN_F12R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F12R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F12R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F12R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F12R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F12R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F12R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F12R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F12R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F12R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F12R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F12R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F12R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F12R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F12R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F12R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F12R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F12R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F12R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F12R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F12R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F12R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F12R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F12R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F12R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F12R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F12R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F12R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F12R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F12R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F12R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F12R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/*******************  Bit definition for CAN_F13R2 register  ******************/
+#define  CAN_F13R2_FB0                       ((uint32_t)0x00000001)        /*!<Filter bit 0 */
+#define  CAN_F13R2_FB1                       ((uint32_t)0x00000002)        /*!<Filter bit 1 */
+#define  CAN_F13R2_FB2                       ((uint32_t)0x00000004)        /*!<Filter bit 2 */
+#define  CAN_F13R2_FB3                       ((uint32_t)0x00000008)        /*!<Filter bit 3 */
+#define  CAN_F13R2_FB4                       ((uint32_t)0x00000010)        /*!<Filter bit 4 */
+#define  CAN_F13R2_FB5                       ((uint32_t)0x00000020)        /*!<Filter bit 5 */
+#define  CAN_F13R2_FB6                       ((uint32_t)0x00000040)        /*!<Filter bit 6 */
+#define  CAN_F13R2_FB7                       ((uint32_t)0x00000080)        /*!<Filter bit 7 */
+#define  CAN_F13R2_FB8                       ((uint32_t)0x00000100)        /*!<Filter bit 8 */
+#define  CAN_F13R2_FB9                       ((uint32_t)0x00000200)        /*!<Filter bit 9 */
+#define  CAN_F13R2_FB10                      ((uint32_t)0x00000400)        /*!<Filter bit 10 */
+#define  CAN_F13R2_FB11                      ((uint32_t)0x00000800)        /*!<Filter bit 11 */
+#define  CAN_F13R2_FB12                      ((uint32_t)0x00001000)        /*!<Filter bit 12 */
+#define  CAN_F13R2_FB13                      ((uint32_t)0x00002000)        /*!<Filter bit 13 */
+#define  CAN_F13R2_FB14                      ((uint32_t)0x00004000)        /*!<Filter bit 14 */
+#define  CAN_F13R2_FB15                      ((uint32_t)0x00008000)        /*!<Filter bit 15 */
+#define  CAN_F13R2_FB16                      ((uint32_t)0x00010000)        /*!<Filter bit 16 */
+#define  CAN_F13R2_FB17                      ((uint32_t)0x00020000)        /*!<Filter bit 17 */
+#define  CAN_F13R2_FB18                      ((uint32_t)0x00040000)        /*!<Filter bit 18 */
+#define  CAN_F13R2_FB19                      ((uint32_t)0x00080000)        /*!<Filter bit 19 */
+#define  CAN_F13R2_FB20                      ((uint32_t)0x00100000)        /*!<Filter bit 20 */
+#define  CAN_F13R2_FB21                      ((uint32_t)0x00200000)        /*!<Filter bit 21 */
+#define  CAN_F13R2_FB22                      ((uint32_t)0x00400000)        /*!<Filter bit 22 */
+#define  CAN_F13R2_FB23                      ((uint32_t)0x00800000)        /*!<Filter bit 23 */
+#define  CAN_F13R2_FB24                      ((uint32_t)0x01000000)        /*!<Filter bit 24 */
+#define  CAN_F13R2_FB25                      ((uint32_t)0x02000000)        /*!<Filter bit 25 */
+#define  CAN_F13R2_FB26                      ((uint32_t)0x04000000)        /*!<Filter bit 26 */
+#define  CAN_F13R2_FB27                      ((uint32_t)0x08000000)        /*!<Filter bit 27 */
+#define  CAN_F13R2_FB28                      ((uint32_t)0x10000000)        /*!<Filter bit 28 */
+#define  CAN_F13R2_FB29                      ((uint32_t)0x20000000)        /*!<Filter bit 29 */
+#define  CAN_F13R2_FB30                      ((uint32_t)0x40000000)        /*!<Filter bit 30 */
+#define  CAN_F13R2_FB31                      ((uint32_t)0x80000000)        /*!<Filter bit 31 */
+
+/******************************************************************************/
+/*                                                                            */
+/*                          CRC calculation unit                              */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for CRC_DR register  *********************/
+#define  CRC_DR_DR                           ((uint32_t)0xFFFFFFFF) /*!< Data register bits */
+
+
+/*******************  Bit definition for CRC_IDR register  ********************/
+#define  CRC_IDR_IDR                         ((uint8_t)0xFF)        /*!< General-purpose 8-bit data register bits */
+
+
+/********************  Bit definition for CRC_CR register  ********************/
+#define  CRC_CR_RESET                        ((uint8_t)0x01)        /*!< RESET bit */
+
+/******************************************************************************/
+/*                                                                            */
+/*                            Crypto Processor                                */
+/*                                                                            */
+/******************************************************************************/
+/******************* Bits definition for CRYP_CR register  ********************/
+#define CRYP_CR_ALGODIR                      ((uint32_t)0x00000004)
+
+#define CRYP_CR_ALGOMODE                     ((uint32_t)0x00080038)
+#define CRYP_CR_ALGOMODE_0                   ((uint32_t)0x00000008)
+#define CRYP_CR_ALGOMODE_1                   ((uint32_t)0x00000010)
+#define CRYP_CR_ALGOMODE_2                   ((uint32_t)0x00000020)
+#define CRYP_CR_ALGOMODE_TDES_ECB            ((uint32_t)0x00000000)
+#define CRYP_CR_ALGOMODE_TDES_CBC            ((uint32_t)0x00000008)
+#define CRYP_CR_ALGOMODE_DES_ECB             ((uint32_t)0x00000010)
+#define CRYP_CR_ALGOMODE_DES_CBC             ((uint32_t)0x00000018)
+#define CRYP_CR_ALGOMODE_AES_ECB             ((uint32_t)0x00000020)
+#define CRYP_CR_ALGOMODE_AES_CBC             ((uint32_t)0x00000028)
+#define CRYP_CR_ALGOMODE_AES_CTR             ((uint32_t)0x00000030)
+#define CRYP_CR_ALGOMODE_AES_KEY             ((uint32_t)0x00000038)
+
+#define CRYP_CR_DATATYPE                     ((uint32_t)0x000000C0)
+#define CRYP_CR_DATATYPE_0                   ((uint32_t)0x00000040)
+#define CRYP_CR_DATATYPE_1                   ((uint32_t)0x00000080)
+#define CRYP_CR_KEYSIZE                      ((uint32_t)0x00000300)
+#define CRYP_CR_KEYSIZE_0                    ((uint32_t)0x00000100)
+#define CRYP_CR_KEYSIZE_1                    ((uint32_t)0x00000200)
+#define CRYP_CR_FFLUSH                       ((uint32_t)0x00004000)
+#define CRYP_CR_CRYPEN                       ((uint32_t)0x00008000)
+
+#define CRYP_CR_GCM_CCMPH                    ((uint32_t)0x00030000)
+#define CRYP_CR_GCM_CCMPH_0                  ((uint32_t)0x00010000)
+#define CRYP_CR_GCM_CCMPH_1                  ((uint32_t)0x00020000)
+#define CRYP_CR_ALGOMODE_3                   ((uint32_t)0x00080000) 
+
+/****************** Bits definition for CRYP_SR register  *********************/
+#define CRYP_SR_IFEM                         ((uint32_t)0x00000001)
+#define CRYP_SR_IFNF                         ((uint32_t)0x00000002)
+#define CRYP_SR_OFNE                         ((uint32_t)0x00000004)
+#define CRYP_SR_OFFU                         ((uint32_t)0x00000008)
+#define CRYP_SR_BUSY                         ((uint32_t)0x00000010)
+/****************** Bits definition for CRYP_DMACR register  ******************/
+#define CRYP_DMACR_DIEN                      ((uint32_t)0x00000001)
+#define CRYP_DMACR_DOEN                      ((uint32_t)0x00000002)
+/*****************  Bits definition for CRYP_IMSCR register  ******************/
+#define CRYP_IMSCR_INIM                      ((uint32_t)0x00000001)
+#define CRYP_IMSCR_OUTIM                     ((uint32_t)0x00000002)
+/****************** Bits definition for CRYP_RISR register  *******************/
+#define CRYP_RISR_OUTRIS                     ((uint32_t)0x00000001)
+#define CRYP_RISR_INRIS                      ((uint32_t)0x00000002)
+/****************** Bits definition for CRYP_MISR register  *******************/
+#define CRYP_MISR_INMIS                      ((uint32_t)0x00000001)
+#define CRYP_MISR_OUTMIS                     ((uint32_t)0x00000002)
+
+/******************************************************************************/
+/*                                                                            */
+/*                      Digital to Analog Converter                           */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bit definition for DAC_CR register  ********************/
+#define  DAC_CR_EN1                          ((uint32_t)0x00000001)        /*!<DAC channel1 enable */
+#define  DAC_CR_BOFF1                        ((uint32_t)0x00000002)        /*!<DAC channel1 output buffer disable */
+#define  DAC_CR_TEN1                         ((uint32_t)0x00000004)        /*!<DAC channel1 Trigger enable */
+
+#define  DAC_CR_TSEL1                        ((uint32_t)0x00000038)        /*!<TSEL1[2:0] (DAC channel1 Trigger selection) */
+#define  DAC_CR_TSEL1_0                      ((uint32_t)0x00000008)        /*!<Bit 0 */
+#define  DAC_CR_TSEL1_1                      ((uint32_t)0x00000010)        /*!<Bit 1 */
+#define  DAC_CR_TSEL1_2                      ((uint32_t)0x00000020)        /*!<Bit 2 */
+
+#define  DAC_CR_WAVE1                        ((uint32_t)0x000000C0)        /*!<WAVE1[1:0] (DAC channel1 noise/triangle wave generation enable) */
+#define  DAC_CR_WAVE1_0                      ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  DAC_CR_WAVE1_1                      ((uint32_t)0x00000080)        /*!<Bit 1 */
+
+#define  DAC_CR_MAMP1                        ((uint32_t)0x00000F00)        /*!<MAMP1[3:0] (DAC channel1 Mask/Amplitude selector) */
+#define  DAC_CR_MAMP1_0                      ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  DAC_CR_MAMP1_1                      ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  DAC_CR_MAMP1_2                      ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  DAC_CR_MAMP1_3                      ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  DAC_CR_DMAEN1                       ((uint32_t)0x00001000)        /*!<DAC channel1 DMA enable */
+#define  DAC_CR_EN2                          ((uint32_t)0x00010000)        /*!<DAC channel2 enable */
+#define  DAC_CR_BOFF2                        ((uint32_t)0x00020000)        /*!<DAC channel2 output buffer disable */
+#define  DAC_CR_TEN2                         ((uint32_t)0x00040000)        /*!<DAC channel2 Trigger enable */
+
+#define  DAC_CR_TSEL2                        ((uint32_t)0x00380000)        /*!<TSEL2[2:0] (DAC channel2 Trigger selection) */
+#define  DAC_CR_TSEL2_0                      ((uint32_t)0x00080000)        /*!<Bit 0 */
+#define  DAC_CR_TSEL2_1                      ((uint32_t)0x00100000)        /*!<Bit 1 */
+#define  DAC_CR_TSEL2_2                      ((uint32_t)0x00200000)        /*!<Bit 2 */
+
+#define  DAC_CR_WAVE2                        ((uint32_t)0x00C00000)        /*!<WAVE2[1:0] (DAC channel2 noise/triangle wave generation enable) */
+#define  DAC_CR_WAVE2_0                      ((uint32_t)0x00400000)        /*!<Bit 0 */
+#define  DAC_CR_WAVE2_1                      ((uint32_t)0x00800000)        /*!<Bit 1 */
+
+#define  DAC_CR_MAMP2                        ((uint32_t)0x0F000000)        /*!<MAMP2[3:0] (DAC channel2 Mask/Amplitude selector) */
+#define  DAC_CR_MAMP2_0                      ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  DAC_CR_MAMP2_1                      ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  DAC_CR_MAMP2_2                      ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  DAC_CR_MAMP2_3                      ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  DAC_CR_DMAEN2                       ((uint32_t)0x10000000)        /*!<DAC channel2 DMA enabled */
+
+/*****************  Bit definition for DAC_SWTRIGR register  ******************/
+#define  DAC_SWTRIGR_SWTRIG1                 ((uint8_t)0x01)               /*!<DAC channel1 software trigger */
+#define  DAC_SWTRIGR_SWTRIG2                 ((uint8_t)0x02)               /*!<DAC channel2 software trigger */
+
+/*****************  Bit definition for DAC_DHR12R1 register  ******************/
+#define  DAC_DHR12R1_DACC1DHR                ((uint16_t)0x0FFF)            /*!<DAC channel1 12-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12L1 register  ******************/
+#define  DAC_DHR12L1_DACC1DHR                ((uint16_t)0xFFF0)            /*!<DAC channel1 12-bit Left aligned data */
+
+/******************  Bit definition for DAC_DHR8R1 register  ******************/
+#define  DAC_DHR8R1_DACC1DHR                 ((uint8_t)0xFF)               /*!<DAC channel1 8-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12R2 register  ******************/
+#define  DAC_DHR12R2_DACC2DHR                ((uint16_t)0x0FFF)            /*!<DAC channel2 12-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12L2 register  ******************/
+#define  DAC_DHR12L2_DACC2DHR                ((uint16_t)0xFFF0)            /*!<DAC channel2 12-bit Left aligned data */
+
+/******************  Bit definition for DAC_DHR8R2 register  ******************/
+#define  DAC_DHR8R2_DACC2DHR                 ((uint8_t)0xFF)               /*!<DAC channel2 8-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12RD register  ******************/
+#define  DAC_DHR12RD_DACC1DHR                ((uint32_t)0x00000FFF)        /*!<DAC channel1 12-bit Right aligned data */
+#define  DAC_DHR12RD_DACC2DHR                ((uint32_t)0x0FFF0000)        /*!<DAC channel2 12-bit Right aligned data */
+
+/*****************  Bit definition for DAC_DHR12LD register  ******************/
+#define  DAC_DHR12LD_DACC1DHR                ((uint32_t)0x0000FFF0)        /*!<DAC channel1 12-bit Left aligned data */
+#define  DAC_DHR12LD_DACC2DHR                ((uint32_t)0xFFF00000)        /*!<DAC channel2 12-bit Left aligned data */
+
+/******************  Bit definition for DAC_DHR8RD register  ******************/
+#define  DAC_DHR8RD_DACC1DHR                 ((uint16_t)0x00FF)            /*!<DAC channel1 8-bit Right aligned data */
+#define  DAC_DHR8RD_DACC2DHR                 ((uint16_t)0xFF00)            /*!<DAC channel2 8-bit Right aligned data */
+
+/*******************  Bit definition for DAC_DOR1 register  *******************/
+#define  DAC_DOR1_DACC1DOR                   ((uint16_t)0x0FFF)            /*!<DAC channel1 data output */
+
+/*******************  Bit definition for DAC_DOR2 register  *******************/
+#define  DAC_DOR2_DACC2DOR                   ((uint16_t)0x0FFF)            /*!<DAC channel2 data output */
+
+/********************  Bit definition for DAC_SR register  ********************/
+#define  DAC_SR_DMAUDR1                      ((uint32_t)0x00002000)        /*!<DAC channel1 DMA underrun flag */
+#define  DAC_SR_DMAUDR2                      ((uint32_t)0x20000000)        /*!<DAC channel2 DMA underrun flag */
+
+/******************************************************************************/
+/*                                                                            */
+/*                                 Debug MCU                                  */
+/*                                                                            */
+/******************************************************************************/
+
+/******************************************************************************/
+/*                                                                            */
+/*                                    DCMI                                    */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bits definition for DCMI_CR register  ******************/
+#define DCMI_CR_CAPTURE                      ((uint32_t)0x00000001)
+#define DCMI_CR_CM                           ((uint32_t)0x00000002)
+#define DCMI_CR_CROP                         ((uint32_t)0x00000004)
+#define DCMI_CR_JPEG                         ((uint32_t)0x00000008)
+#define DCMI_CR_ESS                          ((uint32_t)0x00000010)
+#define DCMI_CR_PCKPOL                       ((uint32_t)0x00000020)
+#define DCMI_CR_HSPOL                        ((uint32_t)0x00000040)
+#define DCMI_CR_VSPOL                        ((uint32_t)0x00000080)
+#define DCMI_CR_FCRC_0                       ((uint32_t)0x00000100)
+#define DCMI_CR_FCRC_1                       ((uint32_t)0x00000200)
+#define DCMI_CR_EDM_0                        ((uint32_t)0x00000400)
+#define DCMI_CR_EDM_1                        ((uint32_t)0x00000800)
+#define DCMI_CR_CRE                          ((uint32_t)0x00001000)
+#define DCMI_CR_ENABLE                       ((uint32_t)0x00004000)
+
+/********************  Bits definition for DCMI_SR register  ******************/
+#define DCMI_SR_HSYNC                        ((uint32_t)0x00000001)
+#define DCMI_SR_VSYNC                        ((uint32_t)0x00000002)
+#define DCMI_SR_FNE                          ((uint32_t)0x00000004)
+
+/********************  Bits definition for DCMI_RISR register  ****************/
+#define DCMI_RISR_FRAME_RIS                  ((uint32_t)0x00000001)
+#define DCMI_RISR_OVF_RIS                    ((uint32_t)0x00000002)
+#define DCMI_RISR_ERR_RIS                    ((uint32_t)0x00000004)
+#define DCMI_RISR_VSYNC_RIS                  ((uint32_t)0x00000008)
+#define DCMI_RISR_LINE_RIS                   ((uint32_t)0x00000010)
+
+/********************  Bits definition for DCMI_IER register  *****************/
+#define DCMI_IER_FRAME_IE                    ((uint32_t)0x00000001)
+#define DCMI_IER_OVF_IE                      ((uint32_t)0x00000002)
+#define DCMI_IER_ERR_IE                      ((uint32_t)0x00000004)
+#define DCMI_IER_VSYNC_IE                    ((uint32_t)0x00000008)
+#define DCMI_IER_LINE_IE                     ((uint32_t)0x00000010)
+
+/********************  Bits definition for DCMI_MISR register  ****************/
+#define DCMI_MISR_FRAME_MIS                  ((uint32_t)0x00000001)
+#define DCMI_MISR_OVF_MIS                    ((uint32_t)0x00000002)
+#define DCMI_MISR_ERR_MIS                    ((uint32_t)0x00000004)
+#define DCMI_MISR_VSYNC_MIS                  ((uint32_t)0x00000008)
+#define DCMI_MISR_LINE_MIS                   ((uint32_t)0x00000010)
+
+/********************  Bits definition for DCMI_ICR register  *****************/
+#define DCMI_ICR_FRAME_ISC                   ((uint32_t)0x00000001)
+#define DCMI_ICR_OVF_ISC                     ((uint32_t)0x00000002)
+#define DCMI_ICR_ERR_ISC                     ((uint32_t)0x00000004)
+#define DCMI_ICR_VSYNC_ISC                   ((uint32_t)0x00000008)
+#define DCMI_ICR_LINE_ISC                    ((uint32_t)0x00000010)
+
+/******************************************************************************/
+/*                                                                            */
+/*                             DMA Controller                                 */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bits definition for DMA_SxCR register  *****************/ 
+#define DMA_SxCR_CHSEL                       ((uint32_t)0x0E000000)
+#define DMA_SxCR_CHSEL_0                     ((uint32_t)0x02000000)
+#define DMA_SxCR_CHSEL_1                     ((uint32_t)0x04000000)
+#define DMA_SxCR_CHSEL_2                     ((uint32_t)0x08000000) 
+#define DMA_SxCR_MBURST                      ((uint32_t)0x01800000)
+#define DMA_SxCR_MBURST_0                    ((uint32_t)0x00800000)
+#define DMA_SxCR_MBURST_1                    ((uint32_t)0x01000000)
+#define DMA_SxCR_PBURST                      ((uint32_t)0x00600000)
+#define DMA_SxCR_PBURST_0                    ((uint32_t)0x00200000)
+#define DMA_SxCR_PBURST_1                    ((uint32_t)0x00400000)
+#define DMA_SxCR_ACK                         ((uint32_t)0x00100000)
+#define DMA_SxCR_CT                          ((uint32_t)0x00080000)  
+#define DMA_SxCR_DBM                         ((uint32_t)0x00040000)
+#define DMA_SxCR_PL                          ((uint32_t)0x00030000)
+#define DMA_SxCR_PL_0                        ((uint32_t)0x00010000)
+#define DMA_SxCR_PL_1                        ((uint32_t)0x00020000)
+#define DMA_SxCR_PINCOS                      ((uint32_t)0x00008000)
+#define DMA_SxCR_MSIZE                       ((uint32_t)0x00006000)
+#define DMA_SxCR_MSIZE_0                     ((uint32_t)0x00002000)
+#define DMA_SxCR_MSIZE_1                     ((uint32_t)0x00004000)
+#define DMA_SxCR_PSIZE                       ((uint32_t)0x00001800)
+#define DMA_SxCR_PSIZE_0                     ((uint32_t)0x00000800)
+#define DMA_SxCR_PSIZE_1                     ((uint32_t)0x00001000)
+#define DMA_SxCR_MINC                        ((uint32_t)0x00000400)
+#define DMA_SxCR_PINC                        ((uint32_t)0x00000200)
+#define DMA_SxCR_CIRC                        ((uint32_t)0x00000100)
+#define DMA_SxCR_DIR                         ((uint32_t)0x000000C0)
+#define DMA_SxCR_DIR_0                       ((uint32_t)0x00000040)
+#define DMA_SxCR_DIR_1                       ((uint32_t)0x00000080)
+#define DMA_SxCR_PFCTRL                      ((uint32_t)0x00000020)
+#define DMA_SxCR_TCIE                        ((uint32_t)0x00000010)
+#define DMA_SxCR_HTIE                        ((uint32_t)0x00000008)
+#define DMA_SxCR_TEIE                        ((uint32_t)0x00000004)
+#define DMA_SxCR_DMEIE                       ((uint32_t)0x00000002)
+#define DMA_SxCR_EN                          ((uint32_t)0x00000001)
+
+/********************  Bits definition for DMA_SxCNDTR register  **************/
+#define DMA_SxNDT                            ((uint32_t)0x0000FFFF)
+#define DMA_SxNDT_0                          ((uint32_t)0x00000001)
+#define DMA_SxNDT_1                          ((uint32_t)0x00000002)
+#define DMA_SxNDT_2                          ((uint32_t)0x00000004)
+#define DMA_SxNDT_3                          ((uint32_t)0x00000008)
+#define DMA_SxNDT_4                          ((uint32_t)0x00000010)
+#define DMA_SxNDT_5                          ((uint32_t)0x00000020)
+#define DMA_SxNDT_6                          ((uint32_t)0x00000040)
+#define DMA_SxNDT_7                          ((uint32_t)0x00000080)
+#define DMA_SxNDT_8                          ((uint32_t)0x00000100)
+#define DMA_SxNDT_9                          ((uint32_t)0x00000200)
+#define DMA_SxNDT_10                         ((uint32_t)0x00000400)
+#define DMA_SxNDT_11                         ((uint32_t)0x00000800)
+#define DMA_SxNDT_12                         ((uint32_t)0x00001000)
+#define DMA_SxNDT_13                         ((uint32_t)0x00002000)
+#define DMA_SxNDT_14                         ((uint32_t)0x00004000)
+#define DMA_SxNDT_15                         ((uint32_t)0x00008000)
+
+/********************  Bits definition for DMA_SxFCR register  ****************/ 
+#define DMA_SxFCR_FEIE                       ((uint32_t)0x00000080)
+#define DMA_SxFCR_FS                         ((uint32_t)0x00000038)
+#define DMA_SxFCR_FS_0                       ((uint32_t)0x00000008)
+#define DMA_SxFCR_FS_1                       ((uint32_t)0x00000010)
+#define DMA_SxFCR_FS_2                       ((uint32_t)0x00000020)
+#define DMA_SxFCR_DMDIS                      ((uint32_t)0x00000004)
+#define DMA_SxFCR_FTH                        ((uint32_t)0x00000003)
+#define DMA_SxFCR_FTH_0                      ((uint32_t)0x00000001)
+#define DMA_SxFCR_FTH_1                      ((uint32_t)0x00000002)
+
+/********************  Bits definition for DMA_LISR register  *****************/ 
+#define DMA_LISR_TCIF3                       ((uint32_t)0x08000000)
+#define DMA_LISR_HTIF3                       ((uint32_t)0x04000000)
+#define DMA_LISR_TEIF3                       ((uint32_t)0x02000000)
+#define DMA_LISR_DMEIF3                      ((uint32_t)0x01000000)
+#define DMA_LISR_FEIF3                       ((uint32_t)0x00400000)
+#define DMA_LISR_TCIF2                       ((uint32_t)0x00200000)
+#define DMA_LISR_HTIF2                       ((uint32_t)0x00100000)
+#define DMA_LISR_TEIF2                       ((uint32_t)0x00080000)
+#define DMA_LISR_DMEIF2                      ((uint32_t)0x00040000)
+#define DMA_LISR_FEIF2                       ((uint32_t)0x00010000)
+#define DMA_LISR_TCIF1                       ((uint32_t)0x00000800)
+#define DMA_LISR_HTIF1                       ((uint32_t)0x00000400)
+#define DMA_LISR_TEIF1                       ((uint32_t)0x00000200)
+#define DMA_LISR_DMEIF1                      ((uint32_t)0x00000100)
+#define DMA_LISR_FEIF1                       ((uint32_t)0x00000040)
+#define DMA_LISR_TCIF0                       ((uint32_t)0x00000020)
+#define DMA_LISR_HTIF0                       ((uint32_t)0x00000010)
+#define DMA_LISR_TEIF0                       ((uint32_t)0x00000008)
+#define DMA_LISR_DMEIF0                      ((uint32_t)0x00000004)
+#define DMA_LISR_FEIF0                       ((uint32_t)0x00000001)
+
+/********************  Bits definition for DMA_HISR register  *****************/ 
+#define DMA_HISR_TCIF7                       ((uint32_t)0x08000000)
+#define DMA_HISR_HTIF7                       ((uint32_t)0x04000000)
+#define DMA_HISR_TEIF7                       ((uint32_t)0x02000000)
+#define DMA_HISR_DMEIF7                      ((uint32_t)0x01000000)
+#define DMA_HISR_FEIF7                       ((uint32_t)0x00400000)
+#define DMA_HISR_TCIF6                       ((uint32_t)0x00200000)
+#define DMA_HISR_HTIF6                       ((uint32_t)0x00100000)
+#define DMA_HISR_TEIF6                       ((uint32_t)0x00080000)
+#define DMA_HISR_DMEIF6                      ((uint32_t)0x00040000)
+#define DMA_HISR_FEIF6                       ((uint32_t)0x00010000)
+#define DMA_HISR_TCIF5                       ((uint32_t)0x00000800)
+#define DMA_HISR_HTIF5                       ((uint32_t)0x00000400)
+#define DMA_HISR_TEIF5                       ((uint32_t)0x00000200)
+#define DMA_HISR_DMEIF5                      ((uint32_t)0x00000100)
+#define DMA_HISR_FEIF5                       ((uint32_t)0x00000040)
+#define DMA_HISR_TCIF4                       ((uint32_t)0x00000020)
+#define DMA_HISR_HTIF4                       ((uint32_t)0x00000010)
+#define DMA_HISR_TEIF4                       ((uint32_t)0x00000008)
+#define DMA_HISR_DMEIF4                      ((uint32_t)0x00000004)
+#define DMA_HISR_FEIF4                       ((uint32_t)0x00000001)
+
+/********************  Bits definition for DMA_LIFCR register  ****************/ 
+#define DMA_LIFCR_CTCIF3                     ((uint32_t)0x08000000)
+#define DMA_LIFCR_CHTIF3                     ((uint32_t)0x04000000)
+#define DMA_LIFCR_CTEIF3                     ((uint32_t)0x02000000)
+#define DMA_LIFCR_CDMEIF3                    ((uint32_t)0x01000000)
+#define DMA_LIFCR_CFEIF3                     ((uint32_t)0x00400000)
+#define DMA_LIFCR_CTCIF2                     ((uint32_t)0x00200000)
+#define DMA_LIFCR_CHTIF2                     ((uint32_t)0x00100000)
+#define DMA_LIFCR_CTEIF2                     ((uint32_t)0x00080000)
+#define DMA_LIFCR_CDMEIF2                    ((uint32_t)0x00040000)
+#define DMA_LIFCR_CFEIF2                     ((uint32_t)0x00010000)
+#define DMA_LIFCR_CTCIF1                     ((uint32_t)0x00000800)
+#define DMA_LIFCR_CHTIF1                     ((uint32_t)0x00000400)
+#define DMA_LIFCR_CTEIF1                     ((uint32_t)0x00000200)
+#define DMA_LIFCR_CDMEIF1                    ((uint32_t)0x00000100)
+#define DMA_LIFCR_CFEIF1                     ((uint32_t)0x00000040)
+#define DMA_LIFCR_CTCIF0                     ((uint32_t)0x00000020)
+#define DMA_LIFCR_CHTIF0                     ((uint32_t)0x00000010)
+#define DMA_LIFCR_CTEIF0                     ((uint32_t)0x00000008)
+#define DMA_LIFCR_CDMEIF0                    ((uint32_t)0x00000004)
+#define DMA_LIFCR_CFEIF0                     ((uint32_t)0x00000001)
+
+/********************  Bits definition for DMA_HIFCR  register  ****************/ 
+#define DMA_HIFCR_CTCIF7                     ((uint32_t)0x08000000)
+#define DMA_HIFCR_CHTIF7                     ((uint32_t)0x04000000)
+#define DMA_HIFCR_CTEIF7                     ((uint32_t)0x02000000)
+#define DMA_HIFCR_CDMEIF7                    ((uint32_t)0x01000000)
+#define DMA_HIFCR_CFEIF7                     ((uint32_t)0x00400000)
+#define DMA_HIFCR_CTCIF6                     ((uint32_t)0x00200000)
+#define DMA_HIFCR_CHTIF6                     ((uint32_t)0x00100000)
+#define DMA_HIFCR_CTEIF6                     ((uint32_t)0x00080000)
+#define DMA_HIFCR_CDMEIF6                    ((uint32_t)0x00040000)
+#define DMA_HIFCR_CFEIF6                     ((uint32_t)0x00010000)
+#define DMA_HIFCR_CTCIF5                     ((uint32_t)0x00000800)
+#define DMA_HIFCR_CHTIF5                     ((uint32_t)0x00000400)
+#define DMA_HIFCR_CTEIF5                     ((uint32_t)0x00000200)
+#define DMA_HIFCR_CDMEIF5                    ((uint32_t)0x00000100)
+#define DMA_HIFCR_CFEIF5                     ((uint32_t)0x00000040)
+#define DMA_HIFCR_CTCIF4                     ((uint32_t)0x00000020)
+#define DMA_HIFCR_CHTIF4                     ((uint32_t)0x00000010)
+#define DMA_HIFCR_CTEIF4                     ((uint32_t)0x00000008)
+#define DMA_HIFCR_CDMEIF4                    ((uint32_t)0x00000004)
+#define DMA_HIFCR_CFEIF4                     ((uint32_t)0x00000001)
+
+/******************************************************************************/
+/*                                                                            */
+/*                         AHB Master DMA2D Controller (DMA2D)                */
+/*                                                                            */
+/******************************************************************************/
+
+/********************  Bit definition for DMA2D_CR register  ******************/
+
+#define DMA2D_CR_START                     ((uint32_t)0x00000001)               /*!< Start transfer */
+#define DMA2D_CR_SUSP                      ((uint32_t)0x00000002)               /*!< Suspend transfer */
+#define DMA2D_CR_ABORT                     ((uint32_t)0x00000004)               /*!< Abort transfer */
+#define DMA2D_CR_TEIE                      ((uint32_t)0x00000100)               /*!< Transfer Error Interrupt Enable */
+#define DMA2D_CR_TCIE                      ((uint32_t)0x00000200)               /*!< Transfer Complete Interrupt Enable */
+#define DMA2D_CR_TWIE                      ((uint32_t)0x00000400)               /*!< Transfer Watermark Interrupt Enable */
+#define DMA2D_CR_CAEIE                     ((uint32_t)0x00000800)               /*!< CLUT Access Error Interrupt Enable */
+#define DMA2D_CR_CTCIE                     ((uint32_t)0x00001000)               /*!< CLUT Transfer Complete Interrupt Enable */
+#define DMA2D_CR_CEIE                      ((uint32_t)0x00002000)               /*!< Configuration Error Interrupt Enable */
+#define DMA2D_CR_MODE                      ((uint32_t)0x00030000)               /*!< DMA2D Mode */
+
+/********************  Bit definition for DMA2D_ISR register  *****************/
+
+#define DMA2D_ISR_TEIF                     ((uint32_t)0x00000001)               /*!< Transfer Error Interrupt Flag */
+#define DMA2D_ISR_TCIF                     ((uint32_t)0x00000002)               /*!< Transfer Complete Interrupt Flag */
+#define DMA2D_ISR_TWIF                     ((uint32_t)0x00000004)               /*!< Transfer Watermark Interrupt Flag */
+#define DMA2D_ISR_CAEIF                    ((uint32_t)0x00000008)               /*!< CLUT Access Error Interrupt Flag */
+#define DMA2D_ISR_CTCIF                    ((uint32_t)0x00000010)               /*!< CLUT Transfer Complete Interrupt Flag */
+#define DMA2D_ISR_CEIF                     ((uint32_t)0x00000020)               /*!< Configuration Error Interrupt Flag */
+
+/********************  Bit definition for DMA2D_IFSR register  ****************/
+
+#define DMA2D_IFSR_CTEIF                   ((uint32_t)0x00000001)               /*!< Clears Transfer Error Interrupt Flag */
+#define DMA2D_IFSR_CTCIF                   ((uint32_t)0x00000002)               /*!< Clears Transfer Complete Interrupt Flag */
+#define DMA2D_IFSR_CTWIF                   ((uint32_t)0x00000004)               /*!< Clears Transfer Watermark Interrupt Flag */
+#define DMA2D_IFSR_CCAEIF                  ((uint32_t)0x00000008)               /*!< Clears CLUT Access Error Interrupt Flag */
+#define DMA2D_IFSR_CCTCIF                  ((uint32_t)0x00000010)               /*!< Clears CLUT Transfer Complete Interrupt Flag */
+#define DMA2D_IFSR_CCEIF                   ((uint32_t)0x00000020)               /*!< Clears Configuration Error Interrupt Flag */
+
+/********************  Bit definition for DMA2D_FGMAR register  ***************/
+
+#define DMA2D_FGMAR_MA                     ((uint32_t)0xFFFFFFFF)               /*!< Memory Address */
+
+/********************  Bit definition for DMA2D_FGOR register  ****************/
+
+#define DMA2D_FGOR_LO                      ((uint32_t)0x00003FFF)               /*!< Line Offset */
+
+/********************  Bit definition for DMA2D_BGMAR register  ***************/
+
+#define DMA2D_BGMAR_MA                     ((uint32_t)0xFFFFFFFF)               /*!< Memory Address */
+
+/********************  Bit definition for DMA2D_BGOR register  ****************/
+
+#define DMA2D_BGOR_LO                      ((uint32_t)0x00003FFF)               /*!< Line Offset */
+
+/********************  Bit definition for DMA2D_FGPFCCR register  *************/
+
+#define DMA2D_FGPFCCR_CM                   ((uint32_t)0x0000000F)               /*!< Color mode */
+#define DMA2D_FGPFCCR_CCM                  ((uint32_t)0x00000010)               /*!< CLUT Color mode */
+#define DMA2D_FGPFCCR_START                ((uint32_t)0x00000020)               /*!< Start */
+#define DMA2D_FGPFCCR_CS                   ((uint32_t)0x0000FF00)               /*!< CLUT size */
+#define DMA2D_FGPFCCR_AM                   ((uint32_t)0x00030000)               /*!< Alpha mode */
+#define DMA2D_FGPFCCR_ALPHA                ((uint32_t)0xFF000000)               /*!< Alpha value */
+
+/********************  Bit definition for DMA2D_FGCOLR register  **************/
+
+#define DMA2D_FGCOLR_BLUE                  ((uint32_t)0x000000FF)               /*!< Blue Value */
+#define DMA2D_FGCOLR_GREEN                 ((uint32_t)0x0000FF00)               /*!< Green Value */
+#define DMA2D_FGCOLR_RED                   ((uint32_t)0x00FF0000)               /*!< Red Value */   
+
+/********************  Bit definition for DMA2D_BGPFCCR register  *************/
+
+#define DMA2D_BGPFCCR_CM                   ((uint32_t)0x0000000F)               /*!< Color mode */
+#define DMA2D_BGPFCCR_CCM                  ((uint32_t)0x00000010)               /*!< CLUT Color mode */
+#define DMA2D_BGPFCCR_START                ((uint32_t)0x00000020)               /*!< Start */
+#define DMA2D_BGPFCCR_CS                   ((uint32_t)0x0000FF00)               /*!< CLUT size */
+#define DMA2D_BGPFCCR_AM                   ((uint32_t)0x00030000)               /*!< Alpha Mode */
+#define DMA2D_BGPFCCR_ALPHA                ((uint32_t)0xFF000000)               /*!< Alpha value */
+
+/********************  Bit definition for DMA2D_BGCOLR register  **************/
+
+#define DMA2D_BGCOLR_BLUE                  ((uint32_t)0x000000FF)               /*!< Blue Value */
+#define DMA2D_BGCOLR_GREEN                 ((uint32_t)0x0000FF00)               /*!< Green Value */
+#define DMA2D_BGCOLR_RED                   ((uint32_t)0x00FF0000)               /*!< Red Value */
+
+/********************  Bit definition for DMA2D_FGCMAR register  **************/
+
+#define DMA2D_FGCMAR_MA                    ((uint32_t)0xFFFFFFFF)               /*!< Memory Address */
+
+/********************  Bit definition for DMA2D_BGCMAR register  **************/
+
+#define DMA2D_BGCMAR_MA                    ((uint32_t)0xFFFFFFFF)               /*!< Memory Address */
+
+/********************  Bit definition for DMA2D_OPFCCR register  **************/
+
+#define DMA2D_OPFCCR_CM                    ((uint32_t)0x00000007)               /*!< Color mode */
+
+/********************  Bit definition for DMA2D_OCOLR register  ***************/
+
+/*!<Mode_ARGB8888/RGB888 */
+
+#define DMA2D_OCOLR_BLUE_1                 ((uint32_t)0x000000FF)               /*!< BLUE Value */
+#define DMA2D_OCOLR_GREEN_1                ((uint32_t)0x0000FF00)               /*!< GREEN Value  */
+#define DMA2D_OCOLR_RED_1                  ((uint32_t)0x00FF0000)               /*!< Red Value */
+#define DMA2D_OCOLR_ALPHA_1                ((uint32_t)0xFF000000)               /*!< Alpha Channel Value */
+
+/*!<Mode_RGB565 */
+#define DMA2D_OCOLR_BLUE_2                 ((uint32_t)0x0000001F)               /*!< BLUE Value */
+#define DMA2D_OCOLR_GREEN_2                ((uint32_t)0x000007E0)               /*!< GREEN Value  */
+#define DMA2D_OCOLR_RED_2                  ((uint32_t)0x0000F800)               /*!< Red Value */
+
+/*!<Mode_ARGB1555 */
+#define DMA2D_OCOLR_BLUE_3                 ((uint32_t)0x0000001F)               /*!< BLUE Value */
+#define DMA2D_OCOLR_GREEN_3                ((uint32_t)0x000003E0)               /*!< GREEN Value  */
+#define DMA2D_OCOLR_RED_3                  ((uint32_t)0x00007C00)               /*!< Red Value */
+#define DMA2D_OCOLR_ALPHA_3                ((uint32_t)0x00008000)               /*!< Alpha Channel Value */
+
+/*!<Mode_ARGB4444 */
+#define DMA2D_OCOLR_BLUE_4                 ((uint32_t)0x0000000F)               /*!< BLUE Value */
+#define DMA2D_OCOLR_GREEN_4                ((uint32_t)0x000000F0)               /*!< GREEN Value  */
+#define DMA2D_OCOLR_RED_4                  ((uint32_t)0x00000F00)               /*!< Red Value */
+#define DMA2D_OCOLR_ALPHA_4                ((uint32_t)0x0000F000)               /*!< Alpha Channel Value */
+
+/********************  Bit definition for DMA2D_OMAR register  ****************/
+
+#define DMA2D_OMAR_MA                      ((uint32_t)0xFFFFFFFF)               /*!< Memory Address */
+
+/********************  Bit definition for DMA2D_OOR register  *****************/
+
+#define DMA2D_OOR_LO                       ((uint32_t)0x00003FFF)               /*!< Line Offset */
+
+/********************  Bit definition for DMA2D_NLR register  *****************/
+
+#define DMA2D_NLR_NL                       ((uint32_t)0x0000FFFF)               /*!< Number of Lines */
+#define DMA2D_NLR_PL                       ((uint32_t)0x3FFF0000)               /*!< Pixel per Lines */
+
+/********************  Bit definition for DMA2D_LWR register  *****************/
+
+#define DMA2D_LWR_LW                       ((uint32_t)0x0000FFFF)               /*!< Line Watermark */
+
+/********************  Bit definition for DMA2D_AMTCR register  ***************/
+
+#define DMA2D_AMTCR_EN                     ((uint32_t)0x00000001)               /*!< Enable */
+#define DMA2D_AMTCR_DT                     ((uint32_t)0x0000FF00)               /*!< Dead Time */
+
+
+
+/********************  Bit definition for DMA2D_FGCLUT register  **************/
+                                                                     
+/********************  Bit definition for DMA2D_BGCLUT register  **************/
+
+
+/******************************************************************************/
+/*                                                                            */
+/*                    External Interrupt/Event Controller                     */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for EXTI_IMR register  *******************/
+#define  EXTI_IMR_MR0                        ((uint32_t)0x00000001)        /*!< Interrupt Mask on line 0 */
+#define  EXTI_IMR_MR1                        ((uint32_t)0x00000002)        /*!< Interrupt Mask on line 1 */
+#define  EXTI_IMR_MR2                        ((uint32_t)0x00000004)        /*!< Interrupt Mask on line 2 */
+#define  EXTI_IMR_MR3                        ((uint32_t)0x00000008)        /*!< Interrupt Mask on line 3 */
+#define  EXTI_IMR_MR4                        ((uint32_t)0x00000010)        /*!< Interrupt Mask on line 4 */
+#define  EXTI_IMR_MR5                        ((uint32_t)0x00000020)        /*!< Interrupt Mask on line 5 */
+#define  EXTI_IMR_MR6                        ((uint32_t)0x00000040)        /*!< Interrupt Mask on line 6 */
+#define  EXTI_IMR_MR7                        ((uint32_t)0x00000080)        /*!< Interrupt Mask on line 7 */
+#define  EXTI_IMR_MR8                        ((uint32_t)0x00000100)        /*!< Interrupt Mask on line 8 */
+#define  EXTI_IMR_MR9                        ((uint32_t)0x00000200)        /*!< Interrupt Mask on line 9 */
+#define  EXTI_IMR_MR10                       ((uint32_t)0x00000400)        /*!< Interrupt Mask on line 10 */
+#define  EXTI_IMR_MR11                       ((uint32_t)0x00000800)        /*!< Interrupt Mask on line 11 */
+#define  EXTI_IMR_MR12                       ((uint32_t)0x00001000)        /*!< Interrupt Mask on line 12 */
+#define  EXTI_IMR_MR13                       ((uint32_t)0x00002000)        /*!< Interrupt Mask on line 13 */
+#define  EXTI_IMR_MR14                       ((uint32_t)0x00004000)        /*!< Interrupt Mask on line 14 */
+#define  EXTI_IMR_MR15                       ((uint32_t)0x00008000)        /*!< Interrupt Mask on line 15 */
+#define  EXTI_IMR_MR16                       ((uint32_t)0x00010000)        /*!< Interrupt Mask on line 16 */
+#define  EXTI_IMR_MR17                       ((uint32_t)0x00020000)        /*!< Interrupt Mask on line 17 */
+#define  EXTI_IMR_MR18                       ((uint32_t)0x00040000)        /*!< Interrupt Mask on line 18 */
+#define  EXTI_IMR_MR19                       ((uint32_t)0x00080000)        /*!< Interrupt Mask on line 19 */
+
+/*******************  Bit definition for EXTI_EMR register  *******************/
+#define  EXTI_EMR_MR0                        ((uint32_t)0x00000001)        /*!< Event Mask on line 0 */
+#define  EXTI_EMR_MR1                        ((uint32_t)0x00000002)        /*!< Event Mask on line 1 */
+#define  EXTI_EMR_MR2                        ((uint32_t)0x00000004)        /*!< Event Mask on line 2 */
+#define  EXTI_EMR_MR3                        ((uint32_t)0x00000008)        /*!< Event Mask on line 3 */
+#define  EXTI_EMR_MR4                        ((uint32_t)0x00000010)        /*!< Event Mask on line 4 */
+#define  EXTI_EMR_MR5                        ((uint32_t)0x00000020)        /*!< Event Mask on line 5 */
+#define  EXTI_EMR_MR6                        ((uint32_t)0x00000040)        /*!< Event Mask on line 6 */
+#define  EXTI_EMR_MR7                        ((uint32_t)0x00000080)        /*!< Event Mask on line 7 */
+#define  EXTI_EMR_MR8                        ((uint32_t)0x00000100)        /*!< Event Mask on line 8 */
+#define  EXTI_EMR_MR9                        ((uint32_t)0x00000200)        /*!< Event Mask on line 9 */
+#define  EXTI_EMR_MR10                       ((uint32_t)0x00000400)        /*!< Event Mask on line 10 */
+#define  EXTI_EMR_MR11                       ((uint32_t)0x00000800)        /*!< Event Mask on line 11 */
+#define  EXTI_EMR_MR12                       ((uint32_t)0x00001000)        /*!< Event Mask on line 12 */
+#define  EXTI_EMR_MR13                       ((uint32_t)0x00002000)        /*!< Event Mask on line 13 */
+#define  EXTI_EMR_MR14                       ((uint32_t)0x00004000)        /*!< Event Mask on line 14 */
+#define  EXTI_EMR_MR15                       ((uint32_t)0x00008000)        /*!< Event Mask on line 15 */
+#define  EXTI_EMR_MR16                       ((uint32_t)0x00010000)        /*!< Event Mask on line 16 */
+#define  EXTI_EMR_MR17                       ((uint32_t)0x00020000)        /*!< Event Mask on line 17 */
+#define  EXTI_EMR_MR18                       ((uint32_t)0x00040000)        /*!< Event Mask on line 18 */
+#define  EXTI_EMR_MR19                       ((uint32_t)0x00080000)        /*!< Event Mask on line 19 */
+
+/******************  Bit definition for EXTI_RTSR register  *******************/
+#define  EXTI_RTSR_TR0                       ((uint32_t)0x00000001)        /*!< Rising trigger event configuration bit of line 0 */
+#define  EXTI_RTSR_TR1                       ((uint32_t)0x00000002)        /*!< Rising trigger event configuration bit of line 1 */
+#define  EXTI_RTSR_TR2                       ((uint32_t)0x00000004)        /*!< Rising trigger event configuration bit of line 2 */
+#define  EXTI_RTSR_TR3                       ((uint32_t)0x00000008)        /*!< Rising trigger event configuration bit of line 3 */
+#define  EXTI_RTSR_TR4                       ((uint32_t)0x00000010)        /*!< Rising trigger event configuration bit of line 4 */
+#define  EXTI_RTSR_TR5                       ((uint32_t)0x00000020)        /*!< Rising trigger event configuration bit of line 5 */
+#define  EXTI_RTSR_TR6                       ((uint32_t)0x00000040)        /*!< Rising trigger event configuration bit of line 6 */
+#define  EXTI_RTSR_TR7                       ((uint32_t)0x00000080)        /*!< Rising trigger event configuration bit of line 7 */
+#define  EXTI_RTSR_TR8                       ((uint32_t)0x00000100)        /*!< Rising trigger event configuration bit of line 8 */
+#define  EXTI_RTSR_TR9                       ((uint32_t)0x00000200)        /*!< Rising trigger event configuration bit of line 9 */
+#define  EXTI_RTSR_TR10                      ((uint32_t)0x00000400)        /*!< Rising trigger event configuration bit of line 10 */
+#define  EXTI_RTSR_TR11                      ((uint32_t)0x00000800)        /*!< Rising trigger event configuration bit of line 11 */
+#define  EXTI_RTSR_TR12                      ((uint32_t)0x00001000)        /*!< Rising trigger event configuration bit of line 12 */
+#define  EXTI_RTSR_TR13                      ((uint32_t)0x00002000)        /*!< Rising trigger event configuration bit of line 13 */
+#define  EXTI_RTSR_TR14                      ((uint32_t)0x00004000)        /*!< Rising trigger event configuration bit of line 14 */
+#define  EXTI_RTSR_TR15                      ((uint32_t)0x00008000)        /*!< Rising trigger event configuration bit of line 15 */
+#define  EXTI_RTSR_TR16                      ((uint32_t)0x00010000)        /*!< Rising trigger event configuration bit of line 16 */
+#define  EXTI_RTSR_TR17                      ((uint32_t)0x00020000)        /*!< Rising trigger event configuration bit of line 17 */
+#define  EXTI_RTSR_TR18                      ((uint32_t)0x00040000)        /*!< Rising trigger event configuration bit of line 18 */
+#define  EXTI_RTSR_TR19                      ((uint32_t)0x00080000)        /*!< Rising trigger event configuration bit of line 19 */
+
+/******************  Bit definition for EXTI_FTSR register  *******************/
+#define  EXTI_FTSR_TR0                       ((uint32_t)0x00000001)        /*!< Falling trigger event configuration bit of line 0 */
+#define  EXTI_FTSR_TR1                       ((uint32_t)0x00000002)        /*!< Falling trigger event configuration bit of line 1 */
+#define  EXTI_FTSR_TR2                       ((uint32_t)0x00000004)        /*!< Falling trigger event configuration bit of line 2 */
+#define  EXTI_FTSR_TR3                       ((uint32_t)0x00000008)        /*!< Falling trigger event configuration bit of line 3 */
+#define  EXTI_FTSR_TR4                       ((uint32_t)0x00000010)        /*!< Falling trigger event configuration bit of line 4 */
+#define  EXTI_FTSR_TR5                       ((uint32_t)0x00000020)        /*!< Falling trigger event configuration bit of line 5 */
+#define  EXTI_FTSR_TR6                       ((uint32_t)0x00000040)        /*!< Falling trigger event configuration bit of line 6 */
+#define  EXTI_FTSR_TR7                       ((uint32_t)0x00000080)        /*!< Falling trigger event configuration bit of line 7 */
+#define  EXTI_FTSR_TR8                       ((uint32_t)0x00000100)        /*!< Falling trigger event configuration bit of line 8 */
+#define  EXTI_FTSR_TR9                       ((uint32_t)0x00000200)        /*!< Falling trigger event configuration bit of line 9 */
+#define  EXTI_FTSR_TR10                      ((uint32_t)0x00000400)        /*!< Falling trigger event configuration bit of line 10 */
+#define  EXTI_FTSR_TR11                      ((uint32_t)0x00000800)        /*!< Falling trigger event configuration bit of line 11 */
+#define  EXTI_FTSR_TR12                      ((uint32_t)0x00001000)        /*!< Falling trigger event configuration bit of line 12 */
+#define  EXTI_FTSR_TR13                      ((uint32_t)0x00002000)        /*!< Falling trigger event configuration bit of line 13 */
+#define  EXTI_FTSR_TR14                      ((uint32_t)0x00004000)        /*!< Falling trigger event configuration bit of line 14 */
+#define  EXTI_FTSR_TR15                      ((uint32_t)0x00008000)        /*!< Falling trigger event configuration bit of line 15 */
+#define  EXTI_FTSR_TR16                      ((uint32_t)0x00010000)        /*!< Falling trigger event configuration bit of line 16 */
+#define  EXTI_FTSR_TR17                      ((uint32_t)0x00020000)        /*!< Falling trigger event configuration bit of line 17 */
+#define  EXTI_FTSR_TR18                      ((uint32_t)0x00040000)        /*!< Falling trigger event configuration bit of line 18 */
+#define  EXTI_FTSR_TR19                      ((uint32_t)0x00080000)        /*!< Falling trigger event configuration bit of line 19 */
+
+/******************  Bit definition for EXTI_SWIER register  ******************/
+#define  EXTI_SWIER_SWIER0                   ((uint32_t)0x00000001)        /*!< Software Interrupt on line 0 */
+#define  EXTI_SWIER_SWIER1                   ((uint32_t)0x00000002)        /*!< Software Interrupt on line 1 */
+#define  EXTI_SWIER_SWIER2                   ((uint32_t)0x00000004)        /*!< Software Interrupt on line 2 */
+#define  EXTI_SWIER_SWIER3                   ((uint32_t)0x00000008)        /*!< Software Interrupt on line 3 */
+#define  EXTI_SWIER_SWIER4                   ((uint32_t)0x00000010)        /*!< Software Interrupt on line 4 */
+#define  EXTI_SWIER_SWIER5                   ((uint32_t)0x00000020)        /*!< Software Interrupt on line 5 */
+#define  EXTI_SWIER_SWIER6                   ((uint32_t)0x00000040)        /*!< Software Interrupt on line 6 */
+#define  EXTI_SWIER_SWIER7                   ((uint32_t)0x00000080)        /*!< Software Interrupt on line 7 */
+#define  EXTI_SWIER_SWIER8                   ((uint32_t)0x00000100)        /*!< Software Interrupt on line 8 */
+#define  EXTI_SWIER_SWIER9                   ((uint32_t)0x00000200)        /*!< Software Interrupt on line 9 */
+#define  EXTI_SWIER_SWIER10                  ((uint32_t)0x00000400)        /*!< Software Interrupt on line 10 */
+#define  EXTI_SWIER_SWIER11                  ((uint32_t)0x00000800)        /*!< Software Interrupt on line 11 */
+#define  EXTI_SWIER_SWIER12                  ((uint32_t)0x00001000)        /*!< Software Interrupt on line 12 */
+#define  EXTI_SWIER_SWIER13                  ((uint32_t)0x00002000)        /*!< Software Interrupt on line 13 */
+#define  EXTI_SWIER_SWIER14                  ((uint32_t)0x00004000)        /*!< Software Interrupt on line 14 */
+#define  EXTI_SWIER_SWIER15                  ((uint32_t)0x00008000)        /*!< Software Interrupt on line 15 */
+#define  EXTI_SWIER_SWIER16                  ((uint32_t)0x00010000)        /*!< Software Interrupt on line 16 */
+#define  EXTI_SWIER_SWIER17                  ((uint32_t)0x00020000)        /*!< Software Interrupt on line 17 */
+#define  EXTI_SWIER_SWIER18                  ((uint32_t)0x00040000)        /*!< Software Interrupt on line 18 */
+#define  EXTI_SWIER_SWIER19                  ((uint32_t)0x00080000)        /*!< Software Interrupt on line 19 */
+
+/*******************  Bit definition for EXTI_PR register  ********************/
+#define  EXTI_PR_PR0                         ((uint32_t)0x00000001)        /*!< Pending bit for line 0 */
+#define  EXTI_PR_PR1                         ((uint32_t)0x00000002)        /*!< Pending bit for line 1 */
+#define  EXTI_PR_PR2                         ((uint32_t)0x00000004)        /*!< Pending bit for line 2 */
+#define  EXTI_PR_PR3                         ((uint32_t)0x00000008)        /*!< Pending bit for line 3 */
+#define  EXTI_PR_PR4                         ((uint32_t)0x00000010)        /*!< Pending bit for line 4 */
+#define  EXTI_PR_PR5                         ((uint32_t)0x00000020)        /*!< Pending bit for line 5 */
+#define  EXTI_PR_PR6                         ((uint32_t)0x00000040)        /*!< Pending bit for line 6 */
+#define  EXTI_PR_PR7                         ((uint32_t)0x00000080)        /*!< Pending bit for line 7 */
+#define  EXTI_PR_PR8                         ((uint32_t)0x00000100)        /*!< Pending bit for line 8 */
+#define  EXTI_PR_PR9                         ((uint32_t)0x00000200)        /*!< Pending bit for line 9 */
+#define  EXTI_PR_PR10                        ((uint32_t)0x00000400)        /*!< Pending bit for line 10 */
+#define  EXTI_PR_PR11                        ((uint32_t)0x00000800)        /*!< Pending bit for line 11 */
+#define  EXTI_PR_PR12                        ((uint32_t)0x00001000)        /*!< Pending bit for line 12 */
+#define  EXTI_PR_PR13                        ((uint32_t)0x00002000)        /*!< Pending bit for line 13 */
+#define  EXTI_PR_PR14                        ((uint32_t)0x00004000)        /*!< Pending bit for line 14 */
+#define  EXTI_PR_PR15                        ((uint32_t)0x00008000)        /*!< Pending bit for line 15 */
+#define  EXTI_PR_PR16                        ((uint32_t)0x00010000)        /*!< Pending bit for line 16 */
+#define  EXTI_PR_PR17                        ((uint32_t)0x00020000)        /*!< Pending bit for line 17 */
+#define  EXTI_PR_PR18                        ((uint32_t)0x00040000)        /*!< Pending bit for line 18 */
+#define  EXTI_PR_PR19                        ((uint32_t)0x00080000)        /*!< Pending bit for line 19 */
+
+/******************************************************************************/
+/*                                                                            */
+/*                                    FLASH                                   */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bits definition for FLASH_ACR register  *****************/
+#define FLASH_ACR_LATENCY                    ((uint32_t)0x0000000F)
+#define FLASH_ACR_LATENCY_0WS                ((uint32_t)0x00000000)
+#define FLASH_ACR_LATENCY_1WS                ((uint32_t)0x00000001)
+#define FLASH_ACR_LATENCY_2WS                ((uint32_t)0x00000002)
+#define FLASH_ACR_LATENCY_3WS                ((uint32_t)0x00000003)
+#define FLASH_ACR_LATENCY_4WS                ((uint32_t)0x00000004)
+#define FLASH_ACR_LATENCY_5WS                ((uint32_t)0x00000005)
+#define FLASH_ACR_LATENCY_6WS                ((uint32_t)0x00000006)
+#define FLASH_ACR_LATENCY_7WS                ((uint32_t)0x00000007)
+#define FLASH_ACR_LATENCY_8WS                ((uint32_t)0x00000008)
+#define FLASH_ACR_LATENCY_9WS                ((uint32_t)0x00000009)
+#define FLASH_ACR_LATENCY_10WS               ((uint32_t)0x0000000A)
+#define FLASH_ACR_LATENCY_11WS               ((uint32_t)0x0000000B)
+#define FLASH_ACR_LATENCY_12WS               ((uint32_t)0x0000000C)
+#define FLASH_ACR_LATENCY_13WS               ((uint32_t)0x0000000D)
+#define FLASH_ACR_LATENCY_14WS               ((uint32_t)0x0000000E)
+#define FLASH_ACR_LATENCY_15WS               ((uint32_t)0x0000000F)
+
+#define FLASH_ACR_PRFTEN                     ((uint32_t)0x00000100)
+#define FLASH_ACR_ICEN                       ((uint32_t)0x00000200)
+#define FLASH_ACR_DCEN                       ((uint32_t)0x00000400)
+#define FLASH_ACR_ICRST                      ((uint32_t)0x00000800)
+#define FLASH_ACR_DCRST                      ((uint32_t)0x00001000)
+#define FLASH_ACR_BYTE0_ADDRESS              ((uint32_t)0x40023C00)
+#define FLASH_ACR_BYTE2_ADDRESS              ((uint32_t)0x40023C03)
+
+/*******************  Bits definition for FLASH_SR register  ******************/
+#define FLASH_SR_EOP                         ((uint32_t)0x00000001)
+#define FLASH_SR_SOP                         ((uint32_t)0x00000002)
+#define FLASH_SR_WRPERR                      ((uint32_t)0x00000010)
+#define FLASH_SR_PGAERR                      ((uint32_t)0x00000020)
+#define FLASH_SR_PGPERR                      ((uint32_t)0x00000040)
+#define FLASH_SR_PGSERR                      ((uint32_t)0x00000080)
+#define FLASH_SR_BSY                         ((uint32_t)0x00010000)
+
+/*******************  Bits definition for FLASH_CR register  ******************/
+#define FLASH_CR_PG                          ((uint32_t)0x00000001)
+#define FLASH_CR_SER                         ((uint32_t)0x00000002)
+#define FLASH_CR_MER                         ((uint32_t)0x00000004)
+#define FLASH_CR_MER1                        FLASH_CR_MER
+#define FLASH_CR_SNB                         ((uint32_t)0x000000F8)
+#define FLASH_CR_SNB_0                       ((uint32_t)0x00000008)
+#define FLASH_CR_SNB_1                       ((uint32_t)0x00000010)
+#define FLASH_CR_SNB_2                       ((uint32_t)0x00000020)
+#define FLASH_CR_SNB_3                       ((uint32_t)0x00000040)
+#define FLASH_CR_SNB_4                       ((uint32_t)0x00000040)
+#define FLASH_CR_PSIZE                       ((uint32_t)0x00000300)
+#define FLASH_CR_PSIZE_0                     ((uint32_t)0x00000100)
+#define FLASH_CR_PSIZE_1                     ((uint32_t)0x00000200)
+#define FLASH_CR_MER2                        ((uint32_t)0x00008000)
+#define FLASH_CR_STRT                        ((uint32_t)0x00010000)
+#define FLASH_CR_EOPIE                       ((uint32_t)0x01000000)
+#define FLASH_CR_LOCK                        ((uint32_t)0x80000000)
+
+/*******************  Bits definition for FLASH_OPTCR register  ***************/
+#define FLASH_OPTCR_OPTLOCK                 ((uint32_t)0x00000001)
+#define FLASH_OPTCR_OPTSTRT                 ((uint32_t)0x00000002)
+#define FLASH_OPTCR_BOR_LEV_0               ((uint32_t)0x00000004)
+#define FLASH_OPTCR_BOR_LEV_1               ((uint32_t)0x00000008)
+#define FLASH_OPTCR_BOR_LEV                 ((uint32_t)0x0000000C)
+#define FLASH_OPTCR_BFB2                    ((uint32_t)0x00000010)
+
+#define FLASH_OPTCR_WDG_SW                  ((uint32_t)0x00000020)
+#define FLASH_OPTCR_nRST_STOP               ((uint32_t)0x00000040)
+#define FLASH_OPTCR_nRST_STDBY              ((uint32_t)0x00000080)
+#define FLASH_OPTCR_RDP                     ((uint32_t)0x0000FF00)
+#define FLASH_OPTCR_RDP_0                   ((uint32_t)0x00000100)
+#define FLASH_OPTCR_RDP_1                   ((uint32_t)0x00000200)
+#define FLASH_OPTCR_RDP_2                   ((uint32_t)0x00000400)
+#define FLASH_OPTCR_RDP_3                   ((uint32_t)0x00000800)
+#define FLASH_OPTCR_RDP_4                   ((uint32_t)0x00001000)
+#define FLASH_OPTCR_RDP_5                   ((uint32_t)0x00002000)
+#define FLASH_OPTCR_RDP_6                   ((uint32_t)0x00004000)
+#define FLASH_OPTCR_RDP_7                   ((uint32_t)0x00008000)
+#define FLASH_OPTCR_nWRP                    ((uint32_t)0x0FFF0000)
+#define FLASH_OPTCR_nWRP_0                  ((uint32_t)0x00010000)
+#define FLASH_OPTCR_nWRP_1                  ((uint32_t)0x00020000)
+#define FLASH_OPTCR_nWRP_2                  ((uint32_t)0x00040000)
+#define FLASH_OPTCR_nWRP_3                  ((uint32_t)0x00080000)
+#define FLASH_OPTCR_nWRP_4                  ((uint32_t)0x00100000)
+#define FLASH_OPTCR_nWRP_5                  ((uint32_t)0x00200000)
+#define FLASH_OPTCR_nWRP_6                  ((uint32_t)0x00400000)
+#define FLASH_OPTCR_nWRP_7                  ((uint32_t)0x00800000)
+#define FLASH_OPTCR_nWRP_8                  ((uint32_t)0x01000000)
+#define FLASH_OPTCR_nWRP_9                  ((uint32_t)0x02000000)
+#define FLASH_OPTCR_nWRP_10                 ((uint32_t)0x04000000)
+#define FLASH_OPTCR_nWRP_11                 ((uint32_t)0x08000000)
+
+#define FLASH_OPTCR_DB1M                    ((uint32_t)0x40000000) 
+#define FLASH_OPTCR_SPRMOD                  ((uint32_t)0x80000000) 
+                                             
+/******************  Bits definition for FLASH_OPTCR1 register  ***************/
+#define FLASH_OPTCR1_nWRP                    ((uint32_t)0x0FFF0000)
+#define FLASH_OPTCR1_nWRP_0                  ((uint32_t)0x00010000)
+#define FLASH_OPTCR1_nWRP_1                  ((uint32_t)0x00020000)
+#define FLASH_OPTCR1_nWRP_2                  ((uint32_t)0x00040000)
+#define FLASH_OPTCR1_nWRP_3                  ((uint32_t)0x00080000)
+#define FLASH_OPTCR1_nWRP_4                  ((uint32_t)0x00100000)
+#define FLASH_OPTCR1_nWRP_5                  ((uint32_t)0x00200000)
+#define FLASH_OPTCR1_nWRP_6                  ((uint32_t)0x00400000)
+#define FLASH_OPTCR1_nWRP_7                  ((uint32_t)0x00800000)
+#define FLASH_OPTCR1_nWRP_8                  ((uint32_t)0x01000000)
+#define FLASH_OPTCR1_nWRP_9                  ((uint32_t)0x02000000)
+#define FLASH_OPTCR1_nWRP_10                 ((uint32_t)0x04000000)
+#define FLASH_OPTCR1_nWRP_11                 ((uint32_t)0x08000000)
+
+#if defined (STM32F40_41xxx)
+/******************************************************************************/
+/*                                                                            */
+/*                       Flexible Static Memory Controller                    */
+/*                                                                            */
+/******************************************************************************/
+/******************  Bit definition for FSMC_BCR1 register  *******************/
+#define  FSMC_BCR1_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit                 */
+#define  FSMC_BCR1_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FSMC_BCR1_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FSMC_BCR1_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR1_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR1_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR1_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR1_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR1_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable                    */
+#define  FSMC_BCR1_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit                       */
+#define  FSMC_BCR1_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit               */
+#define  FSMC_BCR1_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support             */
+#define  FSMC_BCR1_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration              */
+#define  FSMC_BCR1_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit                       */
+#define  FSMC_BCR1_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit                        */
+#define  FSMC_BCR1_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable                   */
+#define  FSMC_BCR1_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait                      */
+#define  FSMC_BCR1_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable                     */
+
+/******************  Bit definition for FSMC_BCR2 register  *******************/
+#define  FSMC_BCR2_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit                */
+#define  FSMC_BCR2_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FSMC_BCR2_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FSMC_BCR2_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR2_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR2_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR2_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR2_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR2_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable                    */
+#define  FSMC_BCR2_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit                       */
+#define  FSMC_BCR2_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit               */
+#define  FSMC_BCR2_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support             */
+#define  FSMC_BCR2_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration              */
+#define  FSMC_BCR2_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit                       */
+#define  FSMC_BCR2_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit                        */
+#define  FSMC_BCR2_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable                   */
+#define  FSMC_BCR2_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait                      */
+#define  FSMC_BCR2_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable                     */
+
+/******************  Bit definition for FSMC_BCR3 register  *******************/
+#define  FSMC_BCR3_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit                 */
+#define  FSMC_BCR3_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FSMC_BCR3_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FSMC_BCR3_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR3_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR3_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR3_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR3_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR3_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable                    */
+#define  FSMC_BCR3_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit                       */
+#define  FSMC_BCR3_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit               */
+#define  FSMC_BCR3_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support             */
+#define  FSMC_BCR3_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration              */
+#define  FSMC_BCR3_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit                       */
+#define  FSMC_BCR3_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit                        */
+#define  FSMC_BCR3_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable                   */
+#define  FSMC_BCR3_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait                      */
+#define  FSMC_BCR3_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable                     */
+
+/******************  Bit definition for FSMC_BCR4 register  *******************/
+#define  FSMC_BCR4_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit */
+#define  FSMC_BCR4_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FSMC_BCR4_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FSMC_BCR4_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FSMC_BCR4_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FSMC_BCR4_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FSMC_BCR4_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BCR4_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_BCR4_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable                    */
+#define  FSMC_BCR4_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit                       */
+#define  FSMC_BCR4_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit               */
+#define  FSMC_BCR4_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support             */
+#define  FSMC_BCR4_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration              */
+#define  FSMC_BCR4_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit                       */
+#define  FSMC_BCR4_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit                        */
+#define  FSMC_BCR4_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable                   */
+#define  FSMC_BCR4_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait                      */
+#define  FSMC_BCR4_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable                     */
+
+/******************  Bit definition for FSMC_BTR1 register  ******************/
+#define  FSMC_BTR1_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR1_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR1_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR1_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR1_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR1_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR1_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR1_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR1_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR1_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR1_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR1_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR1_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR1_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR1_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR1_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR1_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR1_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR1_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR1_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR1_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR1_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR1_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR1_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR1_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR1_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR1_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR1_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BTR2 register  *******************/
+#define  FSMC_BTR2_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR2_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR2_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR2_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR2_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR2_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR2_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR2_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR2_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR2_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR2_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR2_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR2_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR2_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR2_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR2_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR2_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR2_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR2_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR2_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR2_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR2_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR2_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR2_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR2_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR2_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR2_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR2_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/*******************  Bit definition for FSMC_BTR3 register  *******************/
+#define  FSMC_BTR3_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR3_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR3_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR3_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR3_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR3_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR3_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR3_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR3_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR3_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR3_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR3_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR3_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR3_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR3_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR3_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR3_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR3_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR3_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR3_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR3_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR3_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR3_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR3_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR3_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR3_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR3_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR3_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BTR4 register  *******************/
+#define  FSMC_BTR4_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BTR4_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BTR4_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BTR4_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BTR4_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BTR4_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BTR4_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BTR4_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BTR4_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BTR4_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BTR4_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BTR4_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BTR4_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FSMC_BTR4_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_BTR4_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_BTR4_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_BTR4_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BTR4_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BTR4_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BTR4_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BTR4_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BTR4_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BTR4_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BTR4_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BTR4_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BTR4_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BTR4_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BTR4_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR1 register  ******************/
+#define  FSMC_BWTR1_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR1_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR1_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR1_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR1_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR1_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR1_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR1_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR1_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR1_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR1_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR1_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR1_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR1_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR1_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BWTR1_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR1_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR1_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR1_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR1_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR1_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR1_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR1_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR1_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR2 register  ******************/
+#define  FSMC_BWTR2_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR2_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR2_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR2_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR2_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR2_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR2_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR2_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR2_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR2_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR2_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR2_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR2_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR2_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR2_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1*/
+#define  FSMC_BWTR2_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR2_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR2_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR2_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR2_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR2_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR2_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR2_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR2_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR3 register  ******************/
+#define  FSMC_BWTR3_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR3_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR3_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR3_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR3_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR3_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR3_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR3_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR3_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR3_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR3_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR3_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR3_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR3_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR3_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BWTR3_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR3_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR3_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR3_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR3_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR3_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR3_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR3_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR3_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_BWTR4 register  ******************/
+#define  FSMC_BWTR4_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FSMC_BWTR4_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_BWTR4_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_BWTR4_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_BWTR4_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FSMC_BWTR4_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_BWTR4_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FSMC_BWTR4_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FSMC_BWTR4_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FSMC_BWTR4_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_BWTR4_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_BWTR4_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_BWTR4_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FSMC_BWTR4_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FSMC_BWTR4_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FSMC_BWTR4_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FSMC_BWTR4_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FSMC_BWTR4_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_BWTR4_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_BWTR4_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_BWTR4_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FSMC_BWTR4_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FSMC_BWTR4_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FSMC_BWTR4_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FSMC_PCR2 register  *******************/
+#define  FSMC_PCR2_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit */
+#define  FSMC_PCR2_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FSMC_PCR2_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type */
+
+#define  FSMC_PCR2_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FSMC_PCR2_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_PCR2_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_PCR2_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit */
+
+#define  FSMC_PCR2_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay) */
+#define  FSMC_PCR2_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FSMC_PCR2_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FSMC_PCR2_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FSMC_PCR2_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FSMC_PCR2_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay) */
+#define  FSMC_PCR2_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FSMC_PCR2_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FSMC_PCR2_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FSMC_PCR2_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FSMC_PCR2_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[1:0] bits (ECC page size) */
+#define  FSMC_PCR2_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FSMC_PCR2_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FSMC_PCR2_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/******************  Bit definition for FSMC_PCR3 register  *******************/
+#define  FSMC_PCR3_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit */
+#define  FSMC_PCR3_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FSMC_PCR3_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type */
+
+#define  FSMC_PCR3_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FSMC_PCR3_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_PCR3_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_PCR3_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit */
+
+#define  FSMC_PCR3_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay) */
+#define  FSMC_PCR3_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FSMC_PCR3_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FSMC_PCR3_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FSMC_PCR3_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FSMC_PCR3_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay) */
+#define  FSMC_PCR3_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FSMC_PCR3_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FSMC_PCR3_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FSMC_PCR3_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FSMC_PCR3_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[2:0] bits (ECC page size) */
+#define  FSMC_PCR3_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FSMC_PCR3_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FSMC_PCR3_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/******************  Bit definition for FSMC_PCR4 register  *******************/
+#define  FSMC_PCR4_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit */
+#define  FSMC_PCR4_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FSMC_PCR4_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type */
+
+#define  FSMC_PCR4_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FSMC_PCR4_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FSMC_PCR4_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FSMC_PCR4_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit */
+
+#define  FSMC_PCR4_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay) */
+#define  FSMC_PCR4_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FSMC_PCR4_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FSMC_PCR4_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FSMC_PCR4_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FSMC_PCR4_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay) */
+#define  FSMC_PCR4_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FSMC_PCR4_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FSMC_PCR4_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FSMC_PCR4_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FSMC_PCR4_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[2:0] bits (ECC page size) */
+#define  FSMC_PCR4_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FSMC_PCR4_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FSMC_PCR4_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/*******************  Bit definition for FSMC_SR2 register  *******************/
+#define  FSMC_SR2_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status                */
+#define  FSMC_SR2_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status                      */
+#define  FSMC_SR2_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status               */
+#define  FSMC_SR2_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit  */
+#define  FSMC_SR2_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit        */
+#define  FSMC_SR2_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FSMC_SR2_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty */
+
+/*******************  Bit definition for FSMC_SR3 register  *******************/
+#define  FSMC_SR3_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status                */
+#define  FSMC_SR3_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status                      */
+#define  FSMC_SR3_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status               */
+#define  FSMC_SR3_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit  */
+#define  FSMC_SR3_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit        */
+#define  FSMC_SR3_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FSMC_SR3_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty */
+
+/*******************  Bit definition for FSMC_SR4 register  *******************/
+#define  FSMC_SR4_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status                 */
+#define  FSMC_SR4_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status                       */
+#define  FSMC_SR4_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status                */
+#define  FSMC_SR4_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit   */
+#define  FSMC_SR4_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit         */
+#define  FSMC_SR4_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit  */
+#define  FSMC_SR4_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty */
+
+/******************  Bit definition for FSMC_PMEM2 register  ******************/
+#define  FSMC_PMEM2_MEMSET2                  ((uint32_t)0x000000FF)        /*!<MEMSET2[7:0] bits (Common memory 2 setup time) */
+#define  FSMC_PMEM2_MEMSET2_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMSET2_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMSET2_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMSET2_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMSET2_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMSET2_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMSET2_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMSET2_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PMEM2_MEMWAIT2                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT2[7:0] bits (Common memory 2 wait time) */
+#define  FSMC_PMEM2_MEMWAIT2_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMWAIT2_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMWAIT2_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMWAIT2_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMWAIT2_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMWAIT2_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMWAIT2_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMWAIT2_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM2_MEMHOLD2                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD2[7:0] bits (Common memory 2 hold time) */
+#define  FSMC_PMEM2_MEMHOLD2_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMHOLD2_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMHOLD2_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMHOLD2_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMHOLD2_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMHOLD2_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMHOLD2_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMHOLD2_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM2_MEMHIZ2                  ((uint32_t)0xFF000000)        /*!<MEMHIZ2[7:0] bits (Common memory 2 databus HiZ time) */
+#define  FSMC_PMEM2_MEMHIZ2_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PMEM2_MEMHIZ2_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PMEM2_MEMHIZ2_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PMEM2_MEMHIZ2_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PMEM2_MEMHIZ2_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PMEM2_MEMHIZ2_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PMEM2_MEMHIZ2_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PMEM2_MEMHIZ2_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PMEM3 register  ******************/
+#define  FSMC_PMEM3_MEMSET3                  ((uint32_t)0x000000FF)        /*!<MEMSET3[7:0] bits (Common memory 3 setup time) */
+#define  FSMC_PMEM3_MEMSET3_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMSET3_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMSET3_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMSET3_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMSET3_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMSET3_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMSET3_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMSET3_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PMEM3_MEMWAIT3                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT3[7:0] bits (Common memory 3 wait time) */
+#define  FSMC_PMEM3_MEMWAIT3_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMWAIT3_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMWAIT3_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMWAIT3_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMWAIT3_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMWAIT3_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMWAIT3_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMWAIT3_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM3_MEMHOLD3                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD3[7:0] bits (Common memory 3 hold time) */
+#define  FSMC_PMEM3_MEMHOLD3_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMHOLD3_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMHOLD3_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMHOLD3_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMHOLD3_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMHOLD3_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMHOLD3_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMHOLD3_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM3_MEMHIZ3                  ((uint32_t)0xFF000000)        /*!<MEMHIZ3[7:0] bits (Common memory 3 databus HiZ time) */
+#define  FSMC_PMEM3_MEMHIZ3_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PMEM3_MEMHIZ3_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PMEM3_MEMHIZ3_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PMEM3_MEMHIZ3_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PMEM3_MEMHIZ3_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PMEM3_MEMHIZ3_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PMEM3_MEMHIZ3_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PMEM3_MEMHIZ3_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PMEM4 register  ******************/
+#define  FSMC_PMEM4_MEMSET4                  ((uint32_t)0x000000FF)        /*!<MEMSET4[7:0] bits (Common memory 4 setup time) */
+#define  FSMC_PMEM4_MEMSET4_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMSET4_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMSET4_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMSET4_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMSET4_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMSET4_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMSET4_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMSET4_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PMEM4_MEMWAIT4                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT4[7:0] bits (Common memory 4 wait time) */
+#define  FSMC_PMEM4_MEMWAIT4_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMWAIT4_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMWAIT4_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMWAIT4_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMWAIT4_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMWAIT4_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMWAIT4_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMWAIT4_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM4_MEMHOLD4                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD4[7:0] bits (Common memory 4 hold time) */
+#define  FSMC_PMEM4_MEMHOLD4_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMHOLD4_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMHOLD4_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMHOLD4_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMHOLD4_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMHOLD4_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMHOLD4_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMHOLD4_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PMEM4_MEMHIZ4                  ((uint32_t)0xFF000000)        /*!<MEMHIZ4[7:0] bits (Common memory 4 databus HiZ time) */
+#define  FSMC_PMEM4_MEMHIZ4_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PMEM4_MEMHIZ4_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PMEM4_MEMHIZ4_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PMEM4_MEMHIZ4_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PMEM4_MEMHIZ4_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PMEM4_MEMHIZ4_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PMEM4_MEMHIZ4_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PMEM4_MEMHIZ4_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PATT2 register  ******************/
+#define  FSMC_PATT2_ATTSET2                  ((uint32_t)0x000000FF)        /*!<ATTSET2[7:0] bits (Attribute memory 2 setup time) */
+#define  FSMC_PATT2_ATTSET2_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTSET2_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTSET2_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTSET2_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTSET2_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTSET2_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTSET2_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTSET2_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PATT2_ATTWAIT2                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT2[7:0] bits (Attribute memory 2 wait time) */
+#define  FSMC_PATT2_ATTWAIT2_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTWAIT2_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTWAIT2_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTWAIT2_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTWAIT2_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTWAIT2_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTWAIT2_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTWAIT2_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PATT2_ATTHOLD2                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD2[7:0] bits (Attribute memory 2 hold time) */
+#define  FSMC_PATT2_ATTHOLD2_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTHOLD2_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTHOLD2_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTHOLD2_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTHOLD2_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTHOLD2_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTHOLD2_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTHOLD2_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PATT2_ATTHIZ2                  ((uint32_t)0xFF000000)        /*!<ATTHIZ2[7:0] bits (Attribute memory 2 databus HiZ time) */
+#define  FSMC_PATT2_ATTHIZ2_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PATT2_ATTHIZ2_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PATT2_ATTHIZ2_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PATT2_ATTHIZ2_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PATT2_ATTHIZ2_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PATT2_ATTHIZ2_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PATT2_ATTHIZ2_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PATT2_ATTHIZ2_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PATT3 register  ******************/
+#define  FSMC_PATT3_ATTSET3                  ((uint32_t)0x000000FF)        /*!<ATTSET3[7:0] bits (Attribute memory 3 setup time) */
+#define  FSMC_PATT3_ATTSET3_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTSET3_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTSET3_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTSET3_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTSET3_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTSET3_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTSET3_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTSET3_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PATT3_ATTWAIT3                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT3[7:0] bits (Attribute memory 3 wait time) */
+#define  FSMC_PATT3_ATTWAIT3_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTWAIT3_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTWAIT3_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTWAIT3_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTWAIT3_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTWAIT3_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTWAIT3_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTWAIT3_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PATT3_ATTHOLD3                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD3[7:0] bits (Attribute memory 3 hold time) */
+#define  FSMC_PATT3_ATTHOLD3_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTHOLD3_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTHOLD3_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTHOLD3_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTHOLD3_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTHOLD3_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTHOLD3_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTHOLD3_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PATT3_ATTHIZ3                  ((uint32_t)0xFF000000)        /*!<ATTHIZ3[7:0] bits (Attribute memory 3 databus HiZ time) */
+#define  FSMC_PATT3_ATTHIZ3_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PATT3_ATTHIZ3_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PATT3_ATTHIZ3_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PATT3_ATTHIZ3_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PATT3_ATTHIZ3_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PATT3_ATTHIZ3_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PATT3_ATTHIZ3_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PATT3_ATTHIZ3_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PATT4 register  ******************/
+#define  FSMC_PATT4_ATTSET4                  ((uint32_t)0x000000FF)        /*!<ATTSET4[7:0] bits (Attribute memory 4 setup time) */
+#define  FSMC_PATT4_ATTSET4_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTSET4_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTSET4_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTSET4_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTSET4_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTSET4_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTSET4_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTSET4_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PATT4_ATTWAIT4                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT4[7:0] bits (Attribute memory 4 wait time) */
+#define  FSMC_PATT4_ATTWAIT4_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTWAIT4_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTWAIT4_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTWAIT4_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTWAIT4_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTWAIT4_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTWAIT4_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTWAIT4_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PATT4_ATTHOLD4                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD4[7:0] bits (Attribute memory 4 hold time) */
+#define  FSMC_PATT4_ATTHOLD4_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTHOLD4_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTHOLD4_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTHOLD4_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTHOLD4_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTHOLD4_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTHOLD4_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTHOLD4_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PATT4_ATTHIZ4                  ((uint32_t)0xFF000000)        /*!<ATTHIZ4[7:0] bits (Attribute memory 4 databus HiZ time) */
+#define  FSMC_PATT4_ATTHIZ4_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PATT4_ATTHIZ4_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PATT4_ATTHIZ4_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PATT4_ATTHIZ4_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PATT4_ATTHIZ4_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PATT4_ATTHIZ4_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PATT4_ATTHIZ4_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PATT4_ATTHIZ4_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_PIO4 register  *******************/
+#define  FSMC_PIO4_IOSET4                    ((uint32_t)0x000000FF)        /*!<IOSET4[7:0] bits (I/O 4 setup time) */
+#define  FSMC_PIO4_IOSET4_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOSET4_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOSET4_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOSET4_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOSET4_4                  ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOSET4_5                  ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOSET4_6                  ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOSET4_7                  ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FSMC_PIO4_IOWAIT4                   ((uint32_t)0x0000FF00)        /*!<IOWAIT4[7:0] bits (I/O 4 wait time) */
+#define  FSMC_PIO4_IOWAIT4_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOWAIT4_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOWAIT4_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOWAIT4_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOWAIT4_4                 ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOWAIT4_5                 ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOWAIT4_6                 ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOWAIT4_7                 ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FSMC_PIO4_IOHOLD4                   ((uint32_t)0x00FF0000)        /*!<IOHOLD4[7:0] bits (I/O 4 hold time) */
+#define  FSMC_PIO4_IOHOLD4_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOHOLD4_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOHOLD4_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOHOLD4_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOHOLD4_4                 ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOHOLD4_5                 ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOHOLD4_6                 ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOHOLD4_7                 ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FSMC_PIO4_IOHIZ4                    ((uint32_t)0xFF000000)        /*!<IOHIZ4[7:0] bits (I/O 4 databus HiZ time) */
+#define  FSMC_PIO4_IOHIZ4_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FSMC_PIO4_IOHIZ4_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FSMC_PIO4_IOHIZ4_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FSMC_PIO4_IOHIZ4_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FSMC_PIO4_IOHIZ4_4                  ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FSMC_PIO4_IOHIZ4_5                  ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FSMC_PIO4_IOHIZ4_6                  ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FSMC_PIO4_IOHIZ4_7                  ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FSMC_ECCR2 register  ******************/
+#define  FSMC_ECCR2_ECC2                     ((uint32_t)0xFFFFFFFF)        /*!<ECC result */
+
+/******************  Bit definition for FSMC_ECCR3 register  ******************/
+#define  FSMC_ECCR3_ECC3                     ((uint32_t)0xFFFFFFFF)        /*!<ECC result */
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+/******************************************************************************/
+/*                                                                            */
+/*                          Flexible Memory Controller                        */
+/*                                                                            */
+/******************************************************************************/
+/******************  Bit definition for FMC_BCR1 register  *******************/
+#define  FMC_BCR1_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit                 */
+#define  FMC_BCR1_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FMC_BCR1_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FMC_BCR1_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FMC_BCR1_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FMC_BCR1_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FMC_BCR1_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BCR1_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_BCR1_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable        */
+#define  FMC_BCR1_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit           */
+#define  FMC_BCR1_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit   */
+#define  FMC_BCR1_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FMC_BCR1_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration  */
+#define  FMC_BCR1_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit           */
+#define  FMC_BCR1_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit            */
+#define  FMC_BCR1_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable       */
+#define  FMC_BCR1_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait          */
+#define  FMC_BCR1_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable         */
+#define  FMC_BCR1_CCLKEN                    ((uint32_t)0x00100000)        /*!<Continous clock enable     */
+
+/******************  Bit definition for FMC_BCR2 register  *******************/
+#define  FMC_BCR2_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit                 */
+#define  FMC_BCR2_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FMC_BCR2_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FMC_BCR2_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FMC_BCR2_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FMC_BCR2_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FMC_BCR2_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BCR2_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_BCR2_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable        */
+#define  FMC_BCR2_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit           */
+#define  FMC_BCR2_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit   */
+#define  FMC_BCR2_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FMC_BCR2_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration  */
+#define  FMC_BCR2_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit           */
+#define  FMC_BCR2_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit            */
+#define  FMC_BCR2_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable       */
+#define  FMC_BCR2_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait          */
+#define  FMC_BCR2_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable         */
+
+/******************  Bit definition for FMC_BCR3 register  *******************/
+#define  FMC_BCR3_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit                 */
+#define  FMC_BCR3_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FMC_BCR3_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FMC_BCR3_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FMC_BCR3_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FMC_BCR3_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FMC_BCR3_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BCR3_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_BCR3_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable        */
+#define  FMC_BCR3_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit           */
+#define  FMC_BCR3_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit   */
+#define  FMC_BCR3_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FMC_BCR3_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration  */
+#define  FMC_BCR3_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit           */
+#define  FMC_BCR3_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit            */
+#define  FMC_BCR3_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable       */
+#define  FMC_BCR3_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait          */
+#define  FMC_BCR3_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable         */
+
+/******************  Bit definition for FMC_BCR4 register  *******************/
+#define  FMC_BCR4_MBKEN                     ((uint32_t)0x00000001)        /*!<Memory bank enable bit                 */
+#define  FMC_BCR4_MUXEN                     ((uint32_t)0x00000002)        /*!<Address/data multiplexing enable bit   */
+
+#define  FMC_BCR4_MTYP                      ((uint32_t)0x0000000C)        /*!<MTYP[1:0] bits (Memory type)           */
+#define  FMC_BCR4_MTYP_0                    ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FMC_BCR4_MTYP_1                    ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FMC_BCR4_MWID                      ((uint32_t)0x00000030)        /*!<MWID[1:0] bits (Memory data bus width) */
+#define  FMC_BCR4_MWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BCR4_MWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_BCR4_FACCEN                    ((uint32_t)0x00000040)        /*!<Flash access enable        */
+#define  FMC_BCR4_BURSTEN                   ((uint32_t)0x00000100)        /*!<Burst enable bit           */
+#define  FMC_BCR4_WAITPOL                   ((uint32_t)0x00000200)        /*!<Wait signal polarity bit   */
+#define  FMC_BCR4_WRAPMOD                   ((uint32_t)0x00000400)        /*!<Wrapped burst mode support */
+#define  FMC_BCR4_WAITCFG                   ((uint32_t)0x00000800)        /*!<Wait timing configuration  */
+#define  FMC_BCR4_WREN                      ((uint32_t)0x00001000)        /*!<Write enable bit           */
+#define  FMC_BCR4_WAITEN                    ((uint32_t)0x00002000)        /*!<Wait enable bit            */
+#define  FMC_BCR4_EXTMOD                    ((uint32_t)0x00004000)        /*!<Extended mode enable       */
+#define  FMC_BCR4_ASYNCWAIT                 ((uint32_t)0x00008000)        /*!<Asynchronous wait          */
+#define  FMC_BCR4_CBURSTRW                  ((uint32_t)0x00080000)        /*!<Write burst enable         */
+
+/******************  Bit definition for FMC_BTR1 register  ******************/
+#define  FMC_BTR1_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BTR1_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BTR1_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BTR1_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BTR1_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BTR1_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration)  */
+#define  FMC_BTR1_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BTR1_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BTR1_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BTR1_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BTR1_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BTR1_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BTR1_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BTR1_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BTR1_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BTR1_DATAST_4                  ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BTR1_DATAST_5                  ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BTR1_DATAST_6                  ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BTR1_DATAST_7                  ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BTR1_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FMC_BTR1_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_BTR1_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_BTR1_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_BTR1_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FMC_BTR1_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BTR1_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BTR1_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_BTR1_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BTR1_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BTR1_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BTR1_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BTR1_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BTR1_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BTR1_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BTR1_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BTR1_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BTR1_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_BTR2 register  *******************/
+#define  FMC_BTR2_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BTR2_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BTR2_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BTR2_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BTR2_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BTR2_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FMC_BTR2_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BTR2_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BTR2_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BTR2_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BTR2_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BTR2_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BTR2_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BTR2_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BTR2_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BTR2_DATAST_4                  ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BTR2_DATAST_5                  ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BTR2_DATAST_6                  ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BTR2_DATAST_7                  ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BTR2_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FMC_BTR2_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_BTR2_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_BTR2_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_BTR2_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FMC_BTR2_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BTR2_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BTR2_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_BTR2_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BTR2_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BTR2_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BTR2_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BTR2_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BTR2_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BTR2_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BTR2_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BTR2_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BTR2_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/*******************  Bit definition for FMC_BTR3 register  *******************/
+#define  FMC_BTR3_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BTR3_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BTR3_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BTR3_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BTR3_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BTR3_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FMC_BTR3_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BTR3_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BTR3_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BTR3_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BTR3_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BTR3_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BTR3_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BTR3_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BTR3_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BTR3_DATAST_4                  ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BTR3_DATAST_5                  ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BTR3_DATAST_6                  ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BTR3_DATAST_7                  ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BTR3_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FMC_BTR3_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_BTR3_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_BTR3_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_BTR3_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FMC_BTR3_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BTR3_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BTR3_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_BTR3_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BTR3_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BTR3_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BTR3_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BTR3_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BTR3_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BTR3_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BTR3_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BTR3_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BTR3_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_BTR4 register  *******************/
+#define  FMC_BTR4_ADDSET                    ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BTR4_ADDSET_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BTR4_ADDSET_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BTR4_ADDSET_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BTR4_ADDSET_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BTR4_ADDHLD                    ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FMC_BTR4_ADDHLD_0                  ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BTR4_ADDHLD_1                  ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BTR4_ADDHLD_2                  ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BTR4_ADDHLD_3                  ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BTR4_DATAST                    ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BTR4_DATAST_0                  ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BTR4_DATAST_1                  ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BTR4_DATAST_2                  ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BTR4_DATAST_3                  ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BTR4_DATAST_4                  ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BTR4_DATAST_5                  ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BTR4_DATAST_6                  ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BTR4_DATAST_7                  ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BTR4_BUSTURN                   ((uint32_t)0x000F0000)        /*!<BUSTURN[3:0] bits (Bus turnaround phase duration) */
+#define  FMC_BTR4_BUSTURN_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_BTR4_BUSTURN_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_BTR4_BUSTURN_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_BTR4_BUSTURN_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+
+#define  FMC_BTR4_CLKDIV                    ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BTR4_CLKDIV_0                  ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BTR4_CLKDIV_1                  ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_BTR4_CLKDIV_2                  ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BTR4_CLKDIV_3                  ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BTR4_DATLAT                    ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BTR4_DATLAT_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BTR4_DATLAT_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BTR4_DATLAT_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BTR4_DATLAT_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BTR4_ACCMOD                    ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BTR4_ACCMOD_0                  ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BTR4_ACCMOD_1                  ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_BWTR1 register  ******************/
+#define  FMC_BWTR1_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BWTR1_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BWTR1_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BWTR1_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BWTR1_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BWTR1_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FMC_BWTR1_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BWTR1_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BWTR1_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BWTR1_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BWTR1_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BWTR1_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BWTR1_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BWTR1_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BWTR1_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BWTR1_DATAST_4                 ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BWTR1_DATAST_5                 ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BWTR1_DATAST_6                 ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BWTR1_DATAST_7                 ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BWTR1_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BWTR1_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BWTR1_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_BWTR1_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BWTR1_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BWTR1_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BWTR1_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BWTR1_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BWTR1_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BWTR1_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BWTR1_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BWTR1_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BWTR1_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_BWTR2 register  ******************/
+#define  FMC_BWTR2_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BWTR2_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BWTR2_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BWTR2_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BWTR2_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BWTR2_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FMC_BWTR2_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BWTR2_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BWTR2_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BWTR2_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BWTR2_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BWTR2_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BWTR2_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BWTR2_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BWTR2_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BWTR2_DATAST_4                 ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BWTR2_DATAST_5                 ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BWTR2_DATAST_6                 ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BWTR2_DATAST_7                 ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BWTR2_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BWTR2_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BWTR2_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1*/
+#define  FMC_BWTR2_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BWTR2_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BWTR2_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BWTR2_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BWTR2_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BWTR2_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BWTR2_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BWTR2_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BWTR2_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BWTR2_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_BWTR3 register  ******************/
+#define  FMC_BWTR3_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BWTR3_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BWTR3_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BWTR3_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BWTR3_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BWTR3_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FMC_BWTR3_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BWTR3_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BWTR3_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BWTR3_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BWTR3_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BWTR3_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BWTR3_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BWTR3_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BWTR3_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BWTR3_DATAST_4                 ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BWTR3_DATAST_5                 ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BWTR3_DATAST_6                 ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BWTR3_DATAST_7                 ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BWTR3_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BWTR3_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BWTR3_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_BWTR3_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BWTR3_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BWTR3_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BWTR3_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BWTR3_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BWTR3_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BWTR3_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BWTR3_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BWTR3_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BWTR3_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_BWTR4 register  ******************/
+#define  FMC_BWTR4_ADDSET                   ((uint32_t)0x0000000F)        /*!<ADDSET[3:0] bits (Address setup phase duration) */
+#define  FMC_BWTR4_ADDSET_0                 ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_BWTR4_ADDSET_1                 ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_BWTR4_ADDSET_2                 ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_BWTR4_ADDSET_3                 ((uint32_t)0x00000008)        /*!<Bit 3 */
+
+#define  FMC_BWTR4_ADDHLD                   ((uint32_t)0x000000F0)        /*!<ADDHLD[3:0] bits (Address-hold phase duration) */
+#define  FMC_BWTR4_ADDHLD_0                 ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_BWTR4_ADDHLD_1                 ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_BWTR4_ADDHLD_2                 ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_BWTR4_ADDHLD_3                 ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_BWTR4_DATAST                   ((uint32_t)0x0000FF00)        /*!<DATAST [3:0] bits (Data-phase duration) */
+#define  FMC_BWTR4_DATAST_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_BWTR4_DATAST_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_BWTR4_DATAST_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_BWTR4_DATAST_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_BWTR4_DATAST_4                 ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_BWTR4_DATAST_5                 ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_BWTR4_DATAST_6                 ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_BWTR4_DATAST_7                 ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_BWTR4_CLKDIV                   ((uint32_t)0x00F00000)        /*!<CLKDIV[3:0] bits (Clock divide ratio) */
+#define  FMC_BWTR4_CLKDIV_0                 ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_BWTR4_CLKDIV_1                 ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_BWTR4_CLKDIV_2                 ((uint32_t)0x00400000)        /*!<Bit 2 */
+#define  FMC_BWTR4_CLKDIV_3                 ((uint32_t)0x00800000)        /*!<Bit 3 */
+
+#define  FMC_BWTR4_DATLAT                   ((uint32_t)0x0F000000)        /*!<DATLA[3:0] bits (Data latency) */
+#define  FMC_BWTR4_DATLAT_0                 ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_BWTR4_DATLAT_1                 ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_BWTR4_DATLAT_2                 ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_BWTR4_DATLAT_3                 ((uint32_t)0x08000000)        /*!<Bit 3 */
+
+#define  FMC_BWTR4_ACCMOD                   ((uint32_t)0x30000000)        /*!<ACCMOD[1:0] bits (Access mode) */
+#define  FMC_BWTR4_ACCMOD_0                 ((uint32_t)0x10000000)        /*!<Bit 0 */
+#define  FMC_BWTR4_ACCMOD_1                 ((uint32_t)0x20000000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_PCR2 register  *******************/
+#define  FMC_PCR2_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit                   */
+#define  FMC_PCR2_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FMC_PCR2_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type                               */
+
+#define  FMC_PCR2_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FMC_PCR2_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_PCR2_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_PCR2_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit          */
+
+#define  FMC_PCR2_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay)          */
+#define  FMC_PCR2_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FMC_PCR2_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FMC_PCR2_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FMC_PCR2_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FMC_PCR2_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay)           */
+#define  FMC_PCR2_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FMC_PCR2_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FMC_PCR2_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FMC_PCR2_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FMC_PCR2_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[1:0] bits (ECC page size)           */
+#define  FMC_PCR2_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FMC_PCR2_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FMC_PCR2_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/******************  Bit definition for FMC_PCR3 register  *******************/
+#define  FMC_PCR3_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit                   */
+#define  FMC_PCR3_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FMC_PCR3_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type                               */
+
+#define  FMC_PCR3_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FMC_PCR3_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_PCR3_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_PCR3_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit          */
+
+#define  FMC_PCR3_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay)          */
+#define  FMC_PCR3_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FMC_PCR3_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FMC_PCR3_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FMC_PCR3_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FMC_PCR3_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay)           */
+#define  FMC_PCR3_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FMC_PCR3_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FMC_PCR3_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FMC_PCR3_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FMC_PCR3_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[2:0] bits (ECC page size)           */
+#define  FMC_PCR3_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FMC_PCR3_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FMC_PCR3_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/******************  Bit definition for FMC_PCR4 register  *******************/
+#define  FMC_PCR4_PWAITEN                   ((uint32_t)0x00000002)        /*!<Wait feature enable bit                   */
+#define  FMC_PCR4_PBKEN                     ((uint32_t)0x00000004)        /*!<PC Card/NAND Flash memory bank enable bit */
+#define  FMC_PCR4_PTYP                      ((uint32_t)0x00000008)        /*!<Memory type                               */
+
+#define  FMC_PCR4_PWID                      ((uint32_t)0x00000030)        /*!<PWID[1:0] bits (NAND Flash databus width) */
+#define  FMC_PCR4_PWID_0                    ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_PCR4_PWID_1                    ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_PCR4_ECCEN                     ((uint32_t)0x00000040)        /*!<ECC computation logic enable bit          */
+
+#define  FMC_PCR4_TCLR                      ((uint32_t)0x00001E00)        /*!<TCLR[3:0] bits (CLE to RE delay)          */
+#define  FMC_PCR4_TCLR_0                    ((uint32_t)0x00000200)        /*!<Bit 0 */
+#define  FMC_PCR4_TCLR_1                    ((uint32_t)0x00000400)        /*!<Bit 1 */
+#define  FMC_PCR4_TCLR_2                    ((uint32_t)0x00000800)        /*!<Bit 2 */
+#define  FMC_PCR4_TCLR_3                    ((uint32_t)0x00001000)        /*!<Bit 3 */
+
+#define  FMC_PCR4_TAR                       ((uint32_t)0x0001E000)        /*!<TAR[3:0] bits (ALE to RE delay)           */
+#define  FMC_PCR4_TAR_0                     ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FMC_PCR4_TAR_1                     ((uint32_t)0x00004000)        /*!<Bit 1 */
+#define  FMC_PCR4_TAR_2                     ((uint32_t)0x00008000)        /*!<Bit 2 */
+#define  FMC_PCR4_TAR_3                     ((uint32_t)0x00010000)        /*!<Bit 3 */
+
+#define  FMC_PCR4_ECCPS                     ((uint32_t)0x000E0000)        /*!<ECCPS[2:0] bits (ECC page size)           */
+#define  FMC_PCR4_ECCPS_0                   ((uint32_t)0x00020000)        /*!<Bit 0 */
+#define  FMC_PCR4_ECCPS_1                   ((uint32_t)0x00040000)        /*!<Bit 1 */
+#define  FMC_PCR4_ECCPS_2                   ((uint32_t)0x00080000)        /*!<Bit 2 */
+
+/*******************  Bit definition for FMC_SR2 register  *******************/
+#define  FMC_SR2_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status                */
+#define  FMC_SR2_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status                      */
+#define  FMC_SR2_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status               */
+#define  FMC_SR2_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit  */
+#define  FMC_SR2_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit        */
+#define  FMC_SR2_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FMC_SR2_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty                                  */
+
+/*******************  Bit definition for FMC_SR3 register  *******************/
+#define  FMC_SR3_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status                */
+#define  FMC_SR3_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status                      */
+#define  FMC_SR3_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status               */
+#define  FMC_SR3_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit  */
+#define  FMC_SR3_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit        */
+#define  FMC_SR3_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FMC_SR3_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty                                  */
+
+/*******************  Bit definition for FMC_SR4 register  *******************/
+#define  FMC_SR4_IRS                        ((uint8_t)0x01)               /*!<Interrupt Rising Edge status                */
+#define  FMC_SR4_ILS                        ((uint8_t)0x02)               /*!<Interrupt Level status                      */
+#define  FMC_SR4_IFS                        ((uint8_t)0x04)               /*!<Interrupt Falling Edge status               */
+#define  FMC_SR4_IREN                       ((uint8_t)0x08)               /*!<Interrupt Rising Edge detection Enable bit  */
+#define  FMC_SR4_ILEN                       ((uint8_t)0x10)               /*!<Interrupt Level detection Enable bit        */
+#define  FMC_SR4_IFEN                       ((uint8_t)0x20)               /*!<Interrupt Falling Edge detection Enable bit */
+#define  FMC_SR4_FEMPT                      ((uint8_t)0x40)               /*!<FIFO empty                                  */
+
+/******************  Bit definition for FMC_PMEM2 register  ******************/
+#define  FMC_PMEM2_MEMSET2                  ((uint32_t)0x000000FF)        /*!<MEMSET2[7:0] bits (Common memory 2 setup time) */
+#define  FMC_PMEM2_MEMSET2_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_PMEM2_MEMSET2_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_PMEM2_MEMSET2_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_PMEM2_MEMSET2_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FMC_PMEM2_MEMSET2_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FMC_PMEM2_MEMSET2_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FMC_PMEM2_MEMSET2_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FMC_PMEM2_MEMSET2_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FMC_PMEM2_MEMWAIT2                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT2[7:0] bits (Common memory 2 wait time) */
+#define  FMC_PMEM2_MEMWAIT2_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_PMEM2_MEMWAIT2_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_PMEM2_MEMWAIT2_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_PMEM2_MEMWAIT2_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_PMEM2_MEMWAIT2_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_PMEM2_MEMWAIT2_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_PMEM2_MEMWAIT2_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_PMEM2_MEMWAIT2_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_PMEM2_MEMHOLD2                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD2[7:0] bits (Common memory 2 hold time) */
+#define  FMC_PMEM2_MEMHOLD2_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_PMEM2_MEMHOLD2_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_PMEM2_MEMHOLD2_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_PMEM2_MEMHOLD2_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FMC_PMEM2_MEMHOLD2_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FMC_PMEM2_MEMHOLD2_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FMC_PMEM2_MEMHOLD2_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FMC_PMEM2_MEMHOLD2_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FMC_PMEM2_MEMHIZ2                  ((uint32_t)0xFF000000)        /*!<MEMHIZ2[7:0] bits (Common memory 2 databus HiZ time) */
+#define  FMC_PMEM2_MEMHIZ2_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_PMEM2_MEMHIZ2_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_PMEM2_MEMHIZ2_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_PMEM2_MEMHIZ2_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FMC_PMEM2_MEMHIZ2_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FMC_PMEM2_MEMHIZ2_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FMC_PMEM2_MEMHIZ2_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FMC_PMEM2_MEMHIZ2_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FMC_PMEM3 register  ******************/
+#define  FMC_PMEM3_MEMSET3                  ((uint32_t)0x000000FF)        /*!<MEMSET3[7:0] bits (Common memory 3 setup time) */
+#define  FMC_PMEM3_MEMSET3_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_PMEM3_MEMSET3_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_PMEM3_MEMSET3_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_PMEM3_MEMSET3_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FMC_PMEM3_MEMSET3_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FMC_PMEM3_MEMSET3_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FMC_PMEM3_MEMSET3_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FMC_PMEM3_MEMSET3_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FMC_PMEM3_MEMWAIT3                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT3[7:0] bits (Common memory 3 wait time) */
+#define  FMC_PMEM3_MEMWAIT3_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_PMEM3_MEMWAIT3_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_PMEM3_MEMWAIT3_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_PMEM3_MEMWAIT3_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_PMEM3_MEMWAIT3_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_PMEM3_MEMWAIT3_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_PMEM3_MEMWAIT3_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_PMEM3_MEMWAIT3_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_PMEM3_MEMHOLD3                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD3[7:0] bits (Common memory 3 hold time) */
+#define  FMC_PMEM3_MEMHOLD3_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_PMEM3_MEMHOLD3_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_PMEM3_MEMHOLD3_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_PMEM3_MEMHOLD3_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FMC_PMEM3_MEMHOLD3_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FMC_PMEM3_MEMHOLD3_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FMC_PMEM3_MEMHOLD3_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FMC_PMEM3_MEMHOLD3_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FMC_PMEM3_MEMHIZ3                  ((uint32_t)0xFF000000)        /*!<MEMHIZ3[7:0] bits (Common memory 3 databus HiZ time) */
+#define  FMC_PMEM3_MEMHIZ3_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_PMEM3_MEMHIZ3_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_PMEM3_MEMHIZ3_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_PMEM3_MEMHIZ3_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FMC_PMEM3_MEMHIZ3_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FMC_PMEM3_MEMHIZ3_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FMC_PMEM3_MEMHIZ3_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FMC_PMEM3_MEMHIZ3_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FMC_PMEM4 register  ******************/
+#define  FMC_PMEM4_MEMSET4                  ((uint32_t)0x000000FF)        /*!<MEMSET4[7:0] bits (Common memory 4 setup time) */
+#define  FMC_PMEM4_MEMSET4_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_PMEM4_MEMSET4_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_PMEM4_MEMSET4_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_PMEM4_MEMSET4_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FMC_PMEM4_MEMSET4_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FMC_PMEM4_MEMSET4_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FMC_PMEM4_MEMSET4_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FMC_PMEM4_MEMSET4_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FMC_PMEM4_MEMWAIT4                 ((uint32_t)0x0000FF00)        /*!<MEMWAIT4[7:0] bits (Common memory 4 wait time) */
+#define  FMC_PMEM4_MEMWAIT4_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_PMEM4_MEMWAIT4_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_PMEM4_MEMWAIT4_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_PMEM4_MEMWAIT4_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_PMEM4_MEMWAIT4_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_PMEM4_MEMWAIT4_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_PMEM4_MEMWAIT4_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_PMEM4_MEMWAIT4_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_PMEM4_MEMHOLD4                 ((uint32_t)0x00FF0000)        /*!<MEMHOLD4[7:0] bits (Common memory 4 hold time) */
+#define  FMC_PMEM4_MEMHOLD4_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_PMEM4_MEMHOLD4_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_PMEM4_MEMHOLD4_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_PMEM4_MEMHOLD4_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FMC_PMEM4_MEMHOLD4_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FMC_PMEM4_MEMHOLD4_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FMC_PMEM4_MEMHOLD4_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FMC_PMEM4_MEMHOLD4_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FMC_PMEM4_MEMHIZ4                  ((uint32_t)0xFF000000)        /*!<MEMHIZ4[7:0] bits (Common memory 4 databus HiZ time) */
+#define  FMC_PMEM4_MEMHIZ4_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_PMEM4_MEMHIZ4_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_PMEM4_MEMHIZ4_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_PMEM4_MEMHIZ4_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FMC_PMEM4_MEMHIZ4_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FMC_PMEM4_MEMHIZ4_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FMC_PMEM4_MEMHIZ4_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FMC_PMEM4_MEMHIZ4_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FMC_PATT2 register  ******************/
+#define  FMC_PATT2_ATTSET2                  ((uint32_t)0x000000FF)        /*!<ATTSET2[7:0] bits (Attribute memory 2 setup time) */
+#define  FMC_PATT2_ATTSET2_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_PATT2_ATTSET2_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_PATT2_ATTSET2_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_PATT2_ATTSET2_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FMC_PATT2_ATTSET2_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FMC_PATT2_ATTSET2_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FMC_PATT2_ATTSET2_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FMC_PATT2_ATTSET2_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FMC_PATT2_ATTWAIT2                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT2[7:0] bits (Attribute memory 2 wait time) */
+#define  FMC_PATT2_ATTWAIT2_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_PATT2_ATTWAIT2_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_PATT2_ATTWAIT2_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_PATT2_ATTWAIT2_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_PATT2_ATTWAIT2_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_PATT2_ATTWAIT2_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_PATT2_ATTWAIT2_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_PATT2_ATTWAIT2_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_PATT2_ATTHOLD2                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD2[7:0] bits (Attribute memory 2 hold time) */
+#define  FMC_PATT2_ATTHOLD2_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_PATT2_ATTHOLD2_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_PATT2_ATTHOLD2_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_PATT2_ATTHOLD2_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FMC_PATT2_ATTHOLD2_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FMC_PATT2_ATTHOLD2_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FMC_PATT2_ATTHOLD2_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FMC_PATT2_ATTHOLD2_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FMC_PATT2_ATTHIZ2                  ((uint32_t)0xFF000000)        /*!<ATTHIZ2[7:0] bits (Attribute memory 2 databus HiZ time) */
+#define  FMC_PATT2_ATTHIZ2_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_PATT2_ATTHIZ2_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_PATT2_ATTHIZ2_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_PATT2_ATTHIZ2_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FMC_PATT2_ATTHIZ2_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FMC_PATT2_ATTHIZ2_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FMC_PATT2_ATTHIZ2_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FMC_PATT2_ATTHIZ2_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FMC_PATT3 register  ******************/
+#define  FMC_PATT3_ATTSET3                  ((uint32_t)0x000000FF)        /*!<ATTSET3[7:0] bits (Attribute memory 3 setup time) */
+#define  FMC_PATT3_ATTSET3_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_PATT3_ATTSET3_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_PATT3_ATTSET3_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_PATT3_ATTSET3_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FMC_PATT3_ATTSET3_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FMC_PATT3_ATTSET3_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FMC_PATT3_ATTSET3_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FMC_PATT3_ATTSET3_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FMC_PATT3_ATTWAIT3                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT3[7:0] bits (Attribute memory 3 wait time) */
+#define  FMC_PATT3_ATTWAIT3_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_PATT3_ATTWAIT3_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_PATT3_ATTWAIT3_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_PATT3_ATTWAIT3_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_PATT3_ATTWAIT3_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_PATT3_ATTWAIT3_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_PATT3_ATTWAIT3_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_PATT3_ATTWAIT3_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_PATT3_ATTHOLD3                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD3[7:0] bits (Attribute memory 3 hold time) */
+#define  FMC_PATT3_ATTHOLD3_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_PATT3_ATTHOLD3_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_PATT3_ATTHOLD3_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_PATT3_ATTHOLD3_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FMC_PATT3_ATTHOLD3_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FMC_PATT3_ATTHOLD3_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FMC_PATT3_ATTHOLD3_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FMC_PATT3_ATTHOLD3_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FMC_PATT3_ATTHIZ3                  ((uint32_t)0xFF000000)        /*!<ATTHIZ3[7:0] bits (Attribute memory 3 databus HiZ time) */
+#define  FMC_PATT3_ATTHIZ3_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_PATT3_ATTHIZ3_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_PATT3_ATTHIZ3_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_PATT3_ATTHIZ3_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FMC_PATT3_ATTHIZ3_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FMC_PATT3_ATTHIZ3_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FMC_PATT3_ATTHIZ3_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FMC_PATT3_ATTHIZ3_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FMC_PATT4 register  ******************/
+#define  FMC_PATT4_ATTSET4                  ((uint32_t)0x000000FF)        /*!<ATTSET4[7:0] bits (Attribute memory 4 setup time) */
+#define  FMC_PATT4_ATTSET4_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_PATT4_ATTSET4_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_PATT4_ATTSET4_2                ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_PATT4_ATTSET4_3                ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FMC_PATT4_ATTSET4_4                ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FMC_PATT4_ATTSET4_5                ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FMC_PATT4_ATTSET4_6                ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FMC_PATT4_ATTSET4_7                ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FMC_PATT4_ATTWAIT4                 ((uint32_t)0x0000FF00)        /*!<ATTWAIT4[7:0] bits (Attribute memory 4 wait time) */
+#define  FMC_PATT4_ATTWAIT4_0               ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_PATT4_ATTWAIT4_1               ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_PATT4_ATTWAIT4_2               ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_PATT4_ATTWAIT4_3               ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_PATT4_ATTWAIT4_4               ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_PATT4_ATTWAIT4_5               ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_PATT4_ATTWAIT4_6               ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_PATT4_ATTWAIT4_7               ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_PATT4_ATTHOLD4                 ((uint32_t)0x00FF0000)        /*!<ATTHOLD4[7:0] bits (Attribute memory 4 hold time) */
+#define  FMC_PATT4_ATTHOLD4_0               ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_PATT4_ATTHOLD4_1               ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_PATT4_ATTHOLD4_2               ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_PATT4_ATTHOLD4_3               ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FMC_PATT4_ATTHOLD4_4               ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FMC_PATT4_ATTHOLD4_5               ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FMC_PATT4_ATTHOLD4_6               ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FMC_PATT4_ATTHOLD4_7               ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FMC_PATT4_ATTHIZ4                  ((uint32_t)0xFF000000)        /*!<ATTHIZ4[7:0] bits (Attribute memory 4 databus HiZ time) */
+#define  FMC_PATT4_ATTHIZ4_0                ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_PATT4_ATTHIZ4_1                ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_PATT4_ATTHIZ4_2                ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_PATT4_ATTHIZ4_3                ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FMC_PATT4_ATTHIZ4_4                ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FMC_PATT4_ATTHIZ4_5                ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FMC_PATT4_ATTHIZ4_6                ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FMC_PATT4_ATTHIZ4_7                ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FMC_PIO4 register  *******************/
+#define  FMC_PIO4_IOSET4                    ((uint32_t)0x000000FF)        /*!<IOSET4[7:0] bits (I/O 4 setup time) */
+#define  FMC_PIO4_IOSET4_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_PIO4_IOSET4_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_PIO4_IOSET4_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_PIO4_IOSET4_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  FMC_PIO4_IOSET4_4                  ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  FMC_PIO4_IOSET4_5                  ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  FMC_PIO4_IOSET4_6                  ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  FMC_PIO4_IOSET4_7                  ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  FMC_PIO4_IOWAIT4                   ((uint32_t)0x0000FF00)        /*!<IOWAIT4[7:0] bits (I/O 4 wait time) */
+#define  FMC_PIO4_IOWAIT4_0                 ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_PIO4_IOWAIT4_1                 ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_PIO4_IOWAIT4_2                 ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_PIO4_IOWAIT4_3                 ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  FMC_PIO4_IOWAIT4_4                 ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  FMC_PIO4_IOWAIT4_5                 ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  FMC_PIO4_IOWAIT4_6                 ((uint32_t)0x00004000)        /*!<Bit 6 */
+#define  FMC_PIO4_IOWAIT4_7                 ((uint32_t)0x00008000)        /*!<Bit 7 */
+
+#define  FMC_PIO4_IOHOLD4                   ((uint32_t)0x00FF0000)        /*!<IOHOLD4[7:0] bits (I/O 4 hold time) */
+#define  FMC_PIO4_IOHOLD4_0                 ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_PIO4_IOHOLD4_1                 ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_PIO4_IOHOLD4_2                 ((uint32_t)0x00040000)        /*!<Bit 2 */
+#define  FMC_PIO4_IOHOLD4_3                 ((uint32_t)0x00080000)        /*!<Bit 3 */
+#define  FMC_PIO4_IOHOLD4_4                 ((uint32_t)0x00100000)        /*!<Bit 4 */
+#define  FMC_PIO4_IOHOLD4_5                 ((uint32_t)0x00200000)        /*!<Bit 5 */
+#define  FMC_PIO4_IOHOLD4_6                 ((uint32_t)0x00400000)        /*!<Bit 6 */
+#define  FMC_PIO4_IOHOLD4_7                 ((uint32_t)0x00800000)        /*!<Bit 7 */
+
+#define  FMC_PIO4_IOHIZ4                    ((uint32_t)0xFF000000)        /*!<IOHIZ4[7:0] bits (I/O 4 databus HiZ time) */
+#define  FMC_PIO4_IOHIZ4_0                  ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_PIO4_IOHIZ4_1                  ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_PIO4_IOHIZ4_2                  ((uint32_t)0x04000000)        /*!<Bit 2 */
+#define  FMC_PIO4_IOHIZ4_3                  ((uint32_t)0x08000000)        /*!<Bit 3 */
+#define  FMC_PIO4_IOHIZ4_4                  ((uint32_t)0x10000000)        /*!<Bit 4 */
+#define  FMC_PIO4_IOHIZ4_5                  ((uint32_t)0x20000000)        /*!<Bit 5 */
+#define  FMC_PIO4_IOHIZ4_6                  ((uint32_t)0x40000000)        /*!<Bit 6 */
+#define  FMC_PIO4_IOHIZ4_7                  ((uint32_t)0x80000000)        /*!<Bit 7 */
+
+/******************  Bit definition for FMC_ECCR2 register  ******************/
+#define  FMC_ECCR2_ECC2                     ((uint32_t)0xFFFFFFFF)        /*!<ECC result */
+
+/******************  Bit definition for FMC_ECCR3 register  ******************/
+#define  FMC_ECCR3_ECC3                     ((uint32_t)0xFFFFFFFF)        /*!<ECC result */
+
+/******************  Bit definition for FMC_SDCR1 register  ******************/
+#define  FMC_SDCR1_NC                       ((uint32_t)0x00000003)        /*!<NC[1:0] bits (Number of column bits) */
+#define  FMC_SDCR1_NC_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_SDCR1_NC_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+
+#define  FMC_SDCR1_NR                       ((uint32_t)0x0000000C)        /*!<NR[1:0] bits (Number of row bits) */
+#define  FMC_SDCR1_NR_0                     ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FMC_SDCR1_NR_1                     ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FMC_SDCR1_MWID                     ((uint32_t)0x00000030)        /*!<NR[1:0] bits (Number of row bits) */
+#define  FMC_SDCR1_MWID_0                   ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_SDCR1_MWID_1                   ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_SDCR1_NB                       ((uint32_t)0x00000040)        /*!<Number of internal bank */
+
+#define  FMC_SDCR1_CAS                      ((uint32_t)0x00000180)        /*!<CAS[1:0] bits (CAS latency) */
+#define  FMC_SDCR1_CAS_0                    ((uint32_t)0x00000080)        /*!<Bit 0 */
+#define  FMC_SDCR1_CAS_1                    ((uint32_t)0x00000100)        /*!<Bit 1 */
+
+#define  FMC_SDCR1_WP                       ((uint32_t)0x00000200)        /*!<Write protection */
+
+#define  FMC_SDCR1_SDCLK                    ((uint32_t)0x00000C00)        /*!<SDRAM clock configuration */
+#define  FMC_SDCR1_SDCLK_0                  ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  FMC_SDCR1_SDCLK_1                  ((uint32_t)0x00000800)        /*!<Bit 1 */
+
+#define  FMC_SDCR1_RBURST                   ((uint32_t)0x00001000)        /*!<Read burst */
+
+#define  FMC_SDCR1_RPIPE                    ((uint32_t)0x00006000)        /*!<Write protection */
+#define  FMC_SDCR1_RPIPE_0                  ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FMC_SDCR1_RPIPE_1                  ((uint32_t)0x00004000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_SDCR2 register  ******************/
+#define  FMC_SDCR2_NC                       ((uint32_t)0x00000003)        /*!<NC[1:0] bits (Number of column bits) */
+#define  FMC_SDCR2_NC_0                     ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_SDCR2_NC_1                     ((uint32_t)0x00000002)        /*!<Bit 1 */
+
+#define  FMC_SDCR2_NR                       ((uint32_t)0x0000000C)        /*!<NR[1:0] bits (Number of row bits) */
+#define  FMC_SDCR2_NR_0                     ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  FMC_SDCR2_NR_1                     ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  FMC_SDCR2_MWID                     ((uint32_t)0x00000030)        /*!<NR[1:0] bits (Number of row bits) */
+#define  FMC_SDCR2_MWID_0                   ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_SDCR2_MWID_1                   ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+#define  FMC_SDCR2_NB                       ((uint32_t)0x00000040)        /*!<Number of internal bank */
+
+#define  FMC_SDCR2_CAS                      ((uint32_t)0x00000180)        /*!<CAS[1:0] bits (CAS latency) */
+#define  FMC_SDCR2_CAS_0                    ((uint32_t)0x00000080)        /*!<Bit 0 */
+#define  FMC_SDCR2_CAS_1                    ((uint32_t)0x00000100)        /*!<Bit 1 */
+
+#define  FMC_SDCR2_WP                       ((uint32_t)0x00000200)        /*!<Write protection */
+
+#define  FMC_SDCR2_SDCLK                    ((uint32_t)0x00000C00)        /*!<SDCLK[1:0] (SDRAM clock configuration) */
+#define  FMC_SDCR2_SDCLK_0                  ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  FMC_SDCR2_SDCLK_1                  ((uint32_t)0x00000800)        /*!<Bit 1 */
+
+#define  FMC_SDCR2_RBURST                   ((uint32_t)0x00001000)        /*!<Read burst */
+
+#define  FMC_SDCR2_RPIPE                    ((uint32_t)0x00006000)        /*!<RPIPE[1:0](Read pipe) */
+#define  FMC_SDCR2_RPIPE_0                  ((uint32_t)0x00002000)        /*!<Bit 0 */
+#define  FMC_SDCR2_RPIPE_1                  ((uint32_t)0x00004000)        /*!<Bit 1 */
+
+/******************  Bit definition for FMC_SDTR1 register  ******************/
+#define  FMC_SDTR1_TMRD                     ((uint32_t)0x0000000F)        /*!<TMRD[3:0] bits (Load mode register to active) */
+#define  FMC_SDTR1_TMRD_0                   ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_SDTR1_TMRD_1                   ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_SDTR1_TMRD_2                   ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_SDTR1_TMRD_3                   ((uint32_t)0x00000008)        /*!<Bit 3 */
+                                            
+#define  FMC_SDTR1_TXSR                     ((uint32_t)0x000000F0)        /*!<TXSR[3:0] bits (Exit self refresh) */
+#define  FMC_SDTR1_TXSR_0                   ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_SDTR1_TXSR_1                   ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_SDTR1_TXSR_2                   ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_SDTR1_TXSR_3                   ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_SDTR1_TRAS                     ((uint32_t)0x00000F00)        /*!<TRAS[3:0] bits (Self refresh time) */
+#define  FMC_SDTR1_TRAS_0                   ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_SDTR1_TRAS_1                   ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_SDTR1_TRAS_2                   ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_SDTR1_TRAS_3                   ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FMC_SDTR1_TRC                      ((uint32_t)0x0000F000)        /*!<TRC[2:0] bits (Row cycle delay) */
+#define  FMC_SDTR1_TRC_0                    ((uint32_t)0x00001000)        /*!<Bit 0 */
+#define  FMC_SDTR1_TRC_1                    ((uint32_t)0x00002000)        /*!<Bit 1 */
+#define  FMC_SDTR1_TRC_2                    ((uint32_t)0x00004000)        /*!<Bit 2 */
+
+#define  FMC_SDTR1_TWR                      ((uint32_t)0x000F0000)        /*!<TRC[2:0] bits (Write recovery delay) */
+#define  FMC_SDTR1_TWR_0                    ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_SDTR1_TWR_1                    ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_SDTR1_TWR_2                    ((uint32_t)0x00040000)        /*!<Bit 2 */
+
+#define  FMC_SDTR1_TRP                      ((uint32_t)0x00F00000)        /*!<TRP[2:0] bits (Row precharge delay) */
+#define  FMC_SDTR1_TRP_0                    ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_SDTR1_TRP_1                    ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_SDTR1_TRP_2                    ((uint32_t)0x00400000)        /*!<Bit 2 */
+
+#define  FMC_SDTR1_TRCD                     ((uint32_t)0x0F000000)        /*!<TRP[2:0] bits (Row to column delay) */
+#define  FMC_SDTR1_TRCD_0                   ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_SDTR1_TRCD_1                   ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_SDTR1_TRCD_2                   ((uint32_t)0x04000000)        /*!<Bit 2 */
+
+/******************  Bit definition for FMC_SDTR2 register  ******************/
+#define  FMC_SDTR2_TMRD                     ((uint32_t)0x0000000F)        /*!<TMRD[3:0] bits (Load mode register to active) */
+#define  FMC_SDTR2_TMRD_0                   ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_SDTR2_TMRD_1                   ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_SDTR2_TMRD_2                   ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  FMC_SDTR2_TMRD_3                   ((uint32_t)0x00000008)        /*!<Bit 3 */
+                                            
+#define  FMC_SDTR2_TXSR                     ((uint32_t)0x000000F0)        /*!<TXSR[3:0] bits (Exit self refresh) */
+#define  FMC_SDTR2_TXSR_0                   ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  FMC_SDTR2_TXSR_1                   ((uint32_t)0x00000020)        /*!<Bit 1 */
+#define  FMC_SDTR2_TXSR_2                   ((uint32_t)0x00000040)        /*!<Bit 2 */
+#define  FMC_SDTR2_TXSR_3                   ((uint32_t)0x00000080)        /*!<Bit 3 */
+
+#define  FMC_SDTR2_TRAS                     ((uint32_t)0x00000F00)        /*!<TRAS[3:0] bits (Self refresh time) */
+#define  FMC_SDTR2_TRAS_0                   ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  FMC_SDTR2_TRAS_1                   ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  FMC_SDTR2_TRAS_2                   ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  FMC_SDTR2_TRAS_3                   ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  FMC_SDTR2_TRC                      ((uint32_t)0x0000F000)        /*!<TRC[2:0] bits (Row cycle delay) */
+#define  FMC_SDTR2_TRC_0                    ((uint32_t)0x00001000)        /*!<Bit 0 */
+#define  FMC_SDTR2_TRC_1                    ((uint32_t)0x00002000)        /*!<Bit 1 */
+#define  FMC_SDTR2_TRC_2                    ((uint32_t)0x00004000)        /*!<Bit 2 */
+
+#define  FMC_SDTR2_TWR                      ((uint32_t)0x000F0000)        /*!<TRC[2:0] bits (Write recovery delay) */
+#define  FMC_SDTR2_TWR_0                    ((uint32_t)0x00010000)        /*!<Bit 0 */
+#define  FMC_SDTR2_TWR_1                    ((uint32_t)0x00020000)        /*!<Bit 1 */
+#define  FMC_SDTR2_TWR_2                    ((uint32_t)0x00040000)        /*!<Bit 2 */
+
+#define  FMC_SDTR2_TRP                      ((uint32_t)0x00F00000)        /*!<TRP[2:0] bits (Row precharge delay) */
+#define  FMC_SDTR2_TRP_0                    ((uint32_t)0x00100000)        /*!<Bit 0 */
+#define  FMC_SDTR2_TRP_1                    ((uint32_t)0x00200000)        /*!<Bit 1 */
+#define  FMC_SDTR2_TRP_2                    ((uint32_t)0x00400000)        /*!<Bit 2 */
+
+#define  FMC_SDTR2_TRCD                     ((uint32_t)0x0F000000)        /*!<TRP[2:0] bits (Row to column delay) */
+#define  FMC_SDTR2_TRCD_0                   ((uint32_t)0x01000000)        /*!<Bit 0 */
+#define  FMC_SDTR2_TRCD_1                   ((uint32_t)0x02000000)        /*!<Bit 1 */
+#define  FMC_SDTR2_TRCD_2                   ((uint32_t)0x04000000)        /*!<Bit 2 */
+
+/******************  Bit definition for FMC_SDCMR register  ******************/
+#define  FMC_SDCMR_MODE                     ((uint32_t)0x00000007)        /*!<MODE[2:0] bits (Command mode) */
+#define  FMC_SDCMR_MODE_0                   ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  FMC_SDCMR_MODE_1                   ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  FMC_SDCMR_MODE_2                   ((uint32_t)0x00000003)        /*!<Bit 2 */
+                                            
+#define  FMC_SDCMR_CTB2                     ((uint32_t)0x00000008)        /*!<Command target 2 */
+
+#define  FMC_SDCMR_CTB1                     ((uint32_t)0x00000010)        /*!<Command target 1 */
+
+#define  FMC_SDCMR_NRFS                     ((uint32_t)0x000001E0)        /*!<NRFS[3:0] bits (Number of auto-refresh) */
+#define  FMC_SDCMR_NRFS_0                   ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  FMC_SDCMR_NRFS_1                   ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  FMC_SDCMR_NRFS_2                   ((uint32_t)0x00000080)        /*!<Bit 2 */
+#define  FMC_SDCMR_NRFS_3                   ((uint32_t)0x00000100)        /*!<Bit 3 */
+
+#define  FMC_SDCMR_MRD                      ((uint32_t)0x003FFE00)        /*!<MRD[12:0] bits (Mode register definition) */
+
+/******************  Bit definition for FMC_SDRTR register  ******************/
+#define  FMC_SDRTR_CRE                      ((uint32_t)0x00000001)        /*!<Clear refresh error flag */
+
+#define  FMC_SDRTR_COUNT                    ((uint32_t)0x00003FFE)        /*!<COUNT[12:0] bits (Refresh timer count) */
+
+#define  FMC_SDRTR_REIE                     ((uint32_t)0x00004000)        /*!<RES interupt enable */
+
+/******************  Bit definition for FMC_SDSR register  ******************/
+#define  FMC_SDSR_RE                        ((uint32_t)0x00000001)        /*!<Refresh error flag */
+
+#define  FMC_SDSR_MODES1                    ((uint32_t)0x00000006)        /*!<MODES1[1:0]bits (Status mode for bank 1) */
+#define  FMC_SDSR_MODES1_0                  ((uint32_t)0x00000002)        /*!<Bit 0 */
+#define  FMC_SDSR_MODES1_1                  ((uint32_t)0x00000004)        /*!<Bit 1 */
+
+#define  FMC_SDSR_MODES2                    ((uint32_t)0x00000018)        /*!<MODES2[1:0]bits (Status mode for bank 2) */
+#define  FMC_SDSR_MODES2_0                  ((uint32_t)0x00000008)        /*!<Bit 0 */
+#define  FMC_SDSR_MODES2_1                  ((uint32_t)0x00000010)        /*!<Bit 1 */
+
+#define  FMC_SDSR_BUSY                      ((uint32_t)0x00000020)        /*!<Busy status */
+
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+/******************************************************************************/
+/*                                                                            */
+/*                            General Purpose I/O                             */
+/*                                                                            */
+/******************************************************************************/
+/******************  Bits definition for GPIO_MODER register  *****************/
+#define GPIO_MODER_MODER0                    ((uint32_t)0x00000003)
+#define GPIO_MODER_MODER0_0                  ((uint32_t)0x00000001)
+#define GPIO_MODER_MODER0_1                  ((uint32_t)0x00000002)
+
+#define GPIO_MODER_MODER1                    ((uint32_t)0x0000000C)
+#define GPIO_MODER_MODER1_0                  ((uint32_t)0x00000004)
+#define GPIO_MODER_MODER1_1                  ((uint32_t)0x00000008)
+
+#define GPIO_MODER_MODER2                    ((uint32_t)0x00000030)
+#define GPIO_MODER_MODER2_0                  ((uint32_t)0x00000010)
+#define GPIO_MODER_MODER2_1                  ((uint32_t)0x00000020)
+
+#define GPIO_MODER_MODER3                    ((uint32_t)0x000000C0)
+#define GPIO_MODER_MODER3_0                  ((uint32_t)0x00000040)
+#define GPIO_MODER_MODER3_1                  ((uint32_t)0x00000080)
+
+#define GPIO_MODER_MODER4                    ((uint32_t)0x00000300)
+#define GPIO_MODER_MODER4_0                  ((uint32_t)0x00000100)
+#define GPIO_MODER_MODER4_1                  ((uint32_t)0x00000200)
+
+#define GPIO_MODER_MODER5                    ((uint32_t)0x00000C00)
+#define GPIO_MODER_MODER5_0                  ((uint32_t)0x00000400)
+#define GPIO_MODER_MODER5_1                  ((uint32_t)0x00000800)
+
+#define GPIO_MODER_MODER6                    ((uint32_t)0x00003000)
+#define GPIO_MODER_MODER6_0                  ((uint32_t)0x00001000)
+#define GPIO_MODER_MODER6_1                  ((uint32_t)0x00002000)
+
+#define GPIO_MODER_MODER7                    ((uint32_t)0x0000C000)
+#define GPIO_MODER_MODER7_0                  ((uint32_t)0x00004000)
+#define GPIO_MODER_MODER7_1                  ((uint32_t)0x00008000)
+
+#define GPIO_MODER_MODER8                    ((uint32_t)0x00030000)
+#define GPIO_MODER_MODER8_0                  ((uint32_t)0x00010000)
+#define GPIO_MODER_MODER8_1                  ((uint32_t)0x00020000)
+
+#define GPIO_MODER_MODER9                    ((uint32_t)0x000C0000)
+#define GPIO_MODER_MODER9_0                  ((uint32_t)0x00040000)
+#define GPIO_MODER_MODER9_1                  ((uint32_t)0x00080000)
+
+#define GPIO_MODER_MODER10                   ((uint32_t)0x00300000)
+#define GPIO_MODER_MODER10_0                 ((uint32_t)0x00100000)
+#define GPIO_MODER_MODER10_1                 ((uint32_t)0x00200000)
+
+#define GPIO_MODER_MODER11                   ((uint32_t)0x00C00000)
+#define GPIO_MODER_MODER11_0                 ((uint32_t)0x00400000)
+#define GPIO_MODER_MODER11_1                 ((uint32_t)0x00800000)
+
+#define GPIO_MODER_MODER12                   ((uint32_t)0x03000000)
+#define GPIO_MODER_MODER12_0                 ((uint32_t)0x01000000)
+#define GPIO_MODER_MODER12_1                 ((uint32_t)0x02000000)
+
+#define GPIO_MODER_MODER13                   ((uint32_t)0x0C000000)
+#define GPIO_MODER_MODER13_0                 ((uint32_t)0x04000000)
+#define GPIO_MODER_MODER13_1                 ((uint32_t)0x08000000)
+
+#define GPIO_MODER_MODER14                   ((uint32_t)0x30000000)
+#define GPIO_MODER_MODER14_0                 ((uint32_t)0x10000000)
+#define GPIO_MODER_MODER14_1                 ((uint32_t)0x20000000)
+
+#define GPIO_MODER_MODER15                   ((uint32_t)0xC0000000)
+#define GPIO_MODER_MODER15_0                 ((uint32_t)0x40000000)
+#define GPIO_MODER_MODER15_1                 ((uint32_t)0x80000000)
+
+/******************  Bits definition for GPIO_OTYPER register  ****************/
+#define GPIO_OTYPER_OT_0                     ((uint32_t)0x00000001)
+#define GPIO_OTYPER_OT_1                     ((uint32_t)0x00000002)
+#define GPIO_OTYPER_OT_2                     ((uint32_t)0x00000004)
+#define GPIO_OTYPER_OT_3                     ((uint32_t)0x00000008)
+#define GPIO_OTYPER_OT_4                     ((uint32_t)0x00000010)
+#define GPIO_OTYPER_OT_5                     ((uint32_t)0x00000020)
+#define GPIO_OTYPER_OT_6                     ((uint32_t)0x00000040)
+#define GPIO_OTYPER_OT_7                     ((uint32_t)0x00000080)
+#define GPIO_OTYPER_OT_8                     ((uint32_t)0x00000100)
+#define GPIO_OTYPER_OT_9                     ((uint32_t)0x00000200)
+#define GPIO_OTYPER_OT_10                    ((uint32_t)0x00000400)
+#define GPIO_OTYPER_OT_11                    ((uint32_t)0x00000800)
+#define GPIO_OTYPER_OT_12                    ((uint32_t)0x00001000)
+#define GPIO_OTYPER_OT_13                    ((uint32_t)0x00002000)
+#define GPIO_OTYPER_OT_14                    ((uint32_t)0x00004000)
+#define GPIO_OTYPER_OT_15                    ((uint32_t)0x00008000)
+
+/******************  Bits definition for GPIO_OSPEEDR register  ***************/
+#define GPIO_OSPEEDER_OSPEEDR0               ((uint32_t)0x00000003)
+#define GPIO_OSPEEDER_OSPEEDR0_0             ((uint32_t)0x00000001)
+#define GPIO_OSPEEDER_OSPEEDR0_1             ((uint32_t)0x00000002)
+
+#define GPIO_OSPEEDER_OSPEEDR1               ((uint32_t)0x0000000C)
+#define GPIO_OSPEEDER_OSPEEDR1_0             ((uint32_t)0x00000004)
+#define GPIO_OSPEEDER_OSPEEDR1_1             ((uint32_t)0x00000008)
+
+#define GPIO_OSPEEDER_OSPEEDR2               ((uint32_t)0x00000030)
+#define GPIO_OSPEEDER_OSPEEDR2_0             ((uint32_t)0x00000010)
+#define GPIO_OSPEEDER_OSPEEDR2_1             ((uint32_t)0x00000020)
+
+#define GPIO_OSPEEDER_OSPEEDR3               ((uint32_t)0x000000C0)
+#define GPIO_OSPEEDER_OSPEEDR3_0             ((uint32_t)0x00000040)
+#define GPIO_OSPEEDER_OSPEEDR3_1             ((uint32_t)0x00000080)
+
+#define GPIO_OSPEEDER_OSPEEDR4               ((uint32_t)0x00000300)
+#define GPIO_OSPEEDER_OSPEEDR4_0             ((uint32_t)0x00000100)
+#define GPIO_OSPEEDER_OSPEEDR4_1             ((uint32_t)0x00000200)
+
+#define GPIO_OSPEEDER_OSPEEDR5               ((uint32_t)0x00000C00)
+#define GPIO_OSPEEDER_OSPEEDR5_0             ((uint32_t)0x00000400)
+#define GPIO_OSPEEDER_OSPEEDR5_1             ((uint32_t)0x00000800)
+
+#define GPIO_OSPEEDER_OSPEEDR6               ((uint32_t)0x00003000)
+#define GPIO_OSPEEDER_OSPEEDR6_0             ((uint32_t)0x00001000)
+#define GPIO_OSPEEDER_OSPEEDR6_1             ((uint32_t)0x00002000)
+
+#define GPIO_OSPEEDER_OSPEEDR7               ((uint32_t)0x0000C000)
+#define GPIO_OSPEEDER_OSPEEDR7_0             ((uint32_t)0x00004000)
+#define GPIO_OSPEEDER_OSPEEDR7_1             ((uint32_t)0x00008000)
+
+#define GPIO_OSPEEDER_OSPEEDR8               ((uint32_t)0x00030000)
+#define GPIO_OSPEEDER_OSPEEDR8_0             ((uint32_t)0x00010000)
+#define GPIO_OSPEEDER_OSPEEDR8_1             ((uint32_t)0x00020000)
+
+#define GPIO_OSPEEDER_OSPEEDR9               ((uint32_t)0x000C0000)
+#define GPIO_OSPEEDER_OSPEEDR9_0             ((uint32_t)0x00040000)
+#define GPIO_OSPEEDER_OSPEEDR9_1             ((uint32_t)0x00080000)
+
+#define GPIO_OSPEEDER_OSPEEDR10              ((uint32_t)0x00300000)
+#define GPIO_OSPEEDER_OSPEEDR10_0            ((uint32_t)0x00100000)
+#define GPIO_OSPEEDER_OSPEEDR10_1            ((uint32_t)0x00200000)
+
+#define GPIO_OSPEEDER_OSPEEDR11              ((uint32_t)0x00C00000)
+#define GPIO_OSPEEDER_OSPEEDR11_0            ((uint32_t)0x00400000)
+#define GPIO_OSPEEDER_OSPEEDR11_1            ((uint32_t)0x00800000)
+
+#define GPIO_OSPEEDER_OSPEEDR12              ((uint32_t)0x03000000)
+#define GPIO_OSPEEDER_OSPEEDR12_0            ((uint32_t)0x01000000)
+#define GPIO_OSPEEDER_OSPEEDR12_1            ((uint32_t)0x02000000)
+
+#define GPIO_OSPEEDER_OSPEEDR13              ((uint32_t)0x0C000000)
+#define GPIO_OSPEEDER_OSPEEDR13_0            ((uint32_t)0x04000000)
+#define GPIO_OSPEEDER_OSPEEDR13_1            ((uint32_t)0x08000000)
+
+#define GPIO_OSPEEDER_OSPEEDR14              ((uint32_t)0x30000000)
+#define GPIO_OSPEEDER_OSPEEDR14_0            ((uint32_t)0x10000000)
+#define GPIO_OSPEEDER_OSPEEDR14_1            ((uint32_t)0x20000000)
+
+#define GPIO_OSPEEDER_OSPEEDR15              ((uint32_t)0xC0000000)
+#define GPIO_OSPEEDER_OSPEEDR15_0            ((uint32_t)0x40000000)
+#define GPIO_OSPEEDER_OSPEEDR15_1            ((uint32_t)0x80000000)
+
+/******************  Bits definition for GPIO_PUPDR register  *****************/
+#define GPIO_PUPDR_PUPDR0                    ((uint32_t)0x00000003)
+#define GPIO_PUPDR_PUPDR0_0                  ((uint32_t)0x00000001)
+#define GPIO_PUPDR_PUPDR0_1                  ((uint32_t)0x00000002)
+
+#define GPIO_PUPDR_PUPDR1                    ((uint32_t)0x0000000C)
+#define GPIO_PUPDR_PUPDR1_0                  ((uint32_t)0x00000004)
+#define GPIO_PUPDR_PUPDR1_1                  ((uint32_t)0x00000008)
+
+#define GPIO_PUPDR_PUPDR2                    ((uint32_t)0x00000030)
+#define GPIO_PUPDR_PUPDR2_0                  ((uint32_t)0x00000010)
+#define GPIO_PUPDR_PUPDR2_1                  ((uint32_t)0x00000020)
+
+#define GPIO_PUPDR_PUPDR3                    ((uint32_t)0x000000C0)
+#define GPIO_PUPDR_PUPDR3_0                  ((uint32_t)0x00000040)
+#define GPIO_PUPDR_PUPDR3_1                  ((uint32_t)0x00000080)
+
+#define GPIO_PUPDR_PUPDR4                    ((uint32_t)0x00000300)
+#define GPIO_PUPDR_PUPDR4_0                  ((uint32_t)0x00000100)
+#define GPIO_PUPDR_PUPDR4_1                  ((uint32_t)0x00000200)
+
+#define GPIO_PUPDR_PUPDR5                    ((uint32_t)0x00000C00)
+#define GPIO_PUPDR_PUPDR5_0                  ((uint32_t)0x00000400)
+#define GPIO_PUPDR_PUPDR5_1                  ((uint32_t)0x00000800)
+
+#define GPIO_PUPDR_PUPDR6                    ((uint32_t)0x00003000)
+#define GPIO_PUPDR_PUPDR6_0                  ((uint32_t)0x00001000)
+#define GPIO_PUPDR_PUPDR6_1                  ((uint32_t)0x00002000)
+
+#define GPIO_PUPDR_PUPDR7                    ((uint32_t)0x0000C000)
+#define GPIO_PUPDR_PUPDR7_0                  ((uint32_t)0x00004000)
+#define GPIO_PUPDR_PUPDR7_1                  ((uint32_t)0x00008000)
+
+#define GPIO_PUPDR_PUPDR8                    ((uint32_t)0x00030000)
+#define GPIO_PUPDR_PUPDR8_0                  ((uint32_t)0x00010000)
+#define GPIO_PUPDR_PUPDR8_1                  ((uint32_t)0x00020000)
+
+#define GPIO_PUPDR_PUPDR9                    ((uint32_t)0x000C0000)
+#define GPIO_PUPDR_PUPDR9_0                  ((uint32_t)0x00040000)
+#define GPIO_PUPDR_PUPDR9_1                  ((uint32_t)0x00080000)
+
+#define GPIO_PUPDR_PUPDR10                   ((uint32_t)0x00300000)
+#define GPIO_PUPDR_PUPDR10_0                 ((uint32_t)0x00100000)
+#define GPIO_PUPDR_PUPDR10_1                 ((uint32_t)0x00200000)
+
+#define GPIO_PUPDR_PUPDR11                   ((uint32_t)0x00C00000)
+#define GPIO_PUPDR_PUPDR11_0                 ((uint32_t)0x00400000)
+#define GPIO_PUPDR_PUPDR11_1                 ((uint32_t)0x00800000)
+
+#define GPIO_PUPDR_PUPDR12                   ((uint32_t)0x03000000)
+#define GPIO_PUPDR_PUPDR12_0                 ((uint32_t)0x01000000)
+#define GPIO_PUPDR_PUPDR12_1                 ((uint32_t)0x02000000)
+
+#define GPIO_PUPDR_PUPDR13                   ((uint32_t)0x0C000000)
+#define GPIO_PUPDR_PUPDR13_0                 ((uint32_t)0x04000000)
+#define GPIO_PUPDR_PUPDR13_1                 ((uint32_t)0x08000000)
+
+#define GPIO_PUPDR_PUPDR14                   ((uint32_t)0x30000000)
+#define GPIO_PUPDR_PUPDR14_0                 ((uint32_t)0x10000000)
+#define GPIO_PUPDR_PUPDR14_1                 ((uint32_t)0x20000000)
+
+#define GPIO_PUPDR_PUPDR15                   ((uint32_t)0xC0000000)
+#define GPIO_PUPDR_PUPDR15_0                 ((uint32_t)0x40000000)
+#define GPIO_PUPDR_PUPDR15_1                 ((uint32_t)0x80000000)
+
+/******************  Bits definition for GPIO_IDR register  *******************/
+#define GPIO_IDR_IDR_0                       ((uint32_t)0x00000001)
+#define GPIO_IDR_IDR_1                       ((uint32_t)0x00000002)
+#define GPIO_IDR_IDR_2                       ((uint32_t)0x00000004)
+#define GPIO_IDR_IDR_3                       ((uint32_t)0x00000008)
+#define GPIO_IDR_IDR_4                       ((uint32_t)0x00000010)
+#define GPIO_IDR_IDR_5                       ((uint32_t)0x00000020)
+#define GPIO_IDR_IDR_6                       ((uint32_t)0x00000040)
+#define GPIO_IDR_IDR_7                       ((uint32_t)0x00000080)
+#define GPIO_IDR_IDR_8                       ((uint32_t)0x00000100)
+#define GPIO_IDR_IDR_9                       ((uint32_t)0x00000200)
+#define GPIO_IDR_IDR_10                      ((uint32_t)0x00000400)
+#define GPIO_IDR_IDR_11                      ((uint32_t)0x00000800)
+#define GPIO_IDR_IDR_12                      ((uint32_t)0x00001000)
+#define GPIO_IDR_IDR_13                      ((uint32_t)0x00002000)
+#define GPIO_IDR_IDR_14                      ((uint32_t)0x00004000)
+#define GPIO_IDR_IDR_15                      ((uint32_t)0x00008000)
+/* Old GPIO_IDR register bits definition, maintained for legacy purpose */
+#define GPIO_OTYPER_IDR_0                    GPIO_IDR_IDR_0
+#define GPIO_OTYPER_IDR_1                    GPIO_IDR_IDR_1
+#define GPIO_OTYPER_IDR_2                    GPIO_IDR_IDR_2
+#define GPIO_OTYPER_IDR_3                    GPIO_IDR_IDR_3
+#define GPIO_OTYPER_IDR_4                    GPIO_IDR_IDR_4
+#define GPIO_OTYPER_IDR_5                    GPIO_IDR_IDR_5
+#define GPIO_OTYPER_IDR_6                    GPIO_IDR_IDR_6
+#define GPIO_OTYPER_IDR_7                    GPIO_IDR_IDR_7
+#define GPIO_OTYPER_IDR_8                    GPIO_IDR_IDR_8
+#define GPIO_OTYPER_IDR_9                    GPIO_IDR_IDR_9
+#define GPIO_OTYPER_IDR_10                   GPIO_IDR_IDR_10
+#define GPIO_OTYPER_IDR_11                   GPIO_IDR_IDR_11
+#define GPIO_OTYPER_IDR_12                   GPIO_IDR_IDR_12
+#define GPIO_OTYPER_IDR_13                   GPIO_IDR_IDR_13
+#define GPIO_OTYPER_IDR_14                   GPIO_IDR_IDR_14
+#define GPIO_OTYPER_IDR_15                   GPIO_IDR_IDR_15
+
+/******************  Bits definition for GPIO_ODR register  *******************/
+#define GPIO_ODR_ODR_0                       ((uint32_t)0x00000001)
+#define GPIO_ODR_ODR_1                       ((uint32_t)0x00000002)
+#define GPIO_ODR_ODR_2                       ((uint32_t)0x00000004)
+#define GPIO_ODR_ODR_3                       ((uint32_t)0x00000008)
+#define GPIO_ODR_ODR_4                       ((uint32_t)0x00000010)
+#define GPIO_ODR_ODR_5                       ((uint32_t)0x00000020)
+#define GPIO_ODR_ODR_6                       ((uint32_t)0x00000040)
+#define GPIO_ODR_ODR_7                       ((uint32_t)0x00000080)
+#define GPIO_ODR_ODR_8                       ((uint32_t)0x00000100)
+#define GPIO_ODR_ODR_9                       ((uint32_t)0x00000200)
+#define GPIO_ODR_ODR_10                      ((uint32_t)0x00000400)
+#define GPIO_ODR_ODR_11                      ((uint32_t)0x00000800)
+#define GPIO_ODR_ODR_12                      ((uint32_t)0x00001000)
+#define GPIO_ODR_ODR_13                      ((uint32_t)0x00002000)
+#define GPIO_ODR_ODR_14                      ((uint32_t)0x00004000)
+#define GPIO_ODR_ODR_15                      ((uint32_t)0x00008000)
+/* Old GPIO_ODR register bits definition, maintained for legacy purpose */
+#define GPIO_OTYPER_ODR_0                    GPIO_ODR_ODR_0
+#define GPIO_OTYPER_ODR_1                    GPIO_ODR_ODR_1
+#define GPIO_OTYPER_ODR_2                    GPIO_ODR_ODR_2
+#define GPIO_OTYPER_ODR_3                    GPIO_ODR_ODR_3
+#define GPIO_OTYPER_ODR_4                    GPIO_ODR_ODR_4
+#define GPIO_OTYPER_ODR_5                    GPIO_ODR_ODR_5
+#define GPIO_OTYPER_ODR_6                    GPIO_ODR_ODR_6
+#define GPIO_OTYPER_ODR_7                    GPIO_ODR_ODR_7
+#define GPIO_OTYPER_ODR_8                    GPIO_ODR_ODR_8
+#define GPIO_OTYPER_ODR_9                    GPIO_ODR_ODR_9
+#define GPIO_OTYPER_ODR_10                   GPIO_ODR_ODR_10
+#define GPIO_OTYPER_ODR_11                   GPIO_ODR_ODR_11
+#define GPIO_OTYPER_ODR_12                   GPIO_ODR_ODR_12
+#define GPIO_OTYPER_ODR_13                   GPIO_ODR_ODR_13
+#define GPIO_OTYPER_ODR_14                   GPIO_ODR_ODR_14
+#define GPIO_OTYPER_ODR_15                   GPIO_ODR_ODR_15
+
+/******************  Bits definition for GPIO_BSRR register  ******************/
+#define GPIO_BSRR_BS_0                       ((uint32_t)0x00000001)
+#define GPIO_BSRR_BS_1                       ((uint32_t)0x00000002)
+#define GPIO_BSRR_BS_2                       ((uint32_t)0x00000004)
+#define GPIO_BSRR_BS_3                       ((uint32_t)0x00000008)
+#define GPIO_BSRR_BS_4                       ((uint32_t)0x00000010)
+#define GPIO_BSRR_BS_5                       ((uint32_t)0x00000020)
+#define GPIO_BSRR_BS_6                       ((uint32_t)0x00000040)
+#define GPIO_BSRR_BS_7                       ((uint32_t)0x00000080)
+#define GPIO_BSRR_BS_8                       ((uint32_t)0x00000100)
+#define GPIO_BSRR_BS_9                       ((uint32_t)0x00000200)
+#define GPIO_BSRR_BS_10                      ((uint32_t)0x00000400)
+#define GPIO_BSRR_BS_11                      ((uint32_t)0x00000800)
+#define GPIO_BSRR_BS_12                      ((uint32_t)0x00001000)
+#define GPIO_BSRR_BS_13                      ((uint32_t)0x00002000)
+#define GPIO_BSRR_BS_14                      ((uint32_t)0x00004000)
+#define GPIO_BSRR_BS_15                      ((uint32_t)0x00008000)
+#define GPIO_BSRR_BR_0                       ((uint32_t)0x00010000)
+#define GPIO_BSRR_BR_1                       ((uint32_t)0x00020000)
+#define GPIO_BSRR_BR_2                       ((uint32_t)0x00040000)
+#define GPIO_BSRR_BR_3                       ((uint32_t)0x00080000)
+#define GPIO_BSRR_BR_4                       ((uint32_t)0x00100000)
+#define GPIO_BSRR_BR_5                       ((uint32_t)0x00200000)
+#define GPIO_BSRR_BR_6                       ((uint32_t)0x00400000)
+#define GPIO_BSRR_BR_7                       ((uint32_t)0x00800000)
+#define GPIO_BSRR_BR_8                       ((uint32_t)0x01000000)
+#define GPIO_BSRR_BR_9                       ((uint32_t)0x02000000)
+#define GPIO_BSRR_BR_10                      ((uint32_t)0x04000000)
+#define GPIO_BSRR_BR_11                      ((uint32_t)0x08000000)
+#define GPIO_BSRR_BR_12                      ((uint32_t)0x10000000)
+#define GPIO_BSRR_BR_13                      ((uint32_t)0x20000000)
+#define GPIO_BSRR_BR_14                      ((uint32_t)0x40000000)
+#define GPIO_BSRR_BR_15                      ((uint32_t)0x80000000)
+
+/******************************************************************************/
+/*                                                                            */
+/*                                    HASH                                    */
+/*                                                                            */
+/******************************************************************************/
+/******************  Bits definition for HASH_CR register  ********************/
+#define HASH_CR_INIT                         ((uint32_t)0x00000004)
+#define HASH_CR_DMAE                         ((uint32_t)0x00000008)
+#define HASH_CR_DATATYPE                     ((uint32_t)0x00000030)
+#define HASH_CR_DATATYPE_0                   ((uint32_t)0x00000010)
+#define HASH_CR_DATATYPE_1                   ((uint32_t)0x00000020)
+#define HASH_CR_MODE                         ((uint32_t)0x00000040)
+#define HASH_CR_ALGO                         ((uint32_t)0x00040080)
+#define HASH_CR_ALGO_0                       ((uint32_t)0x00000080)
+#define HASH_CR_ALGO_1                       ((uint32_t)0x00040000)
+#define HASH_CR_NBW                          ((uint32_t)0x00000F00)
+#define HASH_CR_NBW_0                        ((uint32_t)0x00000100)
+#define HASH_CR_NBW_1                        ((uint32_t)0x00000200)
+#define HASH_CR_NBW_2                        ((uint32_t)0x00000400)
+#define HASH_CR_NBW_3                        ((uint32_t)0x00000800)
+#define HASH_CR_DINNE                        ((uint32_t)0x00001000)
+#define HASH_CR_MDMAT                        ((uint32_t)0x00002000)
+#define HASH_CR_LKEY                         ((uint32_t)0x00010000)
+
+/******************  Bits definition for HASH_STR register  *******************/
+#define HASH_STR_NBW                         ((uint32_t)0x0000001F)
+#define HASH_STR_NBW_0                       ((uint32_t)0x00000001)
+#define HASH_STR_NBW_1                       ((uint32_t)0x00000002)
+#define HASH_STR_NBW_2                       ((uint32_t)0x00000004)
+#define HASH_STR_NBW_3                       ((uint32_t)0x00000008)
+#define HASH_STR_NBW_4                       ((uint32_t)0x00000010)
+#define HASH_STR_DCAL                        ((uint32_t)0x00000100)
+
+/******************  Bits definition for HASH_IMR register  *******************/
+#define HASH_IMR_DINIM                       ((uint32_t)0x00000001)
+#define HASH_IMR_DCIM                        ((uint32_t)0x00000002)
+
+/******************  Bits definition for HASH_SR register  ********************/
+#define HASH_SR_DINIS                        ((uint32_t)0x00000001)
+#define HASH_SR_DCIS                         ((uint32_t)0x00000002)
+#define HASH_SR_DMAS                         ((uint32_t)0x00000004)
+#define HASH_SR_BUSY                         ((uint32_t)0x00000008)
+
+/******************************************************************************/
+/*                                                                            */
+/*                      Inter-integrated Circuit Interface                    */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for I2C_CR1 register  ********************/
+#define  I2C_CR1_PE                          ((uint16_t)0x0001)            /*!<Peripheral Enable                             */
+#define  I2C_CR1_SMBUS                       ((uint16_t)0x0002)            /*!<SMBus Mode                                    */
+#define  I2C_CR1_SMBTYPE                     ((uint16_t)0x0008)            /*!<SMBus Type                                    */
+#define  I2C_CR1_ENARP                       ((uint16_t)0x0010)            /*!<ARP Enable                                    */
+#define  I2C_CR1_ENPEC                       ((uint16_t)0x0020)            /*!<PEC Enable                                    */
+#define  I2C_CR1_ENGC                        ((uint16_t)0x0040)            /*!<General Call Enable                           */
+#define  I2C_CR1_NOSTRETCH                   ((uint16_t)0x0080)            /*!<Clock Stretching Disable (Slave mode)         */
+#define  I2C_CR1_START                       ((uint16_t)0x0100)            /*!<Start Generation                              */
+#define  I2C_CR1_STOP                        ((uint16_t)0x0200)            /*!<Stop Generation                               */
+#define  I2C_CR1_ACK                         ((uint16_t)0x0400)            /*!<Acknowledge Enable                            */
+#define  I2C_CR1_POS                         ((uint16_t)0x0800)            /*!<Acknowledge/PEC Position (for data reception) */
+#define  I2C_CR1_PEC                         ((uint16_t)0x1000)            /*!<Packet Error Checking                         */
+#define  I2C_CR1_ALERT                       ((uint16_t)0x2000)            /*!<SMBus Alert                                   */
+#define  I2C_CR1_SWRST                       ((uint16_t)0x8000)            /*!<Software Reset                                */
+
+/*******************  Bit definition for I2C_CR2 register  ********************/
+#define  I2C_CR2_FREQ                        ((uint16_t)0x003F)            /*!<FREQ[5:0] bits (Peripheral Clock Frequency)   */
+#define  I2C_CR2_FREQ_0                      ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  I2C_CR2_FREQ_1                      ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  I2C_CR2_FREQ_2                      ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  I2C_CR2_FREQ_3                      ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  I2C_CR2_FREQ_4                      ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  I2C_CR2_FREQ_5                      ((uint16_t)0x0020)            /*!<Bit 5 */
+
+#define  I2C_CR2_ITERREN                     ((uint16_t)0x0100)            /*!<Error Interrupt Enable  */
+#define  I2C_CR2_ITEVTEN                     ((uint16_t)0x0200)            /*!<Event Interrupt Enable  */
+#define  I2C_CR2_ITBUFEN                     ((uint16_t)0x0400)            /*!<Buffer Interrupt Enable */
+#define  I2C_CR2_DMAEN                       ((uint16_t)0x0800)            /*!<DMA Requests Enable     */
+#define  I2C_CR2_LAST                        ((uint16_t)0x1000)            /*!<DMA Last Transfer       */
+
+/*******************  Bit definition for I2C_OAR1 register  *******************/
+#define  I2C_OAR1_ADD1_7                     ((uint16_t)0x00FE)            /*!<Interface Address */
+#define  I2C_OAR1_ADD8_9                     ((uint16_t)0x0300)            /*!<Interface Address */
+
+#define  I2C_OAR1_ADD0                       ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  I2C_OAR1_ADD1                       ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  I2C_OAR1_ADD2                       ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  I2C_OAR1_ADD3                       ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  I2C_OAR1_ADD4                       ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  I2C_OAR1_ADD5                       ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  I2C_OAR1_ADD6                       ((uint16_t)0x0040)            /*!<Bit 6 */
+#define  I2C_OAR1_ADD7                       ((uint16_t)0x0080)            /*!<Bit 7 */
+#define  I2C_OAR1_ADD8                       ((uint16_t)0x0100)            /*!<Bit 8 */
+#define  I2C_OAR1_ADD9                       ((uint16_t)0x0200)            /*!<Bit 9 */
+
+#define  I2C_OAR1_ADDMODE                    ((uint16_t)0x8000)            /*!<Addressing Mode (Slave mode) */
+
+/*******************  Bit definition for I2C_OAR2 register  *******************/
+#define  I2C_OAR2_ENDUAL                     ((uint8_t)0x01)               /*!<Dual addressing mode enable */
+#define  I2C_OAR2_ADD2                       ((uint8_t)0xFE)               /*!<Interface address           */
+
+/********************  Bit definition for I2C_DR register  ********************/
+#define  I2C_DR_DR                           ((uint8_t)0xFF)               /*!<8-bit Data Register         */
+
+/*******************  Bit definition for I2C_SR1 register  ********************/
+#define  I2C_SR1_SB                          ((uint16_t)0x0001)            /*!<Start Bit (Master mode)                         */
+#define  I2C_SR1_ADDR                        ((uint16_t)0x0002)            /*!<Address sent (master mode)/matched (slave mode) */
+#define  I2C_SR1_BTF                         ((uint16_t)0x0004)            /*!<Byte Transfer Finished                          */
+#define  I2C_SR1_ADD10                       ((uint16_t)0x0008)            /*!<10-bit header sent (Master mode)                */
+#define  I2C_SR1_STOPF                       ((uint16_t)0x0010)            /*!<Stop detection (Slave mode)                     */
+#define  I2C_SR1_RXNE                        ((uint16_t)0x0040)            /*!<Data Register not Empty (receivers)             */
+#define  I2C_SR1_TXE                         ((uint16_t)0x0080)            /*!<Data Register Empty (transmitters)              */
+#define  I2C_SR1_BERR                        ((uint16_t)0x0100)            /*!<Bus Error                                       */
+#define  I2C_SR1_ARLO                        ((uint16_t)0x0200)            /*!<Arbitration Lost (master mode)                  */
+#define  I2C_SR1_AF                          ((uint16_t)0x0400)            /*!<Acknowledge Failure                             */
+#define  I2C_SR1_OVR                         ((uint16_t)0x0800)            /*!<Overrun/Underrun                                */
+#define  I2C_SR1_PECERR                      ((uint16_t)0x1000)            /*!<PEC Error in reception                          */
+#define  I2C_SR1_TIMEOUT                     ((uint16_t)0x4000)            /*!<Timeout or Tlow Error                           */
+#define  I2C_SR1_SMBALERT                    ((uint16_t)0x8000)            /*!<SMBus Alert                                     */
+
+/*******************  Bit definition for I2C_SR2 register  ********************/
+#define  I2C_SR2_MSL                         ((uint16_t)0x0001)            /*!<Master/Slave                              */
+#define  I2C_SR2_BUSY                        ((uint16_t)0x0002)            /*!<Bus Busy                                  */
+#define  I2C_SR2_TRA                         ((uint16_t)0x0004)            /*!<Transmitter/Receiver                      */
+#define  I2C_SR2_GENCALL                     ((uint16_t)0x0010)            /*!<General Call Address (Slave mode)         */
+#define  I2C_SR2_SMBDEFAULT                  ((uint16_t)0x0020)            /*!<SMBus Device Default Address (Slave mode) */
+#define  I2C_SR2_SMBHOST                     ((uint16_t)0x0040)            /*!<SMBus Host Header (Slave mode)            */
+#define  I2C_SR2_DUALF                       ((uint16_t)0x0080)            /*!<Dual Flag (Slave mode)                    */
+#define  I2C_SR2_PEC                         ((uint16_t)0xFF00)            /*!<Packet Error Checking Register            */
+
+/*******************  Bit definition for I2C_CCR register  ********************/
+#define  I2C_CCR_CCR                         ((uint16_t)0x0FFF)            /*!<Clock Control Register in Fast/Standard mode (Master mode) */
+#define  I2C_CCR_DUTY                        ((uint16_t)0x4000)            /*!<Fast Mode Duty Cycle                                       */
+#define  I2C_CCR_FS                          ((uint16_t)0x8000)            /*!<I2C Master Mode Selection                                  */
+
+/******************  Bit definition for I2C_TRISE register  *******************/
+#define  I2C_TRISE_TRISE                     ((uint8_t)0x3F)               /*!<Maximum Rise Time in Fast/Standard mode (Master mode) */
+
+/******************  Bit definition for I2C_FLTR register  *******************/
+#define  I2C_FLTR_DNF                     ((uint8_t)0x0F)                  /*!<Digital Noise Filter */
+#define  I2C_FLTR_ANOFF                   ((uint8_t)0x10)                  /*!<Analog Noise Filter OFF */
+
+/******************************************************************************/
+/*                                                                            */
+/*                           Independent WATCHDOG                             */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for IWDG_KR register  ********************/
+#define  IWDG_KR_KEY                         ((uint16_t)0xFFFF)            /*!<Key value (write only, read 0000h)  */
+
+/*******************  Bit definition for IWDG_PR register  ********************/
+#define  IWDG_PR_PR                          ((uint8_t)0x07)               /*!<PR[2:0] (Prescaler divider)         */
+#define  IWDG_PR_PR_0                        ((uint8_t)0x01)               /*!<Bit 0 */
+#define  IWDG_PR_PR_1                        ((uint8_t)0x02)               /*!<Bit 1 */
+#define  IWDG_PR_PR_2                        ((uint8_t)0x04)               /*!<Bit 2 */
+
+/*******************  Bit definition for IWDG_RLR register  *******************/
+#define  IWDG_RLR_RL                         ((uint16_t)0x0FFF)            /*!<Watchdog counter reload value        */
+
+/*******************  Bit definition for IWDG_SR register  ********************/
+#define  IWDG_SR_PVU                         ((uint8_t)0x01)               /*!<Watchdog prescaler value update      */
+#define  IWDG_SR_RVU                         ((uint8_t)0x02)               /*!<Watchdog counter reload value update */
+
+/******************************************************************************/
+/*                                                                            */
+/*                      LCD-TFT Display Controller (LTDC)                     */
+/*                                                                            */
+/******************************************************************************/
+
+/********************  Bit definition for LTDC_SSCR register  *****************/
+
+#define LTDC_SSCR_VSH                       ((uint32_t)0x000007FF)              /*!< Vertical Synchronization Height */
+#define LTDC_SSCR_HSW                       ((uint32_t)0x0FFF0000)              /*!< Horizontal Synchronization Width */
+
+/********************  Bit definition for LTDC_BPCR register  *****************/
+
+#define LTDC_BPCR_AVBP                      ((uint32_t)0x000007FF)              /*!< Accumulated Vertical Back Porch */
+#define LTDC_BPCR_AHBP                      ((uint32_t)0x0FFF0000)              /*!< Accumulated Horizontal Back Porch */
+
+/********************  Bit definition for LTDC_AWCR register  *****************/
+
+#define LTDC_AWCR_AAH                       ((uint32_t)0x000007FF)              /*!< Accumulated Active heigh */
+#define LTDC_AWCR_AAW                       ((uint32_t)0x0FFF0000)              /*!< Accumulated Active Width */
+
+/********************  Bit definition for LTDC_TWCR register  *****************/
+
+#define LTDC_TWCR_TOTALH                    ((uint32_t)0x000007FF)              /*!< Total Heigh */
+#define LTDC_TWCR_TOTALW                    ((uint32_t)0x0FFF0000)              /*!< Total Width */
+
+/********************  Bit definition for LTDC_GCR register  ******************/
+
+#define LTDC_GCR_LTDCEN                     ((uint32_t)0x00000001)              /*!< LCD-TFT controller enable bit */
+#define LTDC_GCR_DBW                        ((uint32_t)0x00000070)              /*!< Dither Blue Width */
+#define LTDC_GCR_DGW                        ((uint32_t)0x00000700)              /*!< Dither Green Width */
+#define LTDC_GCR_DRW                        ((uint32_t)0x00007000)              /*!< Dither Red Width */
+#define LTDC_GCR_DTEN                       ((uint32_t)0x00010000)              /*!< Dither Enable */
+#define LTDC_GCR_PCPOL                      ((uint32_t)0x10000000)              /*!< Pixel Clock Polarity */
+#define LTDC_GCR_DEPOL                      ((uint32_t)0x20000000)              /*!< Data Enable Polarity */
+#define LTDC_GCR_VSPOL                      ((uint32_t)0x40000000)              /*!< Vertical Synchronization Polarity */
+#define LTDC_GCR_HSPOL                      ((uint32_t)0x80000000)              /*!< Horizontal Synchronization Polarity */
+
+/********************  Bit definition for LTDC_SRCR register  *****************/
+
+#define LTDC_SRCR_IMR                      ((uint32_t)0x00000001)               /*!< Immediate Reload */
+#define LTDC_SRCR_VBR                      ((uint32_t)0x00000002)               /*!< Vertical Blanking Reload */
+
+/********************  Bit definition for LTDC_BCCR register  *****************/
+
+#define LTDC_BCCR_BCBLUE                    ((uint32_t)0x000000FF)              /*!< Background Blue value */
+#define LTDC_BCCR_BCGREEN                   ((uint32_t)0x0000FF00)              /*!< Background Green value */
+#define LTDC_BCCR_BCRED                     ((uint32_t)0x00FF0000)              /*!< Background Red value */
+
+/********************  Bit definition for LTDC_IER register  ******************/
+
+#define LTDC_IER_LIE                        ((uint32_t)0x00000001)              /*!< Line Interrupt Enable */
+#define LTDC_IER_FUIE                       ((uint32_t)0x00000002)              /*!< FIFO Underrun Interrupt Enable */
+#define LTDC_IER_TERRIE                     ((uint32_t)0x00000004)              /*!< Transfer Error Interrupt Enable */
+#define LTDC_IER_RRIE                       ((uint32_t)0x00000008)              /*!< Register Reload interrupt enable */
+
+/********************  Bit definition for LTDC_ISR register  ******************/
+
+#define LTDC_ISR_LIF                        ((uint32_t)0x00000001)              /*!< Line Interrupt Flag */
+#define LTDC_ISR_FUIF                       ((uint32_t)0x00000002)              /*!< FIFO Underrun Interrupt Flag */
+#define LTDC_ISR_TERRIF                     ((uint32_t)0x00000004)              /*!< Transfer Error Interrupt Flag */
+#define LTDC_ISR_RRIF                       ((uint32_t)0x00000008)              /*!< Register Reload interrupt Flag */
+
+/********************  Bit definition for LTDC_ICR register  ******************/
+
+#define LTDC_ICR_CLIF                       ((uint32_t)0x00000001)              /*!< Clears the Line Interrupt Flag */
+#define LTDC_ICR_CFUIF                      ((uint32_t)0x00000002)              /*!< Clears the FIFO Underrun Interrupt Flag */
+#define LTDC_ICR_CTERRIF                    ((uint32_t)0x00000004)              /*!< Clears the Transfer Error Interrupt Flag */
+#define LTDC_ICR_CRRIF                      ((uint32_t)0x00000008)              /*!< Clears Register Reload interrupt Flag */
+
+/********************  Bit definition for LTDC_LIPCR register  ****************/
+
+#define LTDC_LIPCR_LIPOS                    ((uint32_t)0x000007FF)              /*!< Line Interrupt Position */
+
+/********************  Bit definition for LTDC_CPSR register  *****************/
+
+#define LTDC_CPSR_CYPOS                     ((uint32_t)0x0000FFFF)              /*!< Current Y Position */
+#define LTDC_CPSR_CXPOS                     ((uint32_t)0xFFFF0000)              /*!< Current X Position */
+
+/********************  Bit definition for LTDC_CDSR register  *****************/
+
+#define LTDC_CDSR_VDES                      ((uint32_t)0x00000001)              /*!< Vertical Data Enable Status */
+#define LTDC_CDSR_HDES                      ((uint32_t)0x00000002)              /*!< Horizontal Data Enable Status */
+#define LTDC_CDSR_VSYNCS                    ((uint32_t)0x00000004)              /*!< Vertical Synchronization Status */
+#define LTDC_CDSR_HSYNCS                    ((uint32_t)0x00000008)              /*!< Horizontal Synchronization Status */
+
+/********************  Bit definition for LTDC_LxCR register  *****************/
+
+#define LTDC_LxCR_LEN                       ((uint32_t)0x00000001)              /*!< Layer Enable */
+#define LTDC_LxCR_COLKEN                    ((uint32_t)0x00000002)              /*!< Color Keying Enable */
+#define LTDC_LxCR_CLUTEN                    ((uint32_t)0x00000010)              /*!< Color Lockup Table Enable */
+
+/********************  Bit definition for LTDC_LxWHPCR register  **************/
+
+#define LTDC_LxWHPCR_WHSTPOS                ((uint32_t)0x00000FFF)              /*!< Window Horizontal Start Position */
+#define LTDC_LxWHPCR_WHSPPOS                ((uint32_t)0xFFFF0000)              /*!< Window Horizontal Stop Position */
+
+/********************  Bit definition for LTDC_LxWVPCR register  **************/
+
+#define LTDC_LxWVPCR_WVSTPOS                ((uint32_t)0x00000FFF)              /*!< Window Vertical Start Position */
+#define LTDC_LxWVPCR_WVSPPOS                ((uint32_t)0xFFFF0000)              /*!< Window Vertical Stop Position */
+
+/********************  Bit definition for LTDC_LxCKCR register  ***************/
+
+#define LTDC_LxCKCR_CKBLUE                  ((uint32_t)0x000000FF)              /*!< Color Key Blue value */
+#define LTDC_LxCKCR_CKGREEN                 ((uint32_t)0x0000FF00)              /*!< Color Key Green value */
+#define LTDC_LxCKCR_CKRED                   ((uint32_t)0x00FF0000)              /*!< Color Key Red value */
+
+/********************  Bit definition for LTDC_LxPFCR register  ***************/
+
+#define LTDC_LxPFCR_PF                      ((uint32_t)0x00000007)              /*!< Pixel Format */
+
+/********************  Bit definition for LTDC_LxCACR register  ***************/
+
+#define LTDC_LxCACR_CONSTA                  ((uint32_t)0x000000FF)              /*!< Constant Alpha */
+
+/********************  Bit definition for LTDC_LxDCCR register  ***************/
+
+#define LTDC_LxDCCR_DCBLUE                  ((uint32_t)0x000000FF)              /*!< Default Color Blue */
+#define LTDC_LxDCCR_DCGREEN                 ((uint32_t)0x0000FF00)              /*!< Default Color Green */
+#define LTDC_LxDCCR_DCRED                   ((uint32_t)0x00FF0000)              /*!< Default Color Red */
+#define LTDC_LxDCCR_DCALPHA                 ((uint32_t)0xFF000000)              /*!< Default Color Alpha */
+                                
+/********************  Bit definition for LTDC_LxBFCR register  ***************/
+
+#define LTDC_LxBFCR_BF2                     ((uint32_t)0x00000007)              /*!< Blending Factor 2 */
+#define LTDC_LxBFCR_BF1                     ((uint32_t)0x00000700)              /*!< Blending Factor 1 */
+
+/********************  Bit definition for LTDC_LxCFBAR register  **************/
+
+#define LTDC_LxCFBAR_CFBADD                 ((uint32_t)0xFFFFFFFF)              /*!< Color Frame Buffer Start Address */
+
+/********************  Bit definition for LTDC_LxCFBLR register  **************/
+
+#define LTDC_LxCFBLR_CFBLL                  ((uint32_t)0x00001FFF)              /*!< Color Frame Buffer Line Length */
+#define LTDC_LxCFBLR_CFBP                   ((uint32_t)0x1FFF0000)              /*!< Color Frame Buffer Pitch in bytes */
+
+/********************  Bit definition for LTDC_LxCFBLNR register  *************/
+
+#define LTDC_LxCFBLNR_CFBLNBR               ((uint32_t)0x000007FF)              /*!< Frame Buffer Line Number */
+
+/********************  Bit definition for LTDC_LxCLUTWR register  *************/
+
+#define LTDC_LxCLUTWR_BLUE                  ((uint32_t)0x000000FF)              /*!< Blue value */
+#define LTDC_LxCLUTWR_GREEN                 ((uint32_t)0x0000FF00)              /*!< Green value */
+#define LTDC_LxCLUTWR_RED                   ((uint32_t)0x00FF0000)              /*!< Red value */
+#define LTDC_LxCLUTWR_CLUTADD               ((uint32_t)0xFF000000)              /*!< CLUT address */
+
+/******************************************************************************/
+/*                                                                            */
+/*                             Power Control                                  */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bit definition for PWR_CR register  ********************/
+#define  PWR_CR_LPDS                         ((uint32_t)0x00000001)     /*!< Low-Power Deepsleep                 */
+#define  PWR_CR_PDDS                         ((uint32_t)0x00000002)     /*!< Power Down Deepsleep                */
+#define  PWR_CR_CWUF                         ((uint32_t)0x00000004)     /*!< Clear Wakeup Flag                   */
+#define  PWR_CR_CSBF                         ((uint32_t)0x00000008)     /*!< Clear Standby Flag                  */
+#define  PWR_CR_PVDE                         ((uint32_t)0x00000010)     /*!< Power Voltage Detector Enable       */
+
+#define  PWR_CR_PLS                          ((uint32_t)0x000000E0)     /*!< PLS[2:0] bits (PVD Level Selection) */
+#define  PWR_CR_PLS_0                        ((uint32_t)0x00000020)     /*!< Bit 0 */
+#define  PWR_CR_PLS_1                        ((uint32_t)0x00000040)     /*!< Bit 1 */
+#define  PWR_CR_PLS_2                        ((uint32_t)0x00000080)     /*!< Bit 2 */
+
+/*!< PVD level configuration */
+#define  PWR_CR_PLS_LEV0                     ((uint32_t)0x00000000)     /*!< PVD level 0 */
+#define  PWR_CR_PLS_LEV1                     ((uint32_t)0x00000020)     /*!< PVD level 1 */
+#define  PWR_CR_PLS_LEV2                     ((uint32_t)0x00000040)     /*!< PVD level 2 */
+#define  PWR_CR_PLS_LEV3                     ((uint32_t)0x00000060)     /*!< PVD level 3 */
+#define  PWR_CR_PLS_LEV4                     ((uint32_t)0x00000080)     /*!< PVD level 4 */
+#define  PWR_CR_PLS_LEV5                     ((uint32_t)0x000000A0)     /*!< PVD level 5 */
+#define  PWR_CR_PLS_LEV6                     ((uint32_t)0x000000C0)     /*!< PVD level 6 */
+#define  PWR_CR_PLS_LEV7                     ((uint32_t)0x000000E0)     /*!< PVD level 7 */
+
+#define  PWR_CR_DBP                          ((uint32_t)0x00000100)     /*!< Disable Backup Domain write protection                     */
+#define  PWR_CR_FPDS                         ((uint32_t)0x00000200)     /*!< Flash power down in Stop mode                              */
+#define  PWR_CR_LPUDS                        ((uint32_t)0x00000400)     /*!< Low-Power Regulator in Stop under-drive mode               */
+#define  PWR_CR_MRUDS                        ((uint32_t)0x00000800)     /*!< Main regulator in Stop under-drive mode                    */
+
+#define  PWR_CR_ADCDC1                       ((uint32_t)0x00002000)     /*!< Refer to AN4073 on how to use this bit */ 
+
+#define  PWR_CR_VOS                          ((uint32_t)0x0000C000)     /*!< VOS[1:0] bits (Regulator voltage scaling output selection) */
+#define  PWR_CR_VOS_0                        ((uint32_t)0x00004000)     /*!< Bit 0 */
+#define  PWR_CR_VOS_1                        ((uint32_t)0x00008000)     /*!< Bit 1 */
+
+#define  PWR_CR_ODEN                         ((uint32_t)0x00010000)     /*!< Over Drive enable                   */
+#define  PWR_CR_ODSWEN                       ((uint32_t)0x00020000)     /*!< Over Drive switch enabled           */
+#define  PWR_CR_UDEN                         ((uint32_t)0x000C0000)     /*!< Under Drive enable in stop mode     */
+#define  PWR_CR_UDEN_0                       ((uint32_t)0x00040000)     /*!< Bit 0                               */
+#define  PWR_CR_UDEN_1                       ((uint32_t)0x00080000)     /*!< Bit 1                               */
+
+/* Legacy define */
+#define  PWR_CR_PMODE                        PWR_CR_VOS
+
+/*******************  Bit definition for PWR_CSR register  ********************/
+#define  PWR_CSR_WUF                         ((uint32_t)0x00000001)     /*!< Wakeup Flag                                      */
+#define  PWR_CSR_SBF                         ((uint32_t)0x00000002)     /*!< Standby Flag                                     */
+#define  PWR_CSR_PVDO                        ((uint32_t)0x00000004)     /*!< PVD Output                                       */
+#define  PWR_CSR_BRR                         ((uint32_t)0x00000008)     /*!< Backup regulator ready                           */
+#define  PWR_CSR_EWUP                        ((uint32_t)0x00000100)     /*!< Enable WKUP pin                                  */
+#define  PWR_CSR_BRE                         ((uint32_t)0x00000200)     /*!< Backup regulator enable                          */
+#define  PWR_CSR_VOSRDY                      ((uint32_t)0x00004000)     /*!< Regulator voltage scaling output selection ready */
+#define  PWR_CSR_ODRDY                       ((uint32_t)0x00010000)     /*!< Over Drive generator ready                       */
+#define  PWR_CSR_ODSWRDY                     ((uint32_t)0x00020000)     /*!< Over Drive Switch ready                          */
+#define  PWR_CSR_UDSWRDY                     ((uint32_t)0x000C0000)     /*!< Under Drive ready                                */
+
+/* Legacy define */
+#define  PWR_CSR_REGRDY                      PWR_CSR_VOSRDY
+
+/******************************************************************************/
+/*                                                                            */
+/*                         Reset and Clock Control                            */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bit definition for RCC_CR register  ********************/
+#define  RCC_CR_HSION                        ((uint32_t)0x00000001)
+#define  RCC_CR_HSIRDY                       ((uint32_t)0x00000002)
+
+#define  RCC_CR_HSITRIM                      ((uint32_t)0x000000F8)
+#define  RCC_CR_HSITRIM_0                    ((uint32_t)0x00000008)/*!<Bit 0 */
+#define  RCC_CR_HSITRIM_1                    ((uint32_t)0x00000010)/*!<Bit 1 */
+#define  RCC_CR_HSITRIM_2                    ((uint32_t)0x00000020)/*!<Bit 2 */
+#define  RCC_CR_HSITRIM_3                    ((uint32_t)0x00000040)/*!<Bit 3 */
+#define  RCC_CR_HSITRIM_4                    ((uint32_t)0x00000080)/*!<Bit 4 */
+
+#define  RCC_CR_HSICAL                       ((uint32_t)0x0000FF00)
+#define  RCC_CR_HSICAL_0                     ((uint32_t)0x00000100)/*!<Bit 0 */
+#define  RCC_CR_HSICAL_1                     ((uint32_t)0x00000200)/*!<Bit 1 */
+#define  RCC_CR_HSICAL_2                     ((uint32_t)0x00000400)/*!<Bit 2 */
+#define  RCC_CR_HSICAL_3                     ((uint32_t)0x00000800)/*!<Bit 3 */
+#define  RCC_CR_HSICAL_4                     ((uint32_t)0x00001000)/*!<Bit 4 */
+#define  RCC_CR_HSICAL_5                     ((uint32_t)0x00002000)/*!<Bit 5 */
+#define  RCC_CR_HSICAL_6                     ((uint32_t)0x00004000)/*!<Bit 6 */
+#define  RCC_CR_HSICAL_7                     ((uint32_t)0x00008000)/*!<Bit 7 */
+
+#define  RCC_CR_HSEON                        ((uint32_t)0x00010000)
+#define  RCC_CR_HSERDY                       ((uint32_t)0x00020000)
+#define  RCC_CR_HSEBYP                       ((uint32_t)0x00040000)
+#define  RCC_CR_CSSON                        ((uint32_t)0x00080000)
+#define  RCC_CR_PLLON                        ((uint32_t)0x01000000)
+#define  RCC_CR_PLLRDY                       ((uint32_t)0x02000000)
+#define  RCC_CR_PLLI2SON                     ((uint32_t)0x04000000)
+#define  RCC_CR_PLLI2SRDY                    ((uint32_t)0x08000000)
+#define  RCC_CR_PLLSAION                     ((uint32_t)0x10000000)
+#define  RCC_CR_PLLSAIRDY                    ((uint32_t)0x20000000)
+
+/********************  Bit definition for RCC_PLLCFGR register  ***************/
+#define  RCC_PLLCFGR_PLLM                    ((uint32_t)0x0000003F)
+#define  RCC_PLLCFGR_PLLM_0                  ((uint32_t)0x00000001)
+#define  RCC_PLLCFGR_PLLM_1                  ((uint32_t)0x00000002)
+#define  RCC_PLLCFGR_PLLM_2                  ((uint32_t)0x00000004)
+#define  RCC_PLLCFGR_PLLM_3                  ((uint32_t)0x00000008)
+#define  RCC_PLLCFGR_PLLM_4                  ((uint32_t)0x00000010)
+#define  RCC_PLLCFGR_PLLM_5                  ((uint32_t)0x00000020)
+
+#define  RCC_PLLCFGR_PLLN                     ((uint32_t)0x00007FC0)
+#define  RCC_PLLCFGR_PLLN_0                   ((uint32_t)0x00000040)
+#define  RCC_PLLCFGR_PLLN_1                   ((uint32_t)0x00000080)
+#define  RCC_PLLCFGR_PLLN_2                   ((uint32_t)0x00000100)
+#define  RCC_PLLCFGR_PLLN_3                   ((uint32_t)0x00000200)
+#define  RCC_PLLCFGR_PLLN_4                   ((uint32_t)0x00000400)
+#define  RCC_PLLCFGR_PLLN_5                   ((uint32_t)0x00000800)
+#define  RCC_PLLCFGR_PLLN_6                   ((uint32_t)0x00001000)
+#define  RCC_PLLCFGR_PLLN_7                   ((uint32_t)0x00002000)
+#define  RCC_PLLCFGR_PLLN_8                   ((uint32_t)0x00004000)
+
+#define  RCC_PLLCFGR_PLLP                    ((uint32_t)0x00030000)
+#define  RCC_PLLCFGR_PLLP_0                  ((uint32_t)0x00010000)
+#define  RCC_PLLCFGR_PLLP_1                  ((uint32_t)0x00020000)
+
+#define  RCC_PLLCFGR_PLLSRC                  ((uint32_t)0x00400000)
+#define  RCC_PLLCFGR_PLLSRC_HSE              ((uint32_t)0x00400000)
+#define  RCC_PLLCFGR_PLLSRC_HSI              ((uint32_t)0x00000000)
+
+#define  RCC_PLLCFGR_PLLQ                    ((uint32_t)0x0F000000)
+#define  RCC_PLLCFGR_PLLQ_0                  ((uint32_t)0x01000000)
+#define  RCC_PLLCFGR_PLLQ_1                  ((uint32_t)0x02000000)
+#define  RCC_PLLCFGR_PLLQ_2                  ((uint32_t)0x04000000)
+#define  RCC_PLLCFGR_PLLQ_3                  ((uint32_t)0x08000000)
+
+/********************  Bit definition for RCC_CFGR register  ******************/
+/*!< SW configuration */
+#define  RCC_CFGR_SW                         ((uint32_t)0x00000003)        /*!< SW[1:0] bits (System clock Switch) */
+#define  RCC_CFGR_SW_0                       ((uint32_t)0x00000001)        /*!< Bit 0 */
+#define  RCC_CFGR_SW_1                       ((uint32_t)0x00000002)        /*!< Bit 1 */
+
+#define  RCC_CFGR_SW_HSI                     ((uint32_t)0x00000000)        /*!< HSI selected as system clock */
+#define  RCC_CFGR_SW_HSE                     ((uint32_t)0x00000001)        /*!< HSE selected as system clock */
+#define  RCC_CFGR_SW_PLL                     ((uint32_t)0x00000002)        /*!< PLL selected as system clock */
+
+/*!< SWS configuration */
+#define  RCC_CFGR_SWS                        ((uint32_t)0x0000000C)        /*!< SWS[1:0] bits (System Clock Switch Status) */
+#define  RCC_CFGR_SWS_0                      ((uint32_t)0x00000004)        /*!< Bit 0 */
+#define  RCC_CFGR_SWS_1                      ((uint32_t)0x00000008)        /*!< Bit 1 */
+
+#define  RCC_CFGR_SWS_HSI                    ((uint32_t)0x00000000)        /*!< HSI oscillator used as system clock */
+#define  RCC_CFGR_SWS_HSE                    ((uint32_t)0x00000004)        /*!< HSE oscillator used as system clock */
+#define  RCC_CFGR_SWS_PLL                    ((uint32_t)0x00000008)        /*!< PLL used as system clock */
+
+/*!< HPRE configuration */
+#define  RCC_CFGR_HPRE                       ((uint32_t)0x000000F0)        /*!< HPRE[3:0] bits (AHB prescaler) */
+#define  RCC_CFGR_HPRE_0                     ((uint32_t)0x00000010)        /*!< Bit 0 */
+#define  RCC_CFGR_HPRE_1                     ((uint32_t)0x00000020)        /*!< Bit 1 */
+#define  RCC_CFGR_HPRE_2                     ((uint32_t)0x00000040)        /*!< Bit 2 */
+#define  RCC_CFGR_HPRE_3                     ((uint32_t)0x00000080)        /*!< Bit 3 */
+
+#define  RCC_CFGR_HPRE_DIV1                  ((uint32_t)0x00000000)        /*!< SYSCLK not divided */
+#define  RCC_CFGR_HPRE_DIV2                  ((uint32_t)0x00000080)        /*!< SYSCLK divided by 2 */
+#define  RCC_CFGR_HPRE_DIV4                  ((uint32_t)0x00000090)        /*!< SYSCLK divided by 4 */
+#define  RCC_CFGR_HPRE_DIV8                  ((uint32_t)0x000000A0)        /*!< SYSCLK divided by 8 */
+#define  RCC_CFGR_HPRE_DIV16                 ((uint32_t)0x000000B0)        /*!< SYSCLK divided by 16 */
+#define  RCC_CFGR_HPRE_DIV64                 ((uint32_t)0x000000C0)        /*!< SYSCLK divided by 64 */
+#define  RCC_CFGR_HPRE_DIV128                ((uint32_t)0x000000D0)        /*!< SYSCLK divided by 128 */
+#define  RCC_CFGR_HPRE_DIV256                ((uint32_t)0x000000E0)        /*!< SYSCLK divided by 256 */
+#define  RCC_CFGR_HPRE_DIV512                ((uint32_t)0x000000F0)        /*!< SYSCLK divided by 512 */
+
+/*!< PPRE1 configuration */
+#define  RCC_CFGR_PPRE1                      ((uint32_t)0x00001C00)        /*!< PRE1[2:0] bits (APB1 prescaler) */
+#define  RCC_CFGR_PPRE1_0                    ((uint32_t)0x00000400)        /*!< Bit 0 */
+#define  RCC_CFGR_PPRE1_1                    ((uint32_t)0x00000800)        /*!< Bit 1 */
+#define  RCC_CFGR_PPRE1_2                    ((uint32_t)0x00001000)        /*!< Bit 2 */
+
+#define  RCC_CFGR_PPRE1_DIV1                 ((uint32_t)0x00000000)        /*!< HCLK not divided */
+#define  RCC_CFGR_PPRE1_DIV2                 ((uint32_t)0x00001000)        /*!< HCLK divided by 2 */
+#define  RCC_CFGR_PPRE1_DIV4                 ((uint32_t)0x00001400)        /*!< HCLK divided by 4 */
+#define  RCC_CFGR_PPRE1_DIV8                 ((uint32_t)0x00001800)        /*!< HCLK divided by 8 */
+#define  RCC_CFGR_PPRE1_DIV16                ((uint32_t)0x00001C00)        /*!< HCLK divided by 16 */
+
+/*!< PPRE2 configuration */
+#define  RCC_CFGR_PPRE2                      ((uint32_t)0x0000E000)        /*!< PRE2[2:0] bits (APB2 prescaler) */
+#define  RCC_CFGR_PPRE2_0                    ((uint32_t)0x00002000)        /*!< Bit 0 */
+#define  RCC_CFGR_PPRE2_1                    ((uint32_t)0x00004000)        /*!< Bit 1 */
+#define  RCC_CFGR_PPRE2_2                    ((uint32_t)0x00008000)        /*!< Bit 2 */
+
+#define  RCC_CFGR_PPRE2_DIV1                 ((uint32_t)0x00000000)        /*!< HCLK not divided */
+#define  RCC_CFGR_PPRE2_DIV2                 ((uint32_t)0x00008000)        /*!< HCLK divided by 2 */
+#define  RCC_CFGR_PPRE2_DIV4                 ((uint32_t)0x0000A000)        /*!< HCLK divided by 4 */
+#define  RCC_CFGR_PPRE2_DIV8                 ((uint32_t)0x0000C000)        /*!< HCLK divided by 8 */
+#define  RCC_CFGR_PPRE2_DIV16                ((uint32_t)0x0000E000)        /*!< HCLK divided by 16 */
+
+/*!< RTCPRE configuration */
+#define  RCC_CFGR_RTCPRE                     ((uint32_t)0x001F0000)
+#define  RCC_CFGR_RTCPRE_0                   ((uint32_t)0x00010000)
+#define  RCC_CFGR_RTCPRE_1                   ((uint32_t)0x00020000)
+#define  RCC_CFGR_RTCPRE_2                   ((uint32_t)0x00040000)
+#define  RCC_CFGR_RTCPRE_3                   ((uint32_t)0x00080000)
+#define  RCC_CFGR_RTCPRE_4                   ((uint32_t)0x00100000)
+
+/*!< MCO1 configuration */
+#define  RCC_CFGR_MCO1                       ((uint32_t)0x00600000)
+#define  RCC_CFGR_MCO1_0                     ((uint32_t)0x00200000)
+#define  RCC_CFGR_MCO1_1                     ((uint32_t)0x00400000)
+
+#define  RCC_CFGR_I2SSRC                     ((uint32_t)0x00800000)
+
+#define  RCC_CFGR_MCO1PRE                    ((uint32_t)0x07000000)
+#define  RCC_CFGR_MCO1PRE_0                  ((uint32_t)0x01000000)
+#define  RCC_CFGR_MCO1PRE_1                  ((uint32_t)0x02000000)
+#define  RCC_CFGR_MCO1PRE_2                  ((uint32_t)0x04000000)
+
+#define  RCC_CFGR_MCO2PRE                    ((uint32_t)0x38000000)
+#define  RCC_CFGR_MCO2PRE_0                  ((uint32_t)0x08000000)
+#define  RCC_CFGR_MCO2PRE_1                  ((uint32_t)0x10000000)
+#define  RCC_CFGR_MCO2PRE_2                  ((uint32_t)0x20000000)
+
+#define  RCC_CFGR_MCO2                       ((uint32_t)0xC0000000)
+#define  RCC_CFGR_MCO2_0                     ((uint32_t)0x40000000)
+#define  RCC_CFGR_MCO2_1                     ((uint32_t)0x80000000)
+
+/********************  Bit definition for RCC_CIR register  *******************/
+#define  RCC_CIR_LSIRDYF                     ((uint32_t)0x00000001)
+#define  RCC_CIR_LSERDYF                     ((uint32_t)0x00000002)
+#define  RCC_CIR_HSIRDYF                     ((uint32_t)0x00000004)
+#define  RCC_CIR_HSERDYF                     ((uint32_t)0x00000008)
+#define  RCC_CIR_PLLRDYF                     ((uint32_t)0x00000010)
+#define  RCC_CIR_PLLI2SRDYF                  ((uint32_t)0x00000020)
+#define  RCC_CIR_PLLSAIRDYF                  ((uint32_t)0x00000040)
+#define  RCC_CIR_CSSF                        ((uint32_t)0x00000080)
+#define  RCC_CIR_LSIRDYIE                    ((uint32_t)0x00000100)
+#define  RCC_CIR_LSERDYIE                    ((uint32_t)0x00000200)
+#define  RCC_CIR_HSIRDYIE                    ((uint32_t)0x00000400)
+#define  RCC_CIR_HSERDYIE                    ((uint32_t)0x00000800)
+#define  RCC_CIR_PLLRDYIE                    ((uint32_t)0x00001000)
+#define  RCC_CIR_PLLI2SRDYIE                 ((uint32_t)0x00002000)
+#define  RCC_CIR_PLLSAIRDYIE                 ((uint32_t)0x00004000)
+#define  RCC_CIR_LSIRDYC                     ((uint32_t)0x00010000)
+#define  RCC_CIR_LSERDYC                     ((uint32_t)0x00020000)
+#define  RCC_CIR_HSIRDYC                     ((uint32_t)0x00040000)
+#define  RCC_CIR_HSERDYC                     ((uint32_t)0x00080000)
+#define  RCC_CIR_PLLRDYC                     ((uint32_t)0x00100000)
+#define  RCC_CIR_PLLI2SRDYC                  ((uint32_t)0x00200000)
+#define  RCC_CIR_PLLSAIRDYC                  ((uint32_t)0x00400000)
+#define  RCC_CIR_CSSC                        ((uint32_t)0x00800000)
+
+/********************  Bit definition for RCC_AHB1RSTR register  **************/
+#define  RCC_AHB1RSTR_GPIOARST               ((uint32_t)0x00000001)
+#define  RCC_AHB1RSTR_GPIOBRST               ((uint32_t)0x00000002)
+#define  RCC_AHB1RSTR_GPIOCRST               ((uint32_t)0x00000004)
+#define  RCC_AHB1RSTR_GPIODRST               ((uint32_t)0x00000008)
+#define  RCC_AHB1RSTR_GPIOERST               ((uint32_t)0x00000010)
+#define  RCC_AHB1RSTR_GPIOFRST               ((uint32_t)0x00000020)
+#define  RCC_AHB1RSTR_GPIOGRST               ((uint32_t)0x00000040)
+#define  RCC_AHB1RSTR_GPIOHRST               ((uint32_t)0x00000080)
+#define  RCC_AHB1RSTR_GPIOIRST               ((uint32_t)0x00000100)
+#define  RCC_AHB1RSTR_GPIOJRST               ((uint32_t)0x00000200)
+#define  RCC_AHB1RSTR_GPIOKRST               ((uint32_t)0x00000400)
+#define  RCC_AHB1RSTR_CRCRST                 ((uint32_t)0x00001000)
+#define  RCC_AHB1RSTR_DMA1RST                ((uint32_t)0x00200000)
+#define  RCC_AHB1RSTR_DMA2RST                ((uint32_t)0x00400000)
+#define  RCC_AHB1RSTR_DMA2DRST               ((uint32_t)0x00800000)
+#define  RCC_AHB1RSTR_ETHMACRST              ((uint32_t)0x02000000)
+#define  RCC_AHB1RSTR_OTGHRST                ((uint32_t)0x10000000)
+
+/********************  Bit definition for RCC_AHB2RSTR register  **************/
+#define  RCC_AHB2RSTR_DCMIRST                ((uint32_t)0x00000001)
+#define  RCC_AHB2RSTR_CRYPRST                ((uint32_t)0x00000010)
+#define  RCC_AHB2RSTR_HASHRST                ((uint32_t)0x00000020)
+ /* maintained for legacy purpose */
+ #define  RCC_AHB2RSTR_HSAHRST                RCC_AHB2RSTR_HASHRST
+#define  RCC_AHB2RSTR_RNGRST                 ((uint32_t)0x00000040)
+#define  RCC_AHB2RSTR_OTGFSRST               ((uint32_t)0x00000080)
+
+/********************  Bit definition for RCC_AHB3RSTR register  **************/
+#if defined(STM32F40_41xxx)
+#define  RCC_AHB3RSTR_FSMCRST                ((uint32_t)0x00000001)
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define  RCC_AHB3RSTR_FMCRST                ((uint32_t)0x00000001)
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+/********************  Bit definition for RCC_APB1RSTR register  **************/
+#define  RCC_APB1RSTR_TIM2RST                ((uint32_t)0x00000001)
+#define  RCC_APB1RSTR_TIM3RST                ((uint32_t)0x00000002)
+#define  RCC_APB1RSTR_TIM4RST                ((uint32_t)0x00000004)
+#define  RCC_APB1RSTR_TIM5RST                ((uint32_t)0x00000008)
+#define  RCC_APB1RSTR_TIM6RST                ((uint32_t)0x00000010)
+#define  RCC_APB1RSTR_TIM7RST                ((uint32_t)0x00000020)
+#define  RCC_APB1RSTR_TIM12RST               ((uint32_t)0x00000040)
+#define  RCC_APB1RSTR_TIM13RST               ((uint32_t)0x00000080)
+#define  RCC_APB1RSTR_TIM14RST               ((uint32_t)0x00000100)
+#define  RCC_APB1RSTR_WWDGRST                ((uint32_t)0x00000800)
+#define  RCC_APB1RSTR_SPI2RST                ((uint32_t)0x00004000)
+#define  RCC_APB1RSTR_SPI3RST                ((uint32_t)0x00008000)
+#define  RCC_APB1RSTR_USART2RST              ((uint32_t)0x00020000)
+#define  RCC_APB1RSTR_USART3RST              ((uint32_t)0x00040000)
+#define  RCC_APB1RSTR_UART4RST               ((uint32_t)0x00080000)
+#define  RCC_APB1RSTR_UART5RST               ((uint32_t)0x00100000)
+#define  RCC_APB1RSTR_I2C1RST                ((uint32_t)0x00200000)
+#define  RCC_APB1RSTR_I2C2RST                ((uint32_t)0x00400000)
+#define  RCC_APB1RSTR_I2C3RST                ((uint32_t)0x00800000)
+#define  RCC_APB1RSTR_CAN1RST                ((uint32_t)0x02000000)
+#define  RCC_APB1RSTR_CAN2RST                ((uint32_t)0x04000000)
+#define  RCC_APB1RSTR_PWRRST                 ((uint32_t)0x10000000)
+#define  RCC_APB1RSTR_DACRST                 ((uint32_t)0x20000000)
+#define  RCC_APB1RSTR_UART7RST               ((uint32_t)0x40000000)
+#define  RCC_APB1RSTR_UART8RST               ((uint32_t)0x80000000)
+
+/********************  Bit definition for RCC_APB2RSTR register  **************/
+#define  RCC_APB2RSTR_TIM1RST                ((uint32_t)0x00000001)
+#define  RCC_APB2RSTR_TIM8RST                ((uint32_t)0x00000002)
+#define  RCC_APB2RSTR_USART1RST              ((uint32_t)0x00000010)
+#define  RCC_APB2RSTR_USART6RST              ((uint32_t)0x00000020)
+#define  RCC_APB2RSTR_ADCRST                 ((uint32_t)0x00000100)
+#define  RCC_APB2RSTR_SDIORST                ((uint32_t)0x00000800)
+#define  RCC_APB2RSTR_SPI1RST                ((uint32_t)0x00001000)
+#define  RCC_APB2RSTR_SPI4RST                ((uint32_t)0x00002000)
+#define  RCC_APB2RSTR_SYSCFGRST              ((uint32_t)0x00004000)
+#define  RCC_APB2RSTR_TIM9RST                ((uint32_t)0x00010000)
+#define  RCC_APB2RSTR_TIM10RST               ((uint32_t)0x00020000)
+#define  RCC_APB2RSTR_TIM11RST               ((uint32_t)0x00040000)
+#define  RCC_APB2RSTR_SPI5RST                ((uint32_t)0x00100000)
+#define  RCC_APB2RSTR_SPI6RST                ((uint32_t)0x00200000)
+#define  RCC_APB2RSTR_SAI1RST                ((uint32_t)0x00400000)
+#define  RCC_APB2RSTR_LTDCRST                ((uint32_t)0x04000000)
+
+/* Old SPI1RST bit definition, maintained for legacy purpose */
+#define  RCC_APB2RSTR_SPI1                   RCC_APB2RSTR_SPI1RST
+
+/********************  Bit definition for RCC_AHB1ENR register  ***************/
+#define  RCC_AHB1ENR_GPIOAEN                 ((uint32_t)0x00000001)
+#define  RCC_AHB1ENR_GPIOBEN                 ((uint32_t)0x00000002)
+#define  RCC_AHB1ENR_GPIOCEN                 ((uint32_t)0x00000004)
+#define  RCC_AHB1ENR_GPIODEN                 ((uint32_t)0x00000008)
+#define  RCC_AHB1ENR_GPIOEEN                 ((uint32_t)0x00000010)
+#define  RCC_AHB1ENR_GPIOFEN                 ((uint32_t)0x00000020)
+#define  RCC_AHB1ENR_GPIOGEN                 ((uint32_t)0x00000040)
+#define  RCC_AHB1ENR_GPIOHEN                 ((uint32_t)0x00000080)
+#define  RCC_AHB1ENR_GPIOIEN                 ((uint32_t)0x00000100)
+#define  RCC_AHB1ENR_GPIOJEN                 ((uint32_t)0x00000200)
+#define  RCC_AHB1ENR_GPIOKEN                 ((uint32_t)0x00000400)
+#define  RCC_AHB1ENR_CRCEN                   ((uint32_t)0x00001000)
+#define  RCC_AHB1ENR_BKPSRAMEN               ((uint32_t)0x00040000)
+#define  RCC_AHB1ENR_CCMDATARAMEN            ((uint32_t)0x00100000)
+#define  RCC_AHB1ENR_DMA1EN                  ((uint32_t)0x00200000)
+#define  RCC_AHB1ENR_DMA2EN                  ((uint32_t)0x00400000)
+#define  RCC_AHB1ENR_DMA2DEN                 ((uint32_t)0x00800000)
+#define  RCC_AHB1ENR_ETHMACEN                ((uint32_t)0x02000000)
+#define  RCC_AHB1ENR_ETHMACTXEN              ((uint32_t)0x04000000)
+#define  RCC_AHB1ENR_ETHMACRXEN              ((uint32_t)0x08000000)
+#define  RCC_AHB1ENR_ETHMACPTPEN             ((uint32_t)0x10000000)
+#define  RCC_AHB1ENR_OTGHSEN                 ((uint32_t)0x20000000)
+#define  RCC_AHB1ENR_OTGHSULPIEN             ((uint32_t)0x40000000)
+
+/********************  Bit definition for RCC_AHB2ENR register  ***************/
+#define  RCC_AHB2ENR_DCMIEN                  ((uint32_t)0x00000001)
+#define  RCC_AHB2ENR_CRYPEN                  ((uint32_t)0x00000010)
+#define  RCC_AHB2ENR_HASHEN                  ((uint32_t)0x00000020)
+#define  RCC_AHB2ENR_RNGEN                   ((uint32_t)0x00000040)
+#define  RCC_AHB2ENR_OTGFSEN                 ((uint32_t)0x00000080)
+
+/********************  Bit definition for RCC_AHB3ENR register  ***************/
+
+#if defined(STM32F40_41xxx)
+#define  RCC_AHB3ENR_FSMCEN                  ((uint32_t)0x00000001)
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define  RCC_AHB3ENR_FMCEN                  ((uint32_t)0x00000001)
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+/********************  Bit definition for RCC_APB1ENR register  ***************/
+#define  RCC_APB1ENR_TIM2EN                  ((uint32_t)0x00000001)
+#define  RCC_APB1ENR_TIM3EN                  ((uint32_t)0x00000002)
+#define  RCC_APB1ENR_TIM4EN                  ((uint32_t)0x00000004)
+#define  RCC_APB1ENR_TIM5EN                  ((uint32_t)0x00000008)
+#define  RCC_APB1ENR_TIM6EN                  ((uint32_t)0x00000010)
+#define  RCC_APB1ENR_TIM7EN                  ((uint32_t)0x00000020)
+#define  RCC_APB1ENR_TIM12EN                 ((uint32_t)0x00000040)
+#define  RCC_APB1ENR_TIM13EN                 ((uint32_t)0x00000080)
+#define  RCC_APB1ENR_TIM14EN                 ((uint32_t)0x00000100)
+#define  RCC_APB1ENR_WWDGEN                  ((uint32_t)0x00000800)
+#define  RCC_APB1ENR_SPI2EN                  ((uint32_t)0x00004000)
+#define  RCC_APB1ENR_SPI3EN                  ((uint32_t)0x00008000)
+#define  RCC_APB1ENR_USART2EN                ((uint32_t)0x00020000)
+#define  RCC_APB1ENR_USART3EN                ((uint32_t)0x00040000)
+#define  RCC_APB1ENR_UART4EN                 ((uint32_t)0x00080000)
+#define  RCC_APB1ENR_UART5EN                 ((uint32_t)0x00100000)
+#define  RCC_APB1ENR_I2C1EN                  ((uint32_t)0x00200000)
+#define  RCC_APB1ENR_I2C2EN                  ((uint32_t)0x00400000)
+#define  RCC_APB1ENR_I2C3EN                  ((uint32_t)0x00800000)
+#define  RCC_APB1ENR_CAN1EN                  ((uint32_t)0x02000000)
+#define  RCC_APB1ENR_CAN2EN                  ((uint32_t)0x04000000)
+#define  RCC_APB1ENR_PWREN                   ((uint32_t)0x10000000)
+#define  RCC_APB1ENR_DACEN                   ((uint32_t)0x20000000)
+#define  RCC_APB1ENR_UART7EN                 ((uint32_t)0x40000000)
+#define  RCC_APB1ENR_UART8EN                 ((uint32_t)0x80000000)
+
+/********************  Bit definition for RCC_APB2ENR register  ***************/
+#define  RCC_APB2ENR_TIM1EN                  ((uint32_t)0x00000001)
+#define  RCC_APB2ENR_TIM8EN                  ((uint32_t)0x00000002)
+#define  RCC_APB2ENR_USART1EN                ((uint32_t)0x00000010)
+#define  RCC_APB2ENR_USART6EN                ((uint32_t)0x00000020)
+#define  RCC_APB2ENR_ADC1EN                  ((uint32_t)0x00000100)
+#define  RCC_APB2ENR_ADC2EN                  ((uint32_t)0x00000200)
+#define  RCC_APB2ENR_ADC3EN                  ((uint32_t)0x00000400)
+#define  RCC_APB2ENR_SDIOEN                  ((uint32_t)0x00000800)
+#define  RCC_APB2ENR_SPI1EN                  ((uint32_t)0x00001000)
+#define  RCC_APB2ENR_SPI4EN                  ((uint32_t)0x00002000)
+#define  RCC_APB2ENR_SYSCFGEN                ((uint32_t)0x00004000)
+#define  RCC_APB2ENR_TIM9EN                  ((uint32_t)0x00010000)
+#define  RCC_APB2ENR_TIM10EN                 ((uint32_t)0x00020000)
+#define  RCC_APB2ENR_TIM11EN                 ((uint32_t)0x00040000)
+#define  RCC_APB2ENR_SPI5EN                  ((uint32_t)0x00100000)
+#define  RCC_APB2ENR_SPI6EN                  ((uint32_t)0x00200000)
+#define  RCC_APB2ENR_SAI1EN                  ((uint32_t)0x00400000)
+#define  RCC_APB2ENR_LTDCEN                  ((uint32_t)0x04000000)
+
+/********************  Bit definition for RCC_AHB1LPENR register  *************/
+#define  RCC_AHB1LPENR_GPIOALPEN             ((uint32_t)0x00000001)
+#define  RCC_AHB1LPENR_GPIOBLPEN             ((uint32_t)0x00000002)
+#define  RCC_AHB1LPENR_GPIOCLPEN             ((uint32_t)0x00000004)
+#define  RCC_AHB1LPENR_GPIODLPEN             ((uint32_t)0x00000008)
+#define  RCC_AHB1LPENR_GPIOELPEN             ((uint32_t)0x00000010)
+#define  RCC_AHB1LPENR_GPIOFLPEN             ((uint32_t)0x00000020)
+#define  RCC_AHB1LPENR_GPIOGLPEN             ((uint32_t)0x00000040)
+#define  RCC_AHB1LPENR_GPIOHLPEN             ((uint32_t)0x00000080)
+#define  RCC_AHB1LPENR_GPIOILPEN             ((uint32_t)0x00000100)
+#define  RCC_AHB1LPENR_GPIOJLPEN             ((uint32_t)0x00000200)
+#define  RCC_AHB1LPENR_GPIOKLPEN             ((uint32_t)0x00000400)
+#define  RCC_AHB1LPENR_CRCLPEN               ((uint32_t)0x00001000)
+#define  RCC_AHB1LPENR_FLITFLPEN             ((uint32_t)0x00008000)
+#define  RCC_AHB1LPENR_SRAM1LPEN             ((uint32_t)0x00010000)
+#define  RCC_AHB1LPENR_SRAM2LPEN             ((uint32_t)0x00020000)
+#define  RCC_AHB1LPENR_BKPSRAMLPEN           ((uint32_t)0x00040000)
+#define  RCC_AHB1LPENR_SRAM3LPEN             ((uint32_t)0x00080000)
+#define  RCC_AHB1LPENR_DMA1LPEN              ((uint32_t)0x00200000)
+#define  RCC_AHB1LPENR_DMA2LPEN              ((uint32_t)0x00400000)
+#define  RCC_AHB1LPENR_DMA2DLPEN             ((uint32_t)0x00800000)
+#define  RCC_AHB1LPENR_ETHMACLPEN            ((uint32_t)0x02000000)
+#define  RCC_AHB1LPENR_ETHMACTXLPEN          ((uint32_t)0x04000000)
+#define  RCC_AHB1LPENR_ETHMACRXLPEN          ((uint32_t)0x08000000)
+#define  RCC_AHB1LPENR_ETHMACPTPLPEN         ((uint32_t)0x10000000)
+#define  RCC_AHB1LPENR_OTGHSLPEN             ((uint32_t)0x20000000)
+#define  RCC_AHB1LPENR_OTGHSULPILPEN         ((uint32_t)0x40000000)
+
+/********************  Bit definition for RCC_AHB2LPENR register  *************/
+#define  RCC_AHB2LPENR_DCMILPEN              ((uint32_t)0x00000001)
+#define  RCC_AHB2LPENR_CRYPLPEN              ((uint32_t)0x00000010)
+#define  RCC_AHB2LPENR_HASHLPEN              ((uint32_t)0x00000020)
+#define  RCC_AHB2LPENR_RNGLPEN               ((uint32_t)0x00000040)
+#define  RCC_AHB2LPENR_OTGFSLPEN             ((uint32_t)0x00000080)
+
+/********************  Bit definition for RCC_AHB3LPENR register  *************/
+#if defined(STM32F40_41xxx)
+#define  RCC_AHB3LPENR_FSMCLPEN              ((uint32_t)0x00000001)
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define  RCC_AHB3LPENR_FMCLPEN              ((uint32_t)0x00000001)
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+/********************  Bit definition for RCC_APB1LPENR register  *************/
+#define  RCC_APB1LPENR_TIM2LPEN              ((uint32_t)0x00000001)
+#define  RCC_APB1LPENR_TIM3LPEN              ((uint32_t)0x00000002)
+#define  RCC_APB1LPENR_TIM4LPEN              ((uint32_t)0x00000004)
+#define  RCC_APB1LPENR_TIM5LPEN              ((uint32_t)0x00000008)
+#define  RCC_APB1LPENR_TIM6LPEN              ((uint32_t)0x00000010)
+#define  RCC_APB1LPENR_TIM7LPEN              ((uint32_t)0x00000020)
+#define  RCC_APB1LPENR_TIM12LPEN             ((uint32_t)0x00000040)
+#define  RCC_APB1LPENR_TIM13LPEN             ((uint32_t)0x00000080)
+#define  RCC_APB1LPENR_TIM14LPEN             ((uint32_t)0x00000100)
+#define  RCC_APB1LPENR_WWDGLPEN              ((uint32_t)0x00000800)
+#define  RCC_APB1LPENR_SPI2LPEN              ((uint32_t)0x00004000)
+#define  RCC_APB1LPENR_SPI3LPEN              ((uint32_t)0x00008000)
+#define  RCC_APB1LPENR_USART2LPEN            ((uint32_t)0x00020000)
+#define  RCC_APB1LPENR_USART3LPEN            ((uint32_t)0x00040000)
+#define  RCC_APB1LPENR_UART4LPEN             ((uint32_t)0x00080000)
+#define  RCC_APB1LPENR_UART5LPEN             ((uint32_t)0x00100000)
+#define  RCC_APB1LPENR_I2C1LPEN              ((uint32_t)0x00200000)
+#define  RCC_APB1LPENR_I2C2LPEN              ((uint32_t)0x00400000)
+#define  RCC_APB1LPENR_I2C3LPEN              ((uint32_t)0x00800000)
+#define  RCC_APB1LPENR_CAN1LPEN              ((uint32_t)0x02000000)
+#define  RCC_APB1LPENR_CAN2LPEN              ((uint32_t)0x04000000)
+#define  RCC_APB1LPENR_PWRLPEN               ((uint32_t)0x10000000)
+#define  RCC_APB1LPENR_DACLPEN               ((uint32_t)0x20000000)
+#define  RCC_APB1LPENR_UART7LPEN             ((uint32_t)0x40000000)
+#define  RCC_APB1LPENR_UART8LPEN             ((uint32_t)0x80000000)
+
+/********************  Bit definition for RCC_APB2LPENR register  *************/
+#define  RCC_APB2LPENR_TIM1LPEN              ((uint32_t)0x00000001)
+#define  RCC_APB2LPENR_TIM8LPEN              ((uint32_t)0x00000002)
+#define  RCC_APB2LPENR_USART1LPEN            ((uint32_t)0x00000010)
+#define  RCC_APB2LPENR_USART6LPEN            ((uint32_t)0x00000020)
+#define  RCC_APB2LPENR_ADC1LPEN              ((uint32_t)0x00000100)
+#define  RCC_APB2LPENR_ADC2PEN               ((uint32_t)0x00000200)
+#define  RCC_APB2LPENR_ADC3LPEN              ((uint32_t)0x00000400)
+#define  RCC_APB2LPENR_SDIOLPEN              ((uint32_t)0x00000800)
+#define  RCC_APB2LPENR_SPI1LPEN              ((uint32_t)0x00001000)
+#define  RCC_APB2LPENR_SPI4LPEN              ((uint32_t)0x00002000)
+#define  RCC_APB2LPENR_SYSCFGLPEN            ((uint32_t)0x00004000)
+#define  RCC_APB2LPENR_TIM9LPEN              ((uint32_t)0x00010000)
+#define  RCC_APB2LPENR_TIM10LPEN             ((uint32_t)0x00020000)
+#define  RCC_APB2LPENR_TIM11LPEN             ((uint32_t)0x00040000)
+#define  RCC_APB2LPENR_SPI5LPEN              ((uint32_t)0x00100000)
+#define  RCC_APB2LPENR_SPI6LPEN              ((uint32_t)0x00200000)
+#define  RCC_APB2LPENR_SAI1LPEN              ((uint32_t)0x00400000)
+#define  RCC_APB2LPENR_LTDCLPEN              ((uint32_t)0x04000000)
+
+/********************  Bit definition for RCC_BDCR register  ******************/
+#define  RCC_BDCR_LSEON                      ((uint32_t)0x00000001)
+#define  RCC_BDCR_LSERDY                     ((uint32_t)0x00000002)
+#define  RCC_BDCR_LSEBYP                     ((uint32_t)0x00000004)
+
+#define  RCC_BDCR_RTCSEL                    ((uint32_t)0x00000300)
+#define  RCC_BDCR_RTCSEL_0                  ((uint32_t)0x00000100)
+#define  RCC_BDCR_RTCSEL_1                  ((uint32_t)0x00000200)
+
+#define  RCC_BDCR_RTCEN                      ((uint32_t)0x00008000)
+#define  RCC_BDCR_BDRST                      ((uint32_t)0x00010000)
+
+/********************  Bit definition for RCC_CSR register  *******************/
+#define  RCC_CSR_LSION                       ((uint32_t)0x00000001)
+#define  RCC_CSR_LSIRDY                      ((uint32_t)0x00000002)
+#define  RCC_CSR_RMVF                        ((uint32_t)0x01000000)
+#define  RCC_CSR_BORRSTF                     ((uint32_t)0x02000000)
+#define  RCC_CSR_PADRSTF                     ((uint32_t)0x04000000)
+#define  RCC_CSR_PORRSTF                     ((uint32_t)0x08000000)
+#define  RCC_CSR_SFTRSTF                     ((uint32_t)0x10000000)
+#define  RCC_CSR_WDGRSTF                     ((uint32_t)0x20000000)
+#define  RCC_CSR_WWDGRSTF                    ((uint32_t)0x40000000)
+#define  RCC_CSR_LPWRRSTF                    ((uint32_t)0x80000000)
+
+/********************  Bit definition for RCC_SSCGR register  *****************/
+#define  RCC_SSCGR_MODPER                    ((uint32_t)0x00001FFF)
+#define  RCC_SSCGR_INCSTEP                   ((uint32_t)0x0FFFE000)
+#define  RCC_SSCGR_SPREADSEL                 ((uint32_t)0x40000000)
+#define  RCC_SSCGR_SSCGEN                    ((uint32_t)0x80000000)
+
+/********************  Bit definition for RCC_PLLI2SCFGR register  ************/
+#define  RCC_PLLI2SCFGR_PLLI2SN              ((uint32_t)0x00007FC0)
+#define  RCC_PLLI2SCFGR_PLLI2SQ              ((uint32_t)0x0F000000)
+#define  RCC_PLLI2SCFGR_PLLI2SR              ((uint32_t)0x70000000)
+
+/********************  Bit definition for RCC_PLLSAICFGR register  ************/
+#define  RCC_PLLSAICFGR_PLLI2SN              ((uint32_t)0x00007FC0)
+#define  RCC_PLLSAICFGR_PLLI2SQ              ((uint32_t)0x0F000000)
+#define  RCC_PLLSAICFGR_PLLI2SR              ((uint32_t)0x70000000)
+
+/********************  Bit definition for RCC_DCKCFGR register  ***************/
+#define  RCC_DCKCFGR_PLLI2SDIVQ              ((uint32_t)0x0000001F)
+#define  RCC_DCKCFGR_PLLSAIDIVQ              ((uint32_t)0x00001F00)
+#define  RCC_DCKCFGR_PLLSAIDIVR              ((uint32_t)0x00030000)
+#define  RCC_DCKCFGR_SAI1ASRC                ((uint32_t)0x00300000)
+#define  RCC_DCKCFGR_SAI1BSRC                ((uint32_t)0x00C00000)
+#define  RCC_DCKCFGR_TIMPRE                  ((uint32_t)0x01000000)
+
+
+/******************************************************************************/
+/*                                                                            */
+/*                                    RNG                                     */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bits definition for RNG_CR register  *******************/
+#define RNG_CR_RNGEN                         ((uint32_t)0x00000004)
+#define RNG_CR_IE                            ((uint32_t)0x00000008)
+
+/********************  Bits definition for RNG_SR register  *******************/
+#define RNG_SR_DRDY                          ((uint32_t)0x00000001)
+#define RNG_SR_CECS                          ((uint32_t)0x00000002)
+#define RNG_SR_SECS                          ((uint32_t)0x00000004)
+#define RNG_SR_CEIS                          ((uint32_t)0x00000020)
+#define RNG_SR_SEIS                          ((uint32_t)0x00000040)
+
+/******************************************************************************/
+/*                                                                            */
+/*                           Real-Time Clock (RTC)                            */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bits definition for RTC_TR register  *******************/
+#define RTC_TR_PM                            ((uint32_t)0x00400000)
+#define RTC_TR_HT                            ((uint32_t)0x00300000)
+#define RTC_TR_HT_0                          ((uint32_t)0x00100000)
+#define RTC_TR_HT_1                          ((uint32_t)0x00200000)
+#define RTC_TR_HU                            ((uint32_t)0x000F0000)
+#define RTC_TR_HU_0                          ((uint32_t)0x00010000)
+#define RTC_TR_HU_1                          ((uint32_t)0x00020000)
+#define RTC_TR_HU_2                          ((uint32_t)0x00040000)
+#define RTC_TR_HU_3                          ((uint32_t)0x00080000)
+#define RTC_TR_MNT                           ((uint32_t)0x00007000)
+#define RTC_TR_MNT_0                         ((uint32_t)0x00001000)
+#define RTC_TR_MNT_1                         ((uint32_t)0x00002000)
+#define RTC_TR_MNT_2                         ((uint32_t)0x00004000)
+#define RTC_TR_MNU                           ((uint32_t)0x00000F00)
+#define RTC_TR_MNU_0                         ((uint32_t)0x00000100)
+#define RTC_TR_MNU_1                         ((uint32_t)0x00000200)
+#define RTC_TR_MNU_2                         ((uint32_t)0x00000400)
+#define RTC_TR_MNU_3                         ((uint32_t)0x00000800)
+#define RTC_TR_ST                            ((uint32_t)0x00000070)
+#define RTC_TR_ST_0                          ((uint32_t)0x00000010)
+#define RTC_TR_ST_1                          ((uint32_t)0x00000020)
+#define RTC_TR_ST_2                          ((uint32_t)0x00000040)
+#define RTC_TR_SU                            ((uint32_t)0x0000000F)
+#define RTC_TR_SU_0                          ((uint32_t)0x00000001)
+#define RTC_TR_SU_1                          ((uint32_t)0x00000002)
+#define RTC_TR_SU_2                          ((uint32_t)0x00000004)
+#define RTC_TR_SU_3                          ((uint32_t)0x00000008)
+
+/********************  Bits definition for RTC_DR register  *******************/
+#define RTC_DR_YT                            ((uint32_t)0x00F00000)
+#define RTC_DR_YT_0                          ((uint32_t)0x00100000)
+#define RTC_DR_YT_1                          ((uint32_t)0x00200000)
+#define RTC_DR_YT_2                          ((uint32_t)0x00400000)
+#define RTC_DR_YT_3                          ((uint32_t)0x00800000)
+#define RTC_DR_YU                            ((uint32_t)0x000F0000)
+#define RTC_DR_YU_0                          ((uint32_t)0x00010000)
+#define RTC_DR_YU_1                          ((uint32_t)0x00020000)
+#define RTC_DR_YU_2                          ((uint32_t)0x00040000)
+#define RTC_DR_YU_3                          ((uint32_t)0x00080000)
+#define RTC_DR_WDU                           ((uint32_t)0x0000E000)
+#define RTC_DR_WDU_0                         ((uint32_t)0x00002000)
+#define RTC_DR_WDU_1                         ((uint32_t)0x00004000)
+#define RTC_DR_WDU_2                         ((uint32_t)0x00008000)
+#define RTC_DR_MT                            ((uint32_t)0x00001000)
+#define RTC_DR_MU                            ((uint32_t)0x00000F00)
+#define RTC_DR_MU_0                          ((uint32_t)0x00000100)
+#define RTC_DR_MU_1                          ((uint32_t)0x00000200)
+#define RTC_DR_MU_2                          ((uint32_t)0x00000400)
+#define RTC_DR_MU_3                          ((uint32_t)0x00000800)
+#define RTC_DR_DT                            ((uint32_t)0x00000030)
+#define RTC_DR_DT_0                          ((uint32_t)0x00000010)
+#define RTC_DR_DT_1                          ((uint32_t)0x00000020)
+#define RTC_DR_DU                            ((uint32_t)0x0000000F)
+#define RTC_DR_DU_0                          ((uint32_t)0x00000001)
+#define RTC_DR_DU_1                          ((uint32_t)0x00000002)
+#define RTC_DR_DU_2                          ((uint32_t)0x00000004)
+#define RTC_DR_DU_3                          ((uint32_t)0x00000008)
+
+/********************  Bits definition for RTC_CR register  *******************/
+#define RTC_CR_COE                           ((uint32_t)0x00800000)
+#define RTC_CR_OSEL                          ((uint32_t)0x00600000)
+#define RTC_CR_OSEL_0                        ((uint32_t)0x00200000)
+#define RTC_CR_OSEL_1                        ((uint32_t)0x00400000)
+#define RTC_CR_POL                           ((uint32_t)0x00100000)
+#define RTC_CR_COSEL                         ((uint32_t)0x00080000)
+#define RTC_CR_BCK                           ((uint32_t)0x00040000)
+#define RTC_CR_SUB1H                         ((uint32_t)0x00020000)
+#define RTC_CR_ADD1H                         ((uint32_t)0x00010000)
+#define RTC_CR_TSIE                          ((uint32_t)0x00008000)
+#define RTC_CR_WUTIE                         ((uint32_t)0x00004000)
+#define RTC_CR_ALRBIE                        ((uint32_t)0x00002000)
+#define RTC_CR_ALRAIE                        ((uint32_t)0x00001000)
+#define RTC_CR_TSE                           ((uint32_t)0x00000800)
+#define RTC_CR_WUTE                          ((uint32_t)0x00000400)
+#define RTC_CR_ALRBE                         ((uint32_t)0x00000200)
+#define RTC_CR_ALRAE                         ((uint32_t)0x00000100)
+#define RTC_CR_DCE                           ((uint32_t)0x00000080)
+#define RTC_CR_FMT                           ((uint32_t)0x00000040)
+#define RTC_CR_BYPSHAD                       ((uint32_t)0x00000020)
+#define RTC_CR_REFCKON                       ((uint32_t)0x00000010)
+#define RTC_CR_TSEDGE                        ((uint32_t)0x00000008)
+#define RTC_CR_WUCKSEL                       ((uint32_t)0x00000007)
+#define RTC_CR_WUCKSEL_0                     ((uint32_t)0x00000001)
+#define RTC_CR_WUCKSEL_1                     ((uint32_t)0x00000002)
+#define RTC_CR_WUCKSEL_2                     ((uint32_t)0x00000004)
+
+/********************  Bits definition for RTC_ISR register  ******************/
+#define RTC_ISR_RECALPF                      ((uint32_t)0x00010000)
+#define RTC_ISR_TAMP1F                       ((uint32_t)0x00002000)
+#define RTC_ISR_TSOVF                        ((uint32_t)0x00001000)
+#define RTC_ISR_TSF                          ((uint32_t)0x00000800)
+#define RTC_ISR_WUTF                         ((uint32_t)0x00000400)
+#define RTC_ISR_ALRBF                        ((uint32_t)0x00000200)
+#define RTC_ISR_ALRAF                        ((uint32_t)0x00000100)
+#define RTC_ISR_INIT                         ((uint32_t)0x00000080)
+#define RTC_ISR_INITF                        ((uint32_t)0x00000040)
+#define RTC_ISR_RSF                          ((uint32_t)0x00000020)
+#define RTC_ISR_INITS                        ((uint32_t)0x00000010)
+#define RTC_ISR_SHPF                         ((uint32_t)0x00000008)
+#define RTC_ISR_WUTWF                        ((uint32_t)0x00000004)
+#define RTC_ISR_ALRBWF                       ((uint32_t)0x00000002)
+#define RTC_ISR_ALRAWF                       ((uint32_t)0x00000001)
+
+/********************  Bits definition for RTC_PRER register  *****************/
+#define RTC_PRER_PREDIV_A                    ((uint32_t)0x007F0000)
+#define RTC_PRER_PREDIV_S                    ((uint32_t)0x00001FFF)
+
+/********************  Bits definition for RTC_WUTR register  *****************/
+#define RTC_WUTR_WUT                         ((uint32_t)0x0000FFFF)
+
+/********************  Bits definition for RTC_CALIBR register  ***************/
+#define RTC_CALIBR_DCS                       ((uint32_t)0x00000080)
+#define RTC_CALIBR_DC                        ((uint32_t)0x0000001F)
+
+/********************  Bits definition for RTC_ALRMAR register  ***************/
+#define RTC_ALRMAR_MSK4                      ((uint32_t)0x80000000)
+#define RTC_ALRMAR_WDSEL                     ((uint32_t)0x40000000)
+#define RTC_ALRMAR_DT                        ((uint32_t)0x30000000)
+#define RTC_ALRMAR_DT_0                      ((uint32_t)0x10000000)
+#define RTC_ALRMAR_DT_1                      ((uint32_t)0x20000000)
+#define RTC_ALRMAR_DU                        ((uint32_t)0x0F000000)
+#define RTC_ALRMAR_DU_0                      ((uint32_t)0x01000000)
+#define RTC_ALRMAR_DU_1                      ((uint32_t)0x02000000)
+#define RTC_ALRMAR_DU_2                      ((uint32_t)0x04000000)
+#define RTC_ALRMAR_DU_3                      ((uint32_t)0x08000000)
+#define RTC_ALRMAR_MSK3                      ((uint32_t)0x00800000)
+#define RTC_ALRMAR_PM                        ((uint32_t)0x00400000)
+#define RTC_ALRMAR_HT                        ((uint32_t)0x00300000)
+#define RTC_ALRMAR_HT_0                      ((uint32_t)0x00100000)
+#define RTC_ALRMAR_HT_1                      ((uint32_t)0x00200000)
+#define RTC_ALRMAR_HU                        ((uint32_t)0x000F0000)
+#define RTC_ALRMAR_HU_0                      ((uint32_t)0x00010000)
+#define RTC_ALRMAR_HU_1                      ((uint32_t)0x00020000)
+#define RTC_ALRMAR_HU_2                      ((uint32_t)0x00040000)
+#define RTC_ALRMAR_HU_3                      ((uint32_t)0x00080000)
+#define RTC_ALRMAR_MSK2                      ((uint32_t)0x00008000)
+#define RTC_ALRMAR_MNT                       ((uint32_t)0x00007000)
+#define RTC_ALRMAR_MNT_0                     ((uint32_t)0x00001000)
+#define RTC_ALRMAR_MNT_1                     ((uint32_t)0x00002000)
+#define RTC_ALRMAR_MNT_2                     ((uint32_t)0x00004000)
+#define RTC_ALRMAR_MNU                       ((uint32_t)0x00000F00)
+#define RTC_ALRMAR_MNU_0                     ((uint32_t)0x00000100)
+#define RTC_ALRMAR_MNU_1                     ((uint32_t)0x00000200)
+#define RTC_ALRMAR_MNU_2                     ((uint32_t)0x00000400)
+#define RTC_ALRMAR_MNU_3                     ((uint32_t)0x00000800)
+#define RTC_ALRMAR_MSK1                      ((uint32_t)0x00000080)
+#define RTC_ALRMAR_ST                        ((uint32_t)0x00000070)
+#define RTC_ALRMAR_ST_0                      ((uint32_t)0x00000010)
+#define RTC_ALRMAR_ST_1                      ((uint32_t)0x00000020)
+#define RTC_ALRMAR_ST_2                      ((uint32_t)0x00000040)
+#define RTC_ALRMAR_SU                        ((uint32_t)0x0000000F)
+#define RTC_ALRMAR_SU_0                      ((uint32_t)0x00000001)
+#define RTC_ALRMAR_SU_1                      ((uint32_t)0x00000002)
+#define RTC_ALRMAR_SU_2                      ((uint32_t)0x00000004)
+#define RTC_ALRMAR_SU_3                      ((uint32_t)0x00000008)
+
+/********************  Bits definition for RTC_ALRMBR register  ***************/
+#define RTC_ALRMBR_MSK4                      ((uint32_t)0x80000000)
+#define RTC_ALRMBR_WDSEL                     ((uint32_t)0x40000000)
+#define RTC_ALRMBR_DT                        ((uint32_t)0x30000000)
+#define RTC_ALRMBR_DT_0                      ((uint32_t)0x10000000)
+#define RTC_ALRMBR_DT_1                      ((uint32_t)0x20000000)
+#define RTC_ALRMBR_DU                        ((uint32_t)0x0F000000)
+#define RTC_ALRMBR_DU_0                      ((uint32_t)0x01000000)
+#define RTC_ALRMBR_DU_1                      ((uint32_t)0x02000000)
+#define RTC_ALRMBR_DU_2                      ((uint32_t)0x04000000)
+#define RTC_ALRMBR_DU_3                      ((uint32_t)0x08000000)
+#define RTC_ALRMBR_MSK3                      ((uint32_t)0x00800000)
+#define RTC_ALRMBR_PM                        ((uint32_t)0x00400000)
+#define RTC_ALRMBR_HT                        ((uint32_t)0x00300000)
+#define RTC_ALRMBR_HT_0                      ((uint32_t)0x00100000)
+#define RTC_ALRMBR_HT_1                      ((uint32_t)0x00200000)
+#define RTC_ALRMBR_HU                        ((uint32_t)0x000F0000)
+#define RTC_ALRMBR_HU_0                      ((uint32_t)0x00010000)
+#define RTC_ALRMBR_HU_1                      ((uint32_t)0x00020000)
+#define RTC_ALRMBR_HU_2                      ((uint32_t)0x00040000)
+#define RTC_ALRMBR_HU_3                      ((uint32_t)0x00080000)
+#define RTC_ALRMBR_MSK2                      ((uint32_t)0x00008000)
+#define RTC_ALRMBR_MNT                       ((uint32_t)0x00007000)
+#define RTC_ALRMBR_MNT_0                     ((uint32_t)0x00001000)
+#define RTC_ALRMBR_MNT_1                     ((uint32_t)0x00002000)
+#define RTC_ALRMBR_MNT_2                     ((uint32_t)0x00004000)
+#define RTC_ALRMBR_MNU                       ((uint32_t)0x00000F00)
+#define RTC_ALRMBR_MNU_0                     ((uint32_t)0x00000100)
+#define RTC_ALRMBR_MNU_1                     ((uint32_t)0x00000200)
+#define RTC_ALRMBR_MNU_2                     ((uint32_t)0x00000400)
+#define RTC_ALRMBR_MNU_3                     ((uint32_t)0x00000800)
+#define RTC_ALRMBR_MSK1                      ((uint32_t)0x00000080)
+#define RTC_ALRMBR_ST                        ((uint32_t)0x00000070)
+#define RTC_ALRMBR_ST_0                      ((uint32_t)0x00000010)
+#define RTC_ALRMBR_ST_1                      ((uint32_t)0x00000020)
+#define RTC_ALRMBR_ST_2                      ((uint32_t)0x00000040)
+#define RTC_ALRMBR_SU                        ((uint32_t)0x0000000F)
+#define RTC_ALRMBR_SU_0                      ((uint32_t)0x00000001)
+#define RTC_ALRMBR_SU_1                      ((uint32_t)0x00000002)
+#define RTC_ALRMBR_SU_2                      ((uint32_t)0x00000004)
+#define RTC_ALRMBR_SU_3                      ((uint32_t)0x00000008)
+
+/********************  Bits definition for RTC_WPR register  ******************/
+#define RTC_WPR_KEY                          ((uint32_t)0x000000FF)
+
+/********************  Bits definition for RTC_SSR register  ******************/
+#define RTC_SSR_SS                           ((uint32_t)0x0000FFFF)
+
+/********************  Bits definition for RTC_SHIFTR register  ***************/
+#define RTC_SHIFTR_SUBFS                     ((uint32_t)0x00007FFF)
+#define RTC_SHIFTR_ADD1S                     ((uint32_t)0x80000000)
+
+/********************  Bits definition for RTC_TSTR register  *****************/
+#define RTC_TSTR_PM                          ((uint32_t)0x00400000)
+#define RTC_TSTR_HT                          ((uint32_t)0x00300000)
+#define RTC_TSTR_HT_0                        ((uint32_t)0x00100000)
+#define RTC_TSTR_HT_1                        ((uint32_t)0x00200000)
+#define RTC_TSTR_HU                          ((uint32_t)0x000F0000)
+#define RTC_TSTR_HU_0                        ((uint32_t)0x00010000)
+#define RTC_TSTR_HU_1                        ((uint32_t)0x00020000)
+#define RTC_TSTR_HU_2                        ((uint32_t)0x00040000)
+#define RTC_TSTR_HU_3                        ((uint32_t)0x00080000)
+#define RTC_TSTR_MNT                         ((uint32_t)0x00007000)
+#define RTC_TSTR_MNT_0                       ((uint32_t)0x00001000)
+#define RTC_TSTR_MNT_1                       ((uint32_t)0x00002000)
+#define RTC_TSTR_MNT_2                       ((uint32_t)0x00004000)
+#define RTC_TSTR_MNU                         ((uint32_t)0x00000F00)
+#define RTC_TSTR_MNU_0                       ((uint32_t)0x00000100)
+#define RTC_TSTR_MNU_1                       ((uint32_t)0x00000200)
+#define RTC_TSTR_MNU_2                       ((uint32_t)0x00000400)
+#define RTC_TSTR_MNU_3                       ((uint32_t)0x00000800)
+#define RTC_TSTR_ST                          ((uint32_t)0x00000070)
+#define RTC_TSTR_ST_0                        ((uint32_t)0x00000010)
+#define RTC_TSTR_ST_1                        ((uint32_t)0x00000020)
+#define RTC_TSTR_ST_2                        ((uint32_t)0x00000040)
+#define RTC_TSTR_SU                          ((uint32_t)0x0000000F)
+#define RTC_TSTR_SU_0                        ((uint32_t)0x00000001)
+#define RTC_TSTR_SU_1                        ((uint32_t)0x00000002)
+#define RTC_TSTR_SU_2                        ((uint32_t)0x00000004)
+#define RTC_TSTR_SU_3                        ((uint32_t)0x00000008)
+
+/********************  Bits definition for RTC_TSDR register  *****************/
+#define RTC_TSDR_WDU                         ((uint32_t)0x0000E000)
+#define RTC_TSDR_WDU_0                       ((uint32_t)0x00002000)
+#define RTC_TSDR_WDU_1                       ((uint32_t)0x00004000)
+#define RTC_TSDR_WDU_2                       ((uint32_t)0x00008000)
+#define RTC_TSDR_MT                          ((uint32_t)0x00001000)
+#define RTC_TSDR_MU                          ((uint32_t)0x00000F00)
+#define RTC_TSDR_MU_0                        ((uint32_t)0x00000100)
+#define RTC_TSDR_MU_1                        ((uint32_t)0x00000200)
+#define RTC_TSDR_MU_2                        ((uint32_t)0x00000400)
+#define RTC_TSDR_MU_3                        ((uint32_t)0x00000800)
+#define RTC_TSDR_DT                          ((uint32_t)0x00000030)
+#define RTC_TSDR_DT_0                        ((uint32_t)0x00000010)
+#define RTC_TSDR_DT_1                        ((uint32_t)0x00000020)
+#define RTC_TSDR_DU                          ((uint32_t)0x0000000F)
+#define RTC_TSDR_DU_0                        ((uint32_t)0x00000001)
+#define RTC_TSDR_DU_1                        ((uint32_t)0x00000002)
+#define RTC_TSDR_DU_2                        ((uint32_t)0x00000004)
+#define RTC_TSDR_DU_3                        ((uint32_t)0x00000008)
+
+/********************  Bits definition for RTC_TSSSR register  ****************/
+#define RTC_TSSSR_SS                         ((uint32_t)0x0000FFFF)
+
+/********************  Bits definition for RTC_CAL register  *****************/
+#define RTC_CALR_CALP                        ((uint32_t)0x00008000)
+#define RTC_CALR_CALW8                       ((uint32_t)0x00004000)
+#define RTC_CALR_CALW16                      ((uint32_t)0x00002000)
+#define RTC_CALR_CALM                        ((uint32_t)0x000001FF)
+#define RTC_CALR_CALM_0                      ((uint32_t)0x00000001)
+#define RTC_CALR_CALM_1                      ((uint32_t)0x00000002)
+#define RTC_CALR_CALM_2                      ((uint32_t)0x00000004)
+#define RTC_CALR_CALM_3                      ((uint32_t)0x00000008)
+#define RTC_CALR_CALM_4                      ((uint32_t)0x00000010)
+#define RTC_CALR_CALM_5                      ((uint32_t)0x00000020)
+#define RTC_CALR_CALM_6                      ((uint32_t)0x00000040)
+#define RTC_CALR_CALM_7                      ((uint32_t)0x00000080)
+#define RTC_CALR_CALM_8                      ((uint32_t)0x00000100)
+
+/********************  Bits definition for RTC_TAFCR register  ****************/
+#define RTC_TAFCR_ALARMOUTTYPE               ((uint32_t)0x00040000)
+#define RTC_TAFCR_TSINSEL                    ((uint32_t)0x00020000)
+#define RTC_TAFCR_TAMPINSEL                  ((uint32_t)0x00010000)
+#define RTC_TAFCR_TAMPPUDIS                  ((uint32_t)0x00008000)
+#define RTC_TAFCR_TAMPPRCH                   ((uint32_t)0x00006000)
+#define RTC_TAFCR_TAMPPRCH_0                 ((uint32_t)0x00002000)
+#define RTC_TAFCR_TAMPPRCH_1                 ((uint32_t)0x00004000)
+#define RTC_TAFCR_TAMPFLT                    ((uint32_t)0x00001800)
+#define RTC_TAFCR_TAMPFLT_0                  ((uint32_t)0x00000800)
+#define RTC_TAFCR_TAMPFLT_1                  ((uint32_t)0x00001000)
+#define RTC_TAFCR_TAMPFREQ                   ((uint32_t)0x00000700)
+#define RTC_TAFCR_TAMPFREQ_0                 ((uint32_t)0x00000100)
+#define RTC_TAFCR_TAMPFREQ_1                 ((uint32_t)0x00000200)
+#define RTC_TAFCR_TAMPFREQ_2                 ((uint32_t)0x00000400)
+#define RTC_TAFCR_TAMPTS                     ((uint32_t)0x00000080)
+#define RTC_TAFCR_TAMPIE                     ((uint32_t)0x00000004)
+#define RTC_TAFCR_TAMP1TRG                   ((uint32_t)0x00000002)
+#define RTC_TAFCR_TAMP1E                     ((uint32_t)0x00000001)
+
+/********************  Bits definition for RTC_ALRMASSR register  *************/
+#define RTC_ALRMASSR_MASKSS                  ((uint32_t)0x0F000000)
+#define RTC_ALRMASSR_MASKSS_0                ((uint32_t)0x01000000)
+#define RTC_ALRMASSR_MASKSS_1                ((uint32_t)0x02000000)
+#define RTC_ALRMASSR_MASKSS_2                ((uint32_t)0x04000000)
+#define RTC_ALRMASSR_MASKSS_3                ((uint32_t)0x08000000)
+#define RTC_ALRMASSR_SS                      ((uint32_t)0x00007FFF)
+
+/********************  Bits definition for RTC_ALRMBSSR register  *************/
+#define RTC_ALRMBSSR_MASKSS                  ((uint32_t)0x0F000000)
+#define RTC_ALRMBSSR_MASKSS_0                ((uint32_t)0x01000000)
+#define RTC_ALRMBSSR_MASKSS_1                ((uint32_t)0x02000000)
+#define RTC_ALRMBSSR_MASKSS_2                ((uint32_t)0x04000000)
+#define RTC_ALRMBSSR_MASKSS_3                ((uint32_t)0x08000000)
+#define RTC_ALRMBSSR_SS                      ((uint32_t)0x00007FFF)
+
+/********************  Bits definition for RTC_BKP0R register  ****************/
+#define RTC_BKP0R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP1R register  ****************/
+#define RTC_BKP1R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP2R register  ****************/
+#define RTC_BKP2R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP3R register  ****************/
+#define RTC_BKP3R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP4R register  ****************/
+#define RTC_BKP4R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP5R register  ****************/
+#define RTC_BKP5R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP6R register  ****************/
+#define RTC_BKP6R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP7R register  ****************/
+#define RTC_BKP7R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP8R register  ****************/
+#define RTC_BKP8R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP9R register  ****************/
+#define RTC_BKP9R                            ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP10R register  ***************/
+#define RTC_BKP10R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP11R register  ***************/
+#define RTC_BKP11R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP12R register  ***************/
+#define RTC_BKP12R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP13R register  ***************/
+#define RTC_BKP13R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP14R register  ***************/
+#define RTC_BKP14R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP15R register  ***************/
+#define RTC_BKP15R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP16R register  ***************/
+#define RTC_BKP16R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP17R register  ***************/
+#define RTC_BKP17R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP18R register  ***************/
+#define RTC_BKP18R                           ((uint32_t)0xFFFFFFFF)
+
+/********************  Bits definition for RTC_BKP19R register  ***************/
+#define RTC_BKP19R                           ((uint32_t)0xFFFFFFFF)
+
+/******************************************************************************/
+/*                                                                            */
+/*                          Serial Audio Interface                            */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bit definition for SAI_GCR register  *******************/
+#define  SAI_GCR_SYNCIN                  ((uint32_t)0x00000003)        /*!<SYNCIN[1:0] bits (Synchronization Inputs)   */
+#define  SAI_GCR_SYNCIN_0                ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  SAI_GCR_SYNCIN_1                ((uint32_t)0x00000002)        /*!<Bit 1 */
+
+#define  SAI_GCR_SYNCOUT                 ((uint32_t)0x00000030)        /*!<SYNCOUT[1:0] bits (Synchronization Outputs) */
+#define  SAI_GCR_SYNCOUT_0               ((uint32_t)0x00000010)        /*!<Bit 0 */
+#define  SAI_GCR_SYNCOUT_1               ((uint32_t)0x00000020)        /*!<Bit 1 */
+
+/*******************  Bit definition for SAI_xCR1 register  *******************/
+#define  SAI_xCR1_MODE                    ((uint32_t)0x00000003)        /*!<MODE[1:0] bits (Audio Block Mode)           */
+#define  SAI_xCR1_MODE_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  SAI_xCR1_MODE_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+
+#define  SAI_xCR1_PRTCFG                  ((uint32_t)0x0000000C)        /*!<PRTCFG[1:0] bits (Protocol Configuration)   */
+#define  SAI_xCR1_PRTCFG_0                ((uint32_t)0x00000004)        /*!<Bit 0 */
+#define  SAI_xCR1_PRTCFG_1                ((uint32_t)0x00000008)        /*!<Bit 1 */
+
+#define  SAI_xCR1_DS                      ((uint32_t)0x000000E0)        /*!<DS[1:0] bits (Data Size) */
+#define  SAI_xCR1_DS_0                    ((uint32_t)0x00000020)        /*!<Bit 0 */
+#define  SAI_xCR1_DS_1                    ((uint32_t)0x00000040)        /*!<Bit 1 */
+#define  SAI_xCR1_DS_2                    ((uint32_t)0x00000080)        /*!<Bit 2 */
+
+#define  SAI_xCR1_LSBFIRST                ((uint32_t)0x00000100)        /*!<LSB First Configuration  */
+#define  SAI_xCR1_CKSTR                   ((uint32_t)0x00000200)        /*!<ClocK STRobing edge      */
+
+#define  SAI_xCR1_SYNCEN                  ((uint32_t)0x00000C00)        /*!<SYNCEN[1:0](SYNChronization ENable) */
+#define  SAI_xCR1_SYNCEN_0                ((uint32_t)0x00000400)        /*!<Bit 0 */
+#define  SAI_xCR1_SYNCEN_1                ((uint32_t)0x00000800)        /*!<Bit 1 */
+
+#define  SAI_xCR1_MONO                    ((uint32_t)0x00001000)        /*!<Mono mode                  */
+#define  SAI_xCR1_OUTDRIV                 ((uint32_t)0x00002000)        /*!<Output Drive               */
+#define  SAI_xCR1_SAIEN                   ((uint32_t)0x00010000)        /*!<Audio Block enable         */
+#define  SAI_xCR1_DMAEN                   ((uint32_t)0x00020000)        /*!<DMA enable                 */
+#define  SAI_xCR1_NODIV                   ((uint32_t)0x00080000)        /*!<No Divider Configuration   */
+
+#define  SAI_xCR1_MCKDIV                  ((uint32_t)0x00780000)        /*!<MCKDIV[3:0] (Master ClocK Divider)  */
+#define  SAI_xCR1_MCKDIV_0                ((uint32_t)0x00080000)        /*!<Bit 0  */
+#define  SAI_xCR1_MCKDIV_1                ((uint32_t)0x00100000)        /*!<Bit 1  */
+#define  SAI_xCR1_MCKDIV_2                ((uint32_t)0x00200000)        /*!<Bit 2  */
+#define  SAI_xCR1_MCKDIV_3                ((uint32_t)0x00400000)        /*!<Bit 3  */
+
+/*******************  Bit definition for SAI_xCR2 register  *******************/
+#define  SAI_xCR2_FTH                     ((uint32_t)0x00000003)        /*!<FTH[1:0](Fifo THreshold)  */
+#define  SAI_xCR2_FTH_0                   ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  SAI_xCR2_FTH_1                   ((uint32_t)0x00000002)        /*!<Bit 1 */
+
+#define  SAI_xCR2_FFLUSH                  ((uint32_t)0x00000008)        /*!<Fifo FLUSH                       */
+#define  SAI_xCR2_TRIS                    ((uint32_t)0x00000010)        /*!<TRIState Management on data line */
+#define  SAI_xCR2_MUTE                    ((uint32_t)0x00000020)        /*!<Mute mode                        */
+#define  SAI_xCR2_MUTEVAL                 ((uint32_t)0x00000040)        /*!<Muate value                      */
+
+#define  SAI_xCR2_MUTECNT                  ((uint32_t)0x00001F80)       /*!<MUTECNT[5:0] (MUTE counter) */
+#define  SAI_xCR2_MUTECNT_0               ((uint32_t)0x00000080)        /*!<Bit 0 */
+#define  SAI_xCR2_MUTECNT_1               ((uint32_t)0x00000100)        /*!<Bit 1 */
+#define  SAI_xCR2_MUTECNT_2               ((uint32_t)0x00000200)        /*!<Bit 2 */
+#define  SAI_xCR2_MUTECNT_3               ((uint32_t)0x00000400)        /*!<Bit 3 */
+#define  SAI_xCR2_MUTECNT_4               ((uint32_t)0x00000800)        /*!<Bit 4 */
+#define  SAI_xCR2_MUTECNT_5               ((uint32_t)0x00001000)        /*!<Bit 5 */
+
+#define  SAI_xCR2_CPL                     ((uint32_t)0x00080000)        /*!< Complement Bit             */
+
+#define  SAI_xCR2_COMP                    ((uint32_t)0x0000C000)        /*!<COMP[1:0] (Companding mode) */
+#define  SAI_xCR2_COMP_0                  ((uint32_t)0x00004000)        /*!<Bit 0 */
+#define  SAI_xCR2_COMP_1                  ((uint32_t)0x00008000)        /*!<Bit 1 */
+
+/******************  Bit definition for SAI_xFRCR register  *******************/
+#define  SAI_xFRCR_FRL                    ((uint32_t)0x000000FF)        /*!<FRL[1:0](Frame length)  */
+#define  SAI_xFRCR_FRL_0                  ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  SAI_xFRCR_FRL_1                  ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  SAI_xFRCR_FRL_2                  ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  SAI_xFRCR_FRL_3                  ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  SAI_xFRCR_FRL_4                  ((uint32_t)0x00000010)        /*!<Bit 4 */
+#define  SAI_xFRCR_FRL_5                  ((uint32_t)0x00000020)        /*!<Bit 5 */
+#define  SAI_xFRCR_FRL_6                  ((uint32_t)0x00000040)        /*!<Bit 6 */
+#define  SAI_xFRCR_FRL_7                  ((uint32_t)0x00000080)        /*!<Bit 7 */
+
+#define  SAI_xFRCR_FSALL                  ((uint32_t)0x00007F00)        /*!<FRL[1:0] (Frame synchronization active level length)  */
+#define  SAI_xFRCR_FSALL_0                ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  SAI_xFRCR_FSALL_1                ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  SAI_xFRCR_FSALL_2                ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  SAI_xFRCR_FSALL_3                ((uint32_t)0x00000800)        /*!<Bit 3 */
+#define  SAI_xFRCR_FSALL_4                ((uint32_t)0x00001000)        /*!<Bit 4 */
+#define  SAI_xFRCR_FSALL_5                ((uint32_t)0x00002000)        /*!<Bit 5 */
+#define  SAI_xFRCR_FSALL_6                ((uint32_t)0x00004000)        /*!<Bit 6 */
+
+#define  SAI_xFRCR_FSDEF                  ((uint32_t)0x00010000)        /*!< Frame Synchronization Definition */
+#define  SAI_xFRCR_FSPO                   ((uint32_t)0x00020000)        /*!<Frame Synchronization POLarity    */
+#define  SAI_xFRCR_FSOFF                  ((uint32_t)0x00040000)        /*!<Frame Synchronization OFFset      */
+
+/******************  Bit definition for SAI_xSLOTR register  *******************/
+#define  SAI_xSLOTR_FBOFF                 ((uint32_t)0x0000001F)        /*!<FRL[4:0](First Bit Offset)  */
+#define  SAI_xSLOTR_FBOFF_0               ((uint32_t)0x00000001)        /*!<Bit 0 */
+#define  SAI_xSLOTR_FBOFF_1               ((uint32_t)0x00000002)        /*!<Bit 1 */
+#define  SAI_xSLOTR_FBOFF_2               ((uint32_t)0x00000004)        /*!<Bit 2 */
+#define  SAI_xSLOTR_FBOFF_3               ((uint32_t)0x00000008)        /*!<Bit 3 */
+#define  SAI_xSLOTR_FBOFF_4               ((uint32_t)0x00000010)        /*!<Bit 4 */
+                                     
+#define  SAI_xSLOTR_SLOTSZ                ((uint32_t)0x000000C0)        /*!<SLOTSZ[1:0] (Slot size)  */
+#define  SAI_xSLOTR_SLOTSZ_0              ((uint32_t)0x00000040)        /*!<Bit 0 */
+#define  SAI_xSLOTR_SLOTSZ_1              ((uint32_t)0x00000080)        /*!<Bit 1 */
+
+#define  SAI_xSLOTR_NBSLOT                ((uint32_t)0x00000F00)        /*!<NBSLOT[3:0] (Number of Slot in audio Frame)  */
+#define  SAI_xSLOTR_NBSLOT_0              ((uint32_t)0x00000100)        /*!<Bit 0 */
+#define  SAI_xSLOTR_NBSLOT_1              ((uint32_t)0x00000200)        /*!<Bit 1 */
+#define  SAI_xSLOTR_NBSLOT_2              ((uint32_t)0x00000400)        /*!<Bit 2 */
+#define  SAI_xSLOTR_NBSLOT_3              ((uint32_t)0x00000800)        /*!<Bit 3 */
+
+#define  SAI_xSLOTR_SLOTEN                ((uint32_t)0xFFFF0000)        /*!<SLOTEN[15:0] (Slot Enable)  */
+
+/*******************  Bit definition for SAI_xIMR register  *******************/
+#define  SAI_xIMR_OVRUDRIE                ((uint32_t)0x00000001)        /*!<Overrun underrun interrupt enable                              */
+#define  SAI_xIMR_MUTEDETIE               ((uint32_t)0x00000002)        /*!<Mute detection interrupt enable                                */
+#define  SAI_xIMR_WCKCFGIE                ((uint32_t)0x00000004)        /*!<Wrong Clock Configuration interrupt enable                     */
+#define  SAI_xIMR_FREQIE                  ((uint32_t)0x00000008)        /*!<FIFO request interrupt enable                                  */
+#define  SAI_xIMR_CNRDYIE                 ((uint32_t)0x00000010)        /*!<Codec not ready interrupt enable                               */
+#define  SAI_xIMR_AFSDETIE                ((uint32_t)0x00000020)        /*!<Anticipated frame synchronization detection interrupt enable   */
+#define  SAI_xIMR_LFSDETIE                ((uint32_t)0x00000040)        /*!<Late frame synchronization detection interrupt enable          */
+
+/********************  Bit definition for SAI_xSR register  *******************/
+#define  SAI_xSR_OVRUDR                   ((uint32_t)0x00000001)         /*!<Overrun underrun                               */
+#define  SAI_xSR_MUTEDET                  ((uint32_t)0x00000002)         /*!<Mute detection                                 */
+#define  SAI_xSR_WCKCFG                   ((uint32_t)0x00000004)         /*!<Wrong Clock Configuration                      */
+#define  SAI_xSR_FREQ                     ((uint32_t)0x00000008)         /*!<FIFO request                                   */
+#define  SAI_xSR_CNRDY                    ((uint32_t)0x00000010)         /*!<Codec not ready                                */
+#define  SAI_xSR_AFSDET                   ((uint32_t)0x00000020)         /*!<Anticipated frame synchronization detection    */
+#define  SAI_xSR_LFSDET                   ((uint32_t)0x00000040)         /*!<Late frame synchronization detection           */
+
+#define  SAI_xSR_FLVL                     ((uint32_t)0x00070000)         /*!<FLVL[2:0] (FIFO Level Threshold)               */
+#define  SAI_xSR_FLVL_0                   ((uint32_t)0x00010000)         /*!<Bit 0 */
+#define  SAI_xSR_FLVL_1                   ((uint32_t)0x00020000)         /*!<Bit 1 */
+#define  SAI_xSR_FLVL_2                   ((uint32_t)0x00030000)         /*!<Bit 2 */
+
+/******************  Bit definition for SAI_xCLRFR register  ******************/
+#define  SAI_xCLRFR_COVRUDR               ((uint32_t)0x00000001)        /*!<Clear Overrun underrun                               */
+#define  SAI_xCLRFR_CMUTEDET              ((uint32_t)0x00000002)        /*!<Clear Mute detection                                 */
+#define  SAI_xCLRFR_CWCKCFG               ((uint32_t)0x00000004)        /*!<Clear Wrong Clock Configuration                      */
+#define  SAI_xCLRFR_CFREQ                 ((uint32_t)0x00000008)        /*!<Clear FIFO request                                   */
+#define  SAI_xCLRFR_CCNRDY                ((uint32_t)0x00000010)        /*!<Clear Codec not ready                                */
+#define  SAI_xCLRFR_CAFSDET               ((uint32_t)0x00000020)        /*!<Clear Anticipated frame synchronization detection    */
+#define  SAI_xCLRFR_CLFSDET               ((uint32_t)0x00000040)        /*!<Clear Late frame synchronization detection           */
+
+/******************  Bit definition for SAI_xDR register  ******************/
+#define  SAI_xDR_DATA                     ((uint32_t)0xFFFFFFFF)        
+
+/******************************************************************************/
+/*                                                                            */
+/*                          SD host Interface                                 */
+/*                                                                            */
+/******************************************************************************/
+/******************  Bit definition for SDIO_POWER register  ******************/
+#define  SDIO_POWER_PWRCTRL                  ((uint8_t)0x03)               /*!<PWRCTRL[1:0] bits (Power supply control bits) */
+#define  SDIO_POWER_PWRCTRL_0                ((uint8_t)0x01)               /*!<Bit 0 */
+#define  SDIO_POWER_PWRCTRL_1                ((uint8_t)0x02)               /*!<Bit 1 */
+
+/******************  Bit definition for SDIO_CLKCR register  ******************/
+#define  SDIO_CLKCR_CLKDIV                   ((uint16_t)0x00FF)            /*!<Clock divide factor             */
+#define  SDIO_CLKCR_CLKEN                    ((uint16_t)0x0100)            /*!<Clock enable bit                */
+#define  SDIO_CLKCR_PWRSAV                   ((uint16_t)0x0200)            /*!<Power saving configuration bit  */
+#define  SDIO_CLKCR_BYPASS                   ((uint16_t)0x0400)            /*!<Clock divider bypass enable bit */
+
+#define  SDIO_CLKCR_WIDBUS                   ((uint16_t)0x1800)            /*!<WIDBUS[1:0] bits (Wide bus mode enable bit) */
+#define  SDIO_CLKCR_WIDBUS_0                 ((uint16_t)0x0800)            /*!<Bit 0 */
+#define  SDIO_CLKCR_WIDBUS_1                 ((uint16_t)0x1000)            /*!<Bit 1 */
+
+#define  SDIO_CLKCR_NEGEDGE                  ((uint16_t)0x2000)            /*!<SDIO_CK dephasing selection bit */
+#define  SDIO_CLKCR_HWFC_EN                  ((uint16_t)0x4000)            /*!<HW Flow Control enable          */
+
+/*******************  Bit definition for SDIO_ARG register  *******************/
+#define  SDIO_ARG_CMDARG                     ((uint32_t)0xFFFFFFFF)            /*!<Command argument */
+
+/*******************  Bit definition for SDIO_CMD register  *******************/
+#define  SDIO_CMD_CMDINDEX                   ((uint16_t)0x003F)            /*!<Command Index                               */
+
+#define  SDIO_CMD_WAITRESP                   ((uint16_t)0x00C0)            /*!<WAITRESP[1:0] bits (Wait for response bits) */
+#define  SDIO_CMD_WAITRESP_0                 ((uint16_t)0x0040)            /*!< Bit 0 */
+#define  SDIO_CMD_WAITRESP_1                 ((uint16_t)0x0080)            /*!< Bit 1 */
+
+#define  SDIO_CMD_WAITINT                    ((uint16_t)0x0100)            /*!<CPSM Waits for Interrupt Request                               */
+#define  SDIO_CMD_WAITPEND                   ((uint16_t)0x0200)            /*!<CPSM Waits for ends of data transfer (CmdPend internal signal) */
+#define  SDIO_CMD_CPSMEN                     ((uint16_t)0x0400)            /*!<Command path state machine (CPSM) Enable bit                   */
+#define  SDIO_CMD_SDIOSUSPEND                ((uint16_t)0x0800)            /*!<SD I/O suspend command                                         */
+#define  SDIO_CMD_ENCMDCOMPL                 ((uint16_t)0x1000)            /*!<Enable CMD completion                                          */
+#define  SDIO_CMD_NIEN                       ((uint16_t)0x2000)            /*!<Not Interrupt Enable */
+#define  SDIO_CMD_CEATACMD                   ((uint16_t)0x4000)            /*!<CE-ATA command       */
+
+/*****************  Bit definition for SDIO_RESPCMD register  *****************/
+#define  SDIO_RESPCMD_RESPCMD                ((uint8_t)0x3F)               /*!<Response command index */
+
+/******************  Bit definition for SDIO_RESP0 register  ******************/
+#define  SDIO_RESP0_CARDSTATUS0              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP1 register  ******************/
+#define  SDIO_RESP1_CARDSTATUS1              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP2 register  ******************/
+#define  SDIO_RESP2_CARDSTATUS2              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP3 register  ******************/
+#define  SDIO_RESP3_CARDSTATUS3              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_RESP4 register  ******************/
+#define  SDIO_RESP4_CARDSTATUS4              ((uint32_t)0xFFFFFFFF)        /*!<Card Status */
+
+/******************  Bit definition for SDIO_DTIMER register  *****************/
+#define  SDIO_DTIMER_DATATIME                ((uint32_t)0xFFFFFFFF)        /*!<Data timeout period. */
+
+/******************  Bit definition for SDIO_DLEN register  *******************/
+#define  SDIO_DLEN_DATALENGTH                ((uint32_t)0x01FFFFFF)        /*!<Data length value    */
+
+/******************  Bit definition for SDIO_DCTRL register  ******************/
+#define  SDIO_DCTRL_DTEN                     ((uint16_t)0x0001)            /*!<Data transfer enabled bit         */
+#define  SDIO_DCTRL_DTDIR                    ((uint16_t)0x0002)            /*!<Data transfer direction selection */
+#define  SDIO_DCTRL_DTMODE                   ((uint16_t)0x0004)            /*!<Data transfer mode selection      */
+#define  SDIO_DCTRL_DMAEN                    ((uint16_t)0x0008)            /*!<DMA enabled bit                   */
+
+#define  SDIO_DCTRL_DBLOCKSIZE               ((uint16_t)0x00F0)            /*!<DBLOCKSIZE[3:0] bits (Data block size) */
+#define  SDIO_DCTRL_DBLOCKSIZE_0             ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  SDIO_DCTRL_DBLOCKSIZE_1             ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  SDIO_DCTRL_DBLOCKSIZE_2             ((uint16_t)0x0040)            /*!<Bit 2 */
+#define  SDIO_DCTRL_DBLOCKSIZE_3             ((uint16_t)0x0080)            /*!<Bit 3 */
+
+#define  SDIO_DCTRL_RWSTART                  ((uint16_t)0x0100)            /*!<Read wait start         */
+#define  SDIO_DCTRL_RWSTOP                   ((uint16_t)0x0200)            /*!<Read wait stop          */
+#define  SDIO_DCTRL_RWMOD                    ((uint16_t)0x0400)            /*!<Read wait mode          */
+#define  SDIO_DCTRL_SDIOEN                   ((uint16_t)0x0800)            /*!<SD I/O enable functions */
+
+/******************  Bit definition for SDIO_DCOUNT register  *****************/
+#define  SDIO_DCOUNT_DATACOUNT               ((uint32_t)0x01FFFFFF)        /*!<Data count value */
+
+/******************  Bit definition for SDIO_STA register  ********************/
+#define  SDIO_STA_CCRCFAIL                   ((uint32_t)0x00000001)        /*!<Command response received (CRC check failed)  */
+#define  SDIO_STA_DCRCFAIL                   ((uint32_t)0x00000002)        /*!<Data block sent/received (CRC check failed)   */
+#define  SDIO_STA_CTIMEOUT                   ((uint32_t)0x00000004)        /*!<Command response timeout                      */
+#define  SDIO_STA_DTIMEOUT                   ((uint32_t)0x00000008)        /*!<Data timeout                                  */
+#define  SDIO_STA_TXUNDERR                   ((uint32_t)0x00000010)        /*!<Transmit FIFO underrun error                  */
+#define  SDIO_STA_RXOVERR                    ((uint32_t)0x00000020)        /*!<Received FIFO overrun error                   */
+#define  SDIO_STA_CMDREND                    ((uint32_t)0x00000040)        /*!<Command response received (CRC check passed)  */
+#define  SDIO_STA_CMDSENT                    ((uint32_t)0x00000080)        /*!<Command sent (no response required)           */
+#define  SDIO_STA_DATAEND                    ((uint32_t)0x00000100)        /*!<Data end (data counter, SDIDCOUNT, is zero)   */
+#define  SDIO_STA_STBITERR                   ((uint32_t)0x00000200)        /*!<Start bit not detected on all data signals in wide bus mode */
+#define  SDIO_STA_DBCKEND                    ((uint32_t)0x00000400)        /*!<Data block sent/received (CRC check passed)   */
+#define  SDIO_STA_CMDACT                     ((uint32_t)0x00000800)        /*!<Command transfer in progress                  */
+#define  SDIO_STA_TXACT                      ((uint32_t)0x00001000)        /*!<Data transmit in progress                     */
+#define  SDIO_STA_RXACT                      ((uint32_t)0x00002000)        /*!<Data receive in progress                      */
+#define  SDIO_STA_TXFIFOHE                   ((uint32_t)0x00004000)        /*!<Transmit FIFO Half Empty: at least 8 words can be written into the FIFO */
+#define  SDIO_STA_RXFIFOHF                   ((uint32_t)0x00008000)        /*!<Receive FIFO Half Full: there are at least 8 words in the FIFO */
+#define  SDIO_STA_TXFIFOF                    ((uint32_t)0x00010000)        /*!<Transmit FIFO full                            */
+#define  SDIO_STA_RXFIFOF                    ((uint32_t)0x00020000)        /*!<Receive FIFO full                             */
+#define  SDIO_STA_TXFIFOE                    ((uint32_t)0x00040000)        /*!<Transmit FIFO empty                           */
+#define  SDIO_STA_RXFIFOE                    ((uint32_t)0x00080000)        /*!<Receive FIFO empty                            */
+#define  SDIO_STA_TXDAVL                     ((uint32_t)0x00100000)        /*!<Data available in transmit FIFO               */
+#define  SDIO_STA_RXDAVL                     ((uint32_t)0x00200000)        /*!<Data available in receive FIFO                */
+#define  SDIO_STA_SDIOIT                     ((uint32_t)0x00400000)        /*!<SDIO interrupt received                       */
+#define  SDIO_STA_CEATAEND                   ((uint32_t)0x00800000)        /*!<CE-ATA command completion signal received for CMD61 */
+
+/*******************  Bit definition for SDIO_ICR register  *******************/
+#define  SDIO_ICR_CCRCFAILC                  ((uint32_t)0x00000001)        /*!<CCRCFAIL flag clear bit */
+#define  SDIO_ICR_DCRCFAILC                  ((uint32_t)0x00000002)        /*!<DCRCFAIL flag clear bit */
+#define  SDIO_ICR_CTIMEOUTC                  ((uint32_t)0x00000004)        /*!<CTIMEOUT flag clear bit */
+#define  SDIO_ICR_DTIMEOUTC                  ((uint32_t)0x00000008)        /*!<DTIMEOUT flag clear bit */
+#define  SDIO_ICR_TXUNDERRC                  ((uint32_t)0x00000010)        /*!<TXUNDERR flag clear bit */
+#define  SDIO_ICR_RXOVERRC                   ((uint32_t)0x00000020)        /*!<RXOVERR flag clear bit  */
+#define  SDIO_ICR_CMDRENDC                   ((uint32_t)0x00000040)        /*!<CMDREND flag clear bit  */
+#define  SDIO_ICR_CMDSENTC                   ((uint32_t)0x00000080)        /*!<CMDSENT flag clear bit  */
+#define  SDIO_ICR_DATAENDC                   ((uint32_t)0x00000100)        /*!<DATAEND flag clear bit  */
+#define  SDIO_ICR_STBITERRC                  ((uint32_t)0x00000200)        /*!<STBITERR flag clear bit */
+#define  SDIO_ICR_DBCKENDC                   ((uint32_t)0x00000400)        /*!<DBCKEND flag clear bit  */
+#define  SDIO_ICR_SDIOITC                    ((uint32_t)0x00400000)        /*!<SDIOIT flag clear bit   */
+#define  SDIO_ICR_CEATAENDC                  ((uint32_t)0x00800000)        /*!<CEATAEND flag clear bit */
+
+/******************  Bit definition for SDIO_MASK register  *******************/
+#define  SDIO_MASK_CCRCFAILIE                ((uint32_t)0x00000001)        /*!<Command CRC Fail Interrupt Enable          */
+#define  SDIO_MASK_DCRCFAILIE                ((uint32_t)0x00000002)        /*!<Data CRC Fail Interrupt Enable             */
+#define  SDIO_MASK_CTIMEOUTIE                ((uint32_t)0x00000004)        /*!<Command TimeOut Interrupt Enable           */
+#define  SDIO_MASK_DTIMEOUTIE                ((uint32_t)0x00000008)        /*!<Data TimeOut Interrupt Enable              */
+#define  SDIO_MASK_TXUNDERRIE                ((uint32_t)0x00000010)        /*!<Tx FIFO UnderRun Error Interrupt Enable    */
+#define  SDIO_MASK_RXOVERRIE                 ((uint32_t)0x00000020)        /*!<Rx FIFO OverRun Error Interrupt Enable     */
+#define  SDIO_MASK_CMDRENDIE                 ((uint32_t)0x00000040)        /*!<Command Response Received Interrupt Enable */
+#define  SDIO_MASK_CMDSENTIE                 ((uint32_t)0x00000080)        /*!<Command Sent Interrupt Enable              */
+#define  SDIO_MASK_DATAENDIE                 ((uint32_t)0x00000100)        /*!<Data End Interrupt Enable                  */
+#define  SDIO_MASK_STBITERRIE                ((uint32_t)0x00000200)        /*!<Start Bit Error Interrupt Enable           */
+#define  SDIO_MASK_DBCKENDIE                 ((uint32_t)0x00000400)        /*!<Data Block End Interrupt Enable            */
+#define  SDIO_MASK_CMDACTIE                  ((uint32_t)0x00000800)        /*!<CCommand Acting Interrupt Enable           */
+#define  SDIO_MASK_TXACTIE                   ((uint32_t)0x00001000)        /*!<Data Transmit Acting Interrupt Enable      */
+#define  SDIO_MASK_RXACTIE                   ((uint32_t)0x00002000)        /*!<Data receive acting interrupt enabled      */
+#define  SDIO_MASK_TXFIFOHEIE                ((uint32_t)0x00004000)        /*!<Tx FIFO Half Empty interrupt Enable        */
+#define  SDIO_MASK_RXFIFOHFIE                ((uint32_t)0x00008000)        /*!<Rx FIFO Half Full interrupt Enable         */
+#define  SDIO_MASK_TXFIFOFIE                 ((uint32_t)0x00010000)        /*!<Tx FIFO Full interrupt Enable              */
+#define  SDIO_MASK_RXFIFOFIE                 ((uint32_t)0x00020000)        /*!<Rx FIFO Full interrupt Enable              */
+#define  SDIO_MASK_TXFIFOEIE                 ((uint32_t)0x00040000)        /*!<Tx FIFO Empty interrupt Enable             */
+#define  SDIO_MASK_RXFIFOEIE                 ((uint32_t)0x00080000)        /*!<Rx FIFO Empty interrupt Enable             */
+#define  SDIO_MASK_TXDAVLIE                  ((uint32_t)0x00100000)        /*!<Data available in Tx FIFO interrupt Enable */
+#define  SDIO_MASK_RXDAVLIE                  ((uint32_t)0x00200000)        /*!<Data available in Rx FIFO interrupt Enable */
+#define  SDIO_MASK_SDIOITIE                  ((uint32_t)0x00400000)        /*!<SDIO Mode Interrupt Received interrupt Enable */
+#define  SDIO_MASK_CEATAENDIE                ((uint32_t)0x00800000)        /*!<CE-ATA command completion signal received Interrupt Enable */
+
+/*****************  Bit definition for SDIO_FIFOCNT register  *****************/
+#define  SDIO_FIFOCNT_FIFOCOUNT              ((uint32_t)0x00FFFFFF)        /*!<Remaining number of words to be written to or read from the FIFO */
+
+/******************  Bit definition for SDIO_FIFO register  *******************/
+#define  SDIO_FIFO_FIFODATA                  ((uint32_t)0xFFFFFFFF)        /*!<Receive and transmit FIFO data */
+
+/******************************************************************************/
+/*                                                                            */
+/*                        Serial Peripheral Interface                         */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for SPI_CR1 register  ********************/
+#define  SPI_CR1_CPHA                        ((uint16_t)0x0001)            /*!<Clock Phase      */
+#define  SPI_CR1_CPOL                        ((uint16_t)0x0002)            /*!<Clock Polarity   */
+#define  SPI_CR1_MSTR                        ((uint16_t)0x0004)            /*!<Master Selection */
+
+#define  SPI_CR1_BR                          ((uint16_t)0x0038)            /*!<BR[2:0] bits (Baud Rate Control) */
+#define  SPI_CR1_BR_0                        ((uint16_t)0x0008)            /*!<Bit 0 */
+#define  SPI_CR1_BR_1                        ((uint16_t)0x0010)            /*!<Bit 1 */
+#define  SPI_CR1_BR_2                        ((uint16_t)0x0020)            /*!<Bit 2 */
+
+#define  SPI_CR1_SPE                         ((uint16_t)0x0040)            /*!<SPI Enable                          */
+#define  SPI_CR1_LSBFIRST                    ((uint16_t)0x0080)            /*!<Frame Format                        */
+#define  SPI_CR1_SSI                         ((uint16_t)0x0100)            /*!<Internal slave select               */
+#define  SPI_CR1_SSM                         ((uint16_t)0x0200)            /*!<Software slave management           */
+#define  SPI_CR1_RXONLY                      ((uint16_t)0x0400)            /*!<Receive only                        */
+#define  SPI_CR1_DFF                         ((uint16_t)0x0800)            /*!<Data Frame Format                   */
+#define  SPI_CR1_CRCNEXT                     ((uint16_t)0x1000)            /*!<Transmit CRC next                   */
+#define  SPI_CR1_CRCEN                       ((uint16_t)0x2000)            /*!<Hardware CRC calculation enable     */
+#define  SPI_CR1_BIDIOE                      ((uint16_t)0x4000)            /*!<Output enable in bidirectional mode */
+#define  SPI_CR1_BIDIMODE                    ((uint16_t)0x8000)            /*!<Bidirectional data mode enable      */
+
+/*******************  Bit definition for SPI_CR2 register  ********************/
+#define  SPI_CR2_RXDMAEN                     ((uint8_t)0x01)               /*!<Rx Buffer DMA Enable                 */
+#define  SPI_CR2_TXDMAEN                     ((uint8_t)0x02)               /*!<Tx Buffer DMA Enable                 */
+#define  SPI_CR2_SSOE                        ((uint8_t)0x04)               /*!<SS Output Enable                     */
+#define  SPI_CR2_ERRIE                       ((uint8_t)0x20)               /*!<Error Interrupt Enable               */
+#define  SPI_CR2_RXNEIE                      ((uint8_t)0x40)               /*!<RX buffer Not Empty Interrupt Enable */
+#define  SPI_CR2_TXEIE                       ((uint8_t)0x80)               /*!<Tx buffer Empty Interrupt Enable     */
+
+/********************  Bit definition for SPI_SR register  ********************/
+#define  SPI_SR_RXNE                         ((uint8_t)0x01)               /*!<Receive buffer Not Empty */
+#define  SPI_SR_TXE                          ((uint8_t)0x02)               /*!<Transmit buffer Empty    */
+#define  SPI_SR_CHSIDE                       ((uint8_t)0x04)               /*!<Channel side             */
+#define  SPI_SR_UDR                          ((uint8_t)0x08)               /*!<Underrun flag            */
+#define  SPI_SR_CRCERR                       ((uint8_t)0x10)               /*!<CRC Error flag           */
+#define  SPI_SR_MODF                         ((uint8_t)0x20)               /*!<Mode fault               */
+#define  SPI_SR_OVR                          ((uint8_t)0x40)               /*!<Overrun flag             */
+#define  SPI_SR_BSY                          ((uint8_t)0x80)               /*!<Busy flag                */
+
+/********************  Bit definition for SPI_DR register  ********************/
+#define  SPI_DR_DR                           ((uint16_t)0xFFFF)            /*!<Data Register           */
+
+/*******************  Bit definition for SPI_CRCPR register  ******************/
+#define  SPI_CRCPR_CRCPOLY                   ((uint16_t)0xFFFF)            /*!<CRC polynomial register */
+
+/******************  Bit definition for SPI_RXCRCR register  ******************/
+#define  SPI_RXCRCR_RXCRC                    ((uint16_t)0xFFFF)            /*!<Rx CRC Register         */
+
+/******************  Bit definition for SPI_TXCRCR register  ******************/
+#define  SPI_TXCRCR_TXCRC                    ((uint16_t)0xFFFF)            /*!<Tx CRC Register         */
+
+/******************  Bit definition for SPI_I2SCFGR register  *****************/
+#define  SPI_I2SCFGR_CHLEN                   ((uint16_t)0x0001)            /*!<Channel length (number of bits per audio channel) */
+
+#define  SPI_I2SCFGR_DATLEN                  ((uint16_t)0x0006)            /*!<DATLEN[1:0] bits (Data length to be transferred)  */
+#define  SPI_I2SCFGR_DATLEN_0                ((uint16_t)0x0002)            /*!<Bit 0 */
+#define  SPI_I2SCFGR_DATLEN_1                ((uint16_t)0x0004)            /*!<Bit 1 */
+
+#define  SPI_I2SCFGR_CKPOL                   ((uint16_t)0x0008)            /*!<steady state clock polarity               */
+
+#define  SPI_I2SCFGR_I2SSTD                  ((uint16_t)0x0030)            /*!<I2SSTD[1:0] bits (I2S standard selection) */
+#define  SPI_I2SCFGR_I2SSTD_0                ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  SPI_I2SCFGR_I2SSTD_1                ((uint16_t)0x0020)            /*!<Bit 1 */
+
+#define  SPI_I2SCFGR_PCMSYNC                 ((uint16_t)0x0080)            /*!<PCM frame synchronization                 */
+
+#define  SPI_I2SCFGR_I2SCFG                  ((uint16_t)0x0300)            /*!<I2SCFG[1:0] bits (I2S configuration mode) */
+#define  SPI_I2SCFGR_I2SCFG_0                ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  SPI_I2SCFGR_I2SCFG_1                ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  SPI_I2SCFGR_I2SE                    ((uint16_t)0x0400)            /*!<I2S Enable         */
+#define  SPI_I2SCFGR_I2SMOD                  ((uint16_t)0x0800)            /*!<I2S mode selection */
+
+/******************  Bit definition for SPI_I2SPR register  *******************/
+#define  SPI_I2SPR_I2SDIV                    ((uint16_t)0x00FF)            /*!<I2S Linear prescaler         */
+#define  SPI_I2SPR_ODD                       ((uint16_t)0x0100)            /*!<Odd factor for the prescaler */
+#define  SPI_I2SPR_MCKOE                     ((uint16_t)0x0200)            /*!<Master Clock Output Enable   */
+
+/******************************************************************************/
+/*                                                                            */
+/*                                 SYSCFG                                     */
+/*                                                                            */
+/******************************************************************************/
+/******************  Bit definition for SYSCFG_MEMRMP register  ***************/  
+#define SYSCFG_MEMRMP_MEM_MODE          ((uint32_t)0x00000007) /*!< SYSCFG_Memory Remap Config */
+#define SYSCFG_MEMRMP_MEM_MODE_0        ((uint32_t)0x00000001) /*!<Bit 0 */
+#define SYSCFG_MEMRMP_MEM_MODE_1        ((uint32_t)0x00000002) /*!<Bit 1 */
+#define SYSCFG_MEMRMP_MEM_MODE_2        ((uint32_t)0x00000004) /*!<Bit 2 */
+
+#define SYSCFG_MEMRMP_FB_MODE           ((uint32_t)0x00000100) /*!< User Flash Bank mode */
+
+#define SYSCFG_MEMRMP_SWP_FMC           ((uint32_t)0x00000C00) /*!< FMC memory mapping swap */
+#define SYSCFG_MEMRMP_SWP_FMC_0         ((uint32_t)0x00000400) /*!<Bit 0 */
+#define SYSCFG_MEMRMP_SWP_FMC_1         ((uint32_t)0x00000800) /*!<Bit 1 */
+
+
+/******************  Bit definition for SYSCFG_PMC register  ******************/
+#define SYSCFG_PMC_ADCxDC2              ((uint32_t)0x00070000) /*!< Refer to AN4073 on how to use this bit  */
+#define SYSCFG_PMC_ADC1DC2              ((uint32_t)0x00010000) /*!< Refer to AN4073 on how to use this bit  */
+#define SYSCFG_PMC_ADC2DC2              ((uint32_t)0x00020000) /*!< Refer to AN4073 on how to use this bit  */
+#define SYSCFG_PMC_ADC3DC2              ((uint32_t)0x00040000) /*!< Refer to AN4073 on how to use this bit  */
+
+#define SYSCFG_PMC_MII_RMII_SEL         ((uint32_t)0x00800000) /*!<Ethernet PHY interface selection */
+/* Old MII_RMII_SEL bit definition, maintained for legacy purpose */
+#define SYSCFG_PMC_MII_RMII             SYSCFG_PMC_MII_RMII_SEL
+
+/*****************  Bit definition for SYSCFG_EXTICR1 register  ***************/
+#define SYSCFG_EXTICR1_EXTI0            ((uint16_t)0x000F) /*!<EXTI 0 configuration */
+#define SYSCFG_EXTICR1_EXTI1            ((uint16_t)0x00F0) /*!<EXTI 1 configuration */
+#define SYSCFG_EXTICR1_EXTI2            ((uint16_t)0x0F00) /*!<EXTI 2 configuration */
+#define SYSCFG_EXTICR1_EXTI3            ((uint16_t)0xF000) /*!<EXTI 3 configuration */
+/** 
+  * @brief   EXTI0 configuration  
+  */ 
+#define SYSCFG_EXTICR1_EXTI0_PA         ((uint16_t)0x0000) /*!<PA[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PB         ((uint16_t)0x0001) /*!<PB[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PC         ((uint16_t)0x0002) /*!<PC[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PD         ((uint16_t)0x0003) /*!<PD[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PE         ((uint16_t)0x0004) /*!<PE[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PF         ((uint16_t)0x0005) /*!<PF[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PG         ((uint16_t)0x0006) /*!<PG[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PH         ((uint16_t)0x0007) /*!<PH[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PI         ((uint16_t)0x0008) /*!<PI[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PJ         ((uint16_t)0x0009) /*!<PJ[0] pin */
+#define SYSCFG_EXTICR1_EXTI0_PK         ((uint16_t)0x000A) /*!<PK[0] pin */
+
+/** 
+  * @brief   EXTI1 configuration  
+  */ 
+#define SYSCFG_EXTICR1_EXTI1_PA         ((uint16_t)0x0000) /*!<PA[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PB         ((uint16_t)0x0010) /*!<PB[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PC         ((uint16_t)0x0020) /*!<PC[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PD         ((uint16_t)0x0030) /*!<PD[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PE         ((uint16_t)0x0040) /*!<PE[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PF         ((uint16_t)0x0050) /*!<PF[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PG         ((uint16_t)0x0060) /*!<PG[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PH         ((uint16_t)0x0070) /*!<PH[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PI         ((uint16_t)0x0080) /*!<PI[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PJ         ((uint16_t)0x0090) /*!<PJ[1] pin */
+#define SYSCFG_EXTICR1_EXTI1_PK         ((uint16_t)0x00A0) /*!<PK[1] pin */
+
+/** 
+  * @brief   EXTI2 configuration  
+  */ 
+#define SYSCFG_EXTICR1_EXTI2_PA         ((uint16_t)0x0000) /*!<PA[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PB         ((uint16_t)0x0100) /*!<PB[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PC         ((uint16_t)0x0200) /*!<PC[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PD         ((uint16_t)0x0300) /*!<PD[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PE         ((uint16_t)0x0400) /*!<PE[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PF         ((uint16_t)0x0500) /*!<PF[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PG         ((uint16_t)0x0600) /*!<PG[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PH         ((uint16_t)0x0700) /*!<PH[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PI         ((uint16_t)0x0800) /*!<PI[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PJ         ((uint16_t)0x0900) /*!<PJ[2] pin */
+#define SYSCFG_EXTICR1_EXTI2_PK         ((uint16_t)0x0A00) /*!<PK[2] pin */
+
+/** 
+  * @brief   EXTI3 configuration  
+  */ 
+#define SYSCFG_EXTICR1_EXTI3_PA         ((uint16_t)0x0000) /*!<PA[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PB         ((uint16_t)0x1000) /*!<PB[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PC         ((uint16_t)0x2000) /*!<PC[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PD         ((uint16_t)0x3000) /*!<PD[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PE         ((uint16_t)0x4000) /*!<PE[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PF         ((uint16_t)0x5000) /*!<PF[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PG         ((uint16_t)0x6000) /*!<PG[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PH         ((uint16_t)0x7000) /*!<PH[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PI         ((uint16_t)0x8000) /*!<PI[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PJ         ((uint16_t)0x9000) /*!<PJ[3] pin */
+#define SYSCFG_EXTICR1_EXTI3_PK         ((uint16_t)0xA000) /*!<PK[3] pin */
+
+/*****************  Bit definition for SYSCFG_EXTICR2 register  ***************/
+#define SYSCFG_EXTICR2_EXTI4            ((uint16_t)0x000F) /*!<EXTI 4 configuration */
+#define SYSCFG_EXTICR2_EXTI5            ((uint16_t)0x00F0) /*!<EXTI 5 configuration */
+#define SYSCFG_EXTICR2_EXTI6            ((uint16_t)0x0F00) /*!<EXTI 6 configuration */
+#define SYSCFG_EXTICR2_EXTI7            ((uint16_t)0xF000) /*!<EXTI 7 configuration */
+/** 
+  * @brief   EXTI4 configuration  
+  */ 
+#define SYSCFG_EXTICR2_EXTI4_PA         ((uint16_t)0x0000) /*!<PA[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PB         ((uint16_t)0x0001) /*!<PB[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PC         ((uint16_t)0x0002) /*!<PC[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PD         ((uint16_t)0x0003) /*!<PD[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PE         ((uint16_t)0x0004) /*!<PE[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PF         ((uint16_t)0x0005) /*!<PF[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PG         ((uint16_t)0x0006) /*!<PG[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PH         ((uint16_t)0x0007) /*!<PH[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PI         ((uint16_t)0x0008) /*!<PI[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PJ         ((uint16_t)0x0009) /*!<PJ[4] pin */
+#define SYSCFG_EXTICR2_EXTI4_PK         ((uint16_t)0x000A) /*!<PK[4] pin */
+
+/** 
+  * @brief   EXTI5 configuration  
+  */ 
+#define SYSCFG_EXTICR2_EXTI5_PA         ((uint16_t)0x0000) /*!<PA[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PB         ((uint16_t)0x0010) /*!<PB[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PC         ((uint16_t)0x0020) /*!<PC[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PD         ((uint16_t)0x0030) /*!<PD[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PE         ((uint16_t)0x0040) /*!<PE[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PF         ((uint16_t)0x0050) /*!<PF[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PG         ((uint16_t)0x0060) /*!<PG[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PH         ((uint16_t)0x0070) /*!<PH[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PI         ((uint16_t)0x0080) /*!<PI[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PJ         ((uint16_t)0x0090) /*!<PJ[5] pin */
+#define SYSCFG_EXTICR2_EXTI5_PK         ((uint16_t)0x00A0) /*!<PK[5] pin */
+
+/** 
+  * @brief   EXTI6 configuration  
+  */ 
+#define SYSCFG_EXTICR2_EXTI6_PA         ((uint16_t)0x0000) /*!<PA[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PB         ((uint16_t)0x0100) /*!<PB[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PC         ((uint16_t)0x0200) /*!<PC[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PD         ((uint16_t)0x0300) /*!<PD[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PE         ((uint16_t)0x0400) /*!<PE[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PF         ((uint16_t)0x0500) /*!<PF[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PG         ((uint16_t)0x0600) /*!<PG[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PH         ((uint16_t)0x0700) /*!<PH[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PI         ((uint16_t)0x0800) /*!<PI[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PJ         ((uint16_t)0x0900) /*!<PJ[6] pin */
+#define SYSCFG_EXTICR2_EXTI6_PK         ((uint16_t)0x0A00) /*!<PK[6] pin */
+
+/** 
+  * @brief   EXTI7 configuration  
+  */ 
+#define SYSCFG_EXTICR2_EXTI7_PA         ((uint16_t)0x0000) /*!<PA[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PB         ((uint16_t)0x1000) /*!<PB[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PC         ((uint16_t)0x2000) /*!<PC[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PD         ((uint16_t)0x3000) /*!<PD[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PE         ((uint16_t)0x4000) /*!<PE[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PF         ((uint16_t)0x5000) /*!<PF[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PG         ((uint16_t)0x6000) /*!<PG[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PH         ((uint16_t)0x7000) /*!<PH[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PI         ((uint16_t)0x8000) /*!<PI[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PJ         ((uint16_t)0x9000) /*!<PJ[7] pin */
+#define SYSCFG_EXTICR2_EXTI7_PK         ((uint16_t)0xA000) /*!<PK[7] pin */
+
+/*****************  Bit definition for SYSCFG_EXTICR3 register  ***************/
+#define SYSCFG_EXTICR3_EXTI8            ((uint16_t)0x000F) /*!<EXTI 8 configuration */
+#define SYSCFG_EXTICR3_EXTI9            ((uint16_t)0x00F0) /*!<EXTI 9 configuration */
+#define SYSCFG_EXTICR3_EXTI10           ((uint16_t)0x0F00) /*!<EXTI 10 configuration */
+#define SYSCFG_EXTICR3_EXTI11           ((uint16_t)0xF000) /*!<EXTI 11 configuration */
+           
+/** 
+  * @brief   EXTI8 configuration  
+  */ 
+#define SYSCFG_EXTICR3_EXTI8_PA         ((uint16_t)0x0000) /*!<PA[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PB         ((uint16_t)0x0001) /*!<PB[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PC         ((uint16_t)0x0002) /*!<PC[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PD         ((uint16_t)0x0003) /*!<PD[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PE         ((uint16_t)0x0004) /*!<PE[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PF         ((uint16_t)0x0005) /*!<PF[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PG         ((uint16_t)0x0006) /*!<PG[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PH         ((uint16_t)0x0007) /*!<PH[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PI         ((uint16_t)0x0008) /*!<PI[8] pin */
+#define SYSCFG_EXTICR3_EXTI8_PJ         ((uint16_t)0x0009) /*!<PJ[8] pin */
+
+/** 
+  * @brief   EXTI9 configuration  
+  */ 
+#define SYSCFG_EXTICR3_EXTI9_PA         ((uint16_t)0x0000) /*!<PA[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PB         ((uint16_t)0x0010) /*!<PB[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PC         ((uint16_t)0x0020) /*!<PC[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PD         ((uint16_t)0x0030) /*!<PD[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PE         ((uint16_t)0x0040) /*!<PE[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PF         ((uint16_t)0x0050) /*!<PF[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PG         ((uint16_t)0x0060) /*!<PG[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PH         ((uint16_t)0x0070) /*!<PH[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PI         ((uint16_t)0x0080) /*!<PI[9] pin */
+#define SYSCFG_EXTICR3_EXTI9_PJ         ((uint16_t)0x0090) /*!<PJ[9] pin */
+
+/** 
+  * @brief   EXTI10 configuration  
+  */ 
+#define SYSCFG_EXTICR3_EXTI10_PA        ((uint16_t)0x0000) /*!<PA[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PB        ((uint16_t)0x0100) /*!<PB[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PC        ((uint16_t)0x0200) /*!<PC[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PD        ((uint16_t)0x0300) /*!<PD[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PE        ((uint16_t)0x0400) /*!<PE[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PF        ((uint16_t)0x0500) /*!<PF[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PG        ((uint16_t)0x0600) /*!<PG[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PH        ((uint16_t)0x0700) /*!<PH[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PI        ((uint16_t)0x0800) /*!<PI[10] pin */
+#define SYSCFG_EXTICR3_EXTI10_PJ        ((uint16_t)0x0900) /*!<PJ[10] pin */
+
+/** 
+  * @brief   EXTI11 configuration  
+  */ 
+#define SYSCFG_EXTICR3_EXTI11_PA        ((uint16_t)0x0000) /*!<PA[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PB        ((uint16_t)0x1000) /*!<PB[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PC        ((uint16_t)0x2000) /*!<PC[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PD        ((uint16_t)0x3000) /*!<PD[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PE        ((uint16_t)0x4000) /*!<PE[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PF        ((uint16_t)0x5000) /*!<PF[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PG        ((uint16_t)0x6000) /*!<PG[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PH        ((uint16_t)0x7000) /*!<PH[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PI        ((uint16_t)0x8000) /*!<PI[11] pin */
+#define SYSCFG_EXTICR3_EXTI11_PJ        ((uint16_t)0x9000) /*!<PJ[11] pin */
+
+/*****************  Bit definition for SYSCFG_EXTICR4 register  ***************/
+#define SYSCFG_EXTICR4_EXTI12           ((uint16_t)0x000F) /*!<EXTI 12 configuration */
+#define SYSCFG_EXTICR4_EXTI13           ((uint16_t)0x00F0) /*!<EXTI 13 configuration */
+#define SYSCFG_EXTICR4_EXTI14           ((uint16_t)0x0F00) /*!<EXTI 14 configuration */
+#define SYSCFG_EXTICR4_EXTI15           ((uint16_t)0xF000) /*!<EXTI 15 configuration */
+/** 
+  * @brief   EXTI12 configuration  
+  */ 
+#define SYSCFG_EXTICR4_EXTI12_PA        ((uint16_t)0x0000) /*!<PA[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PB        ((uint16_t)0x0001) /*!<PB[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PC        ((uint16_t)0x0002) /*!<PC[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PD        ((uint16_t)0x0003) /*!<PD[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PE        ((uint16_t)0x0004) /*!<PE[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PF        ((uint16_t)0x0005) /*!<PF[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PG        ((uint16_t)0x0006) /*!<PG[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PH        ((uint16_t)0x0007) /*!<PH[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PI        ((uint16_t)0x0008) /*!<PI[12] pin */
+#define SYSCFG_EXTICR4_EXTI12_PJ        ((uint16_t)0x0009) /*!<PJ[12] pin */
+
+/** 
+  * @brief   EXTI13 configuration  
+  */ 
+#define SYSCFG_EXTICR4_EXTI13_PA        ((uint16_t)0x0000) /*!<PA[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PB        ((uint16_t)0x0010) /*!<PB[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PC        ((uint16_t)0x0020) /*!<PC[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PD        ((uint16_t)0x0030) /*!<PD[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PE        ((uint16_t)0x0040) /*!<PE[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PF        ((uint16_t)0x0050) /*!<PF[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PG        ((uint16_t)0x0060) /*!<PG[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PH        ((uint16_t)0x0070) /*!<PH[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PI        ((uint16_t)0x0008) /*!<PI[13] pin */
+#define SYSCFG_EXTICR4_EXTI13_PJ        ((uint16_t)0x0009) /*!<PJ[13] pin */
+
+/** 
+  * @brief   EXTI14 configuration  
+  */ 
+#define SYSCFG_EXTICR4_EXTI14_PA        ((uint16_t)0x0000) /*!<PA[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PB        ((uint16_t)0x0100) /*!<PB[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PC        ((uint16_t)0x0200) /*!<PC[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PD        ((uint16_t)0x0300) /*!<PD[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PE        ((uint16_t)0x0400) /*!<PE[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PF        ((uint16_t)0x0500) /*!<PF[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PG        ((uint16_t)0x0600) /*!<PG[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PH        ((uint16_t)0x0700) /*!<PH[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PI        ((uint16_t)0x0800) /*!<PI[14] pin */
+#define SYSCFG_EXTICR4_EXTI14_PJ        ((uint16_t)0x0900) /*!<PJ[14] pin */
+
+/** 
+  * @brief   EXTI15 configuration  
+  */ 
+#define SYSCFG_EXTICR4_EXTI15_PA        ((uint16_t)0x0000) /*!<PA[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PB        ((uint16_t)0x1000) /*!<PB[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PC        ((uint16_t)0x2000) /*!<PC[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PD        ((uint16_t)0x3000) /*!<PD[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PE        ((uint16_t)0x4000) /*!<PE[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PF        ((uint16_t)0x5000) /*!<PF[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PG        ((uint16_t)0x6000) /*!<PG[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PH        ((uint16_t)0x7000) /*!<PH[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PI        ((uint16_t)0x8000) /*!<PI[15] pin */
+#define SYSCFG_EXTICR4_EXTI15_PJ        ((uint16_t)0x9000) /*!<PJ[15] pin */
+
+/******************  Bit definition for SYSCFG_CMPCR register  ****************/  
+#define SYSCFG_CMPCR_CMP_PD             ((uint32_t)0x00000001) /*!<Compensation cell ready flag */
+#define SYSCFG_CMPCR_READY              ((uint32_t)0x00000100) /*!<Compensation cell power-down */
+
+/******************************************************************************/
+/*                                                                            */
+/*                                    TIM                                     */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for TIM_CR1 register  ********************/
+#define  TIM_CR1_CEN                         ((uint16_t)0x0001)            /*!<Counter enable        */
+#define  TIM_CR1_UDIS                        ((uint16_t)0x0002)            /*!<Update disable        */
+#define  TIM_CR1_URS                         ((uint16_t)0x0004)            /*!<Update request source */
+#define  TIM_CR1_OPM                         ((uint16_t)0x0008)            /*!<One pulse mode        */
+#define  TIM_CR1_DIR                         ((uint16_t)0x0010)            /*!<Direction             */
+
+#define  TIM_CR1_CMS                         ((uint16_t)0x0060)            /*!<CMS[1:0] bits (Center-aligned mode selection) */
+#define  TIM_CR1_CMS_0                       ((uint16_t)0x0020)            /*!<Bit 0 */
+#define  TIM_CR1_CMS_1                       ((uint16_t)0x0040)            /*!<Bit 1 */
+
+#define  TIM_CR1_ARPE                        ((uint16_t)0x0080)            /*!<Auto-reload preload enable     */
+
+#define  TIM_CR1_CKD                         ((uint16_t)0x0300)            /*!<CKD[1:0] bits (clock division) */
+#define  TIM_CR1_CKD_0                       ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_CR1_CKD_1                       ((uint16_t)0x0200)            /*!<Bit 1 */
+
+/*******************  Bit definition for TIM_CR2 register  ********************/
+#define  TIM_CR2_CCPC                        ((uint16_t)0x0001)            /*!<Capture/Compare Preloaded Control        */
+#define  TIM_CR2_CCUS                        ((uint16_t)0x0004)            /*!<Capture/Compare Control Update Selection */
+#define  TIM_CR2_CCDS                        ((uint16_t)0x0008)            /*!<Capture/Compare DMA Selection            */
+
+#define  TIM_CR2_MMS                         ((uint16_t)0x0070)            /*!<MMS[2:0] bits (Master Mode Selection) */
+#define  TIM_CR2_MMS_0                       ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CR2_MMS_1                       ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CR2_MMS_2                       ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_CR2_TI1S                        ((uint16_t)0x0080)            /*!<TI1 Selection */
+#define  TIM_CR2_OIS1                        ((uint16_t)0x0100)            /*!<Output Idle state 1 (OC1 output)  */
+#define  TIM_CR2_OIS1N                       ((uint16_t)0x0200)            /*!<Output Idle state 1 (OC1N output) */
+#define  TIM_CR2_OIS2                        ((uint16_t)0x0400)            /*!<Output Idle state 2 (OC2 output)  */
+#define  TIM_CR2_OIS2N                       ((uint16_t)0x0800)            /*!<Output Idle state 2 (OC2N output) */
+#define  TIM_CR2_OIS3                        ((uint16_t)0x1000)            /*!<Output Idle state 3 (OC3 output)  */
+#define  TIM_CR2_OIS3N                       ((uint16_t)0x2000)            /*!<Output Idle state 3 (OC3N output) */
+#define  TIM_CR2_OIS4                        ((uint16_t)0x4000)            /*!<Output Idle state 4 (OC4 output)  */
+
+/*******************  Bit definition for TIM_SMCR register  *******************/
+#define  TIM_SMCR_SMS                        ((uint16_t)0x0007)            /*!<SMS[2:0] bits (Slave mode selection)    */
+#define  TIM_SMCR_SMS_0                      ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_SMCR_SMS_1                      ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  TIM_SMCR_SMS_2                      ((uint16_t)0x0004)            /*!<Bit 2 */
+
+#define  TIM_SMCR_TS                         ((uint16_t)0x0070)            /*!<TS[2:0] bits (Trigger selection)        */
+#define  TIM_SMCR_TS_0                       ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_SMCR_TS_1                       ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_SMCR_TS_2                       ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_SMCR_MSM                        ((uint16_t)0x0080)            /*!<Master/slave mode                       */
+
+#define  TIM_SMCR_ETF                        ((uint16_t)0x0F00)            /*!<ETF[3:0] bits (External trigger filter) */
+#define  TIM_SMCR_ETF_0                      ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_SMCR_ETF_1                      ((uint16_t)0x0200)            /*!<Bit 1 */
+#define  TIM_SMCR_ETF_2                      ((uint16_t)0x0400)            /*!<Bit 2 */
+#define  TIM_SMCR_ETF_3                      ((uint16_t)0x0800)            /*!<Bit 3 */
+
+#define  TIM_SMCR_ETPS                       ((uint16_t)0x3000)            /*!<ETPS[1:0] bits (External trigger prescaler) */
+#define  TIM_SMCR_ETPS_0                     ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_SMCR_ETPS_1                     ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  TIM_SMCR_ECE                        ((uint16_t)0x4000)            /*!<External clock enable     */
+#define  TIM_SMCR_ETP                        ((uint16_t)0x8000)            /*!<External trigger polarity */
+
+/*******************  Bit definition for TIM_DIER register  *******************/
+#define  TIM_DIER_UIE                        ((uint16_t)0x0001)            /*!<Update interrupt enable */
+#define  TIM_DIER_CC1IE                      ((uint16_t)0x0002)            /*!<Capture/Compare 1 interrupt enable   */
+#define  TIM_DIER_CC2IE                      ((uint16_t)0x0004)            /*!<Capture/Compare 2 interrupt enable   */
+#define  TIM_DIER_CC3IE                      ((uint16_t)0x0008)            /*!<Capture/Compare 3 interrupt enable   */
+#define  TIM_DIER_CC4IE                      ((uint16_t)0x0010)            /*!<Capture/Compare 4 interrupt enable   */
+#define  TIM_DIER_COMIE                      ((uint16_t)0x0020)            /*!<COM interrupt enable                 */
+#define  TIM_DIER_TIE                        ((uint16_t)0x0040)            /*!<Trigger interrupt enable             */
+#define  TIM_DIER_BIE                        ((uint16_t)0x0080)            /*!<Break interrupt enable               */
+#define  TIM_DIER_UDE                        ((uint16_t)0x0100)            /*!<Update DMA request enable            */
+#define  TIM_DIER_CC1DE                      ((uint16_t)0x0200)            /*!<Capture/Compare 1 DMA request enable */
+#define  TIM_DIER_CC2DE                      ((uint16_t)0x0400)            /*!<Capture/Compare 2 DMA request enable */
+#define  TIM_DIER_CC3DE                      ((uint16_t)0x0800)            /*!<Capture/Compare 3 DMA request enable */
+#define  TIM_DIER_CC4DE                      ((uint16_t)0x1000)            /*!<Capture/Compare 4 DMA request enable */
+#define  TIM_DIER_COMDE                      ((uint16_t)0x2000)            /*!<COM DMA request enable               */
+#define  TIM_DIER_TDE                        ((uint16_t)0x4000)            /*!<Trigger DMA request enable           */
+
+/********************  Bit definition for TIM_SR register  ********************/
+#define  TIM_SR_UIF                          ((uint16_t)0x0001)            /*!<Update interrupt Flag              */
+#define  TIM_SR_CC1IF                        ((uint16_t)0x0002)            /*!<Capture/Compare 1 interrupt Flag   */
+#define  TIM_SR_CC2IF                        ((uint16_t)0x0004)            /*!<Capture/Compare 2 interrupt Flag   */
+#define  TIM_SR_CC3IF                        ((uint16_t)0x0008)            /*!<Capture/Compare 3 interrupt Flag   */
+#define  TIM_SR_CC4IF                        ((uint16_t)0x0010)            /*!<Capture/Compare 4 interrupt Flag   */
+#define  TIM_SR_COMIF                        ((uint16_t)0x0020)            /*!<COM interrupt Flag                 */
+#define  TIM_SR_TIF                          ((uint16_t)0x0040)            /*!<Trigger interrupt Flag             */
+#define  TIM_SR_BIF                          ((uint16_t)0x0080)            /*!<Break interrupt Flag               */
+#define  TIM_SR_CC1OF                        ((uint16_t)0x0200)            /*!<Capture/Compare 1 Overcapture Flag */
+#define  TIM_SR_CC2OF                        ((uint16_t)0x0400)            /*!<Capture/Compare 2 Overcapture Flag */
+#define  TIM_SR_CC3OF                        ((uint16_t)0x0800)            /*!<Capture/Compare 3 Overcapture Flag */
+#define  TIM_SR_CC4OF                        ((uint16_t)0x1000)            /*!<Capture/Compare 4 Overcapture Flag */
+
+/*******************  Bit definition for TIM_EGR register  ********************/
+#define  TIM_EGR_UG                          ((uint8_t)0x01)               /*!<Update Generation                         */
+#define  TIM_EGR_CC1G                        ((uint8_t)0x02)               /*!<Capture/Compare 1 Generation              */
+#define  TIM_EGR_CC2G                        ((uint8_t)0x04)               /*!<Capture/Compare 2 Generation              */
+#define  TIM_EGR_CC3G                        ((uint8_t)0x08)               /*!<Capture/Compare 3 Generation              */
+#define  TIM_EGR_CC4G                        ((uint8_t)0x10)               /*!<Capture/Compare 4 Generation              */
+#define  TIM_EGR_COMG                        ((uint8_t)0x20)               /*!<Capture/Compare Control Update Generation */
+#define  TIM_EGR_TG                          ((uint8_t)0x40)               /*!<Trigger Generation                        */
+#define  TIM_EGR_BG                          ((uint8_t)0x80)               /*!<Break Generation                          */
+
+/******************  Bit definition for TIM_CCMR1 register  *******************/
+#define  TIM_CCMR1_CC1S                      ((uint16_t)0x0003)            /*!<CC1S[1:0] bits (Capture/Compare 1 Selection) */
+#define  TIM_CCMR1_CC1S_0                    ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_CCMR1_CC1S_1                    ((uint16_t)0x0002)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_OC1FE                     ((uint16_t)0x0004)            /*!<Output Compare 1 Fast enable                 */
+#define  TIM_CCMR1_OC1PE                     ((uint16_t)0x0008)            /*!<Output Compare 1 Preload enable              */
+
+#define  TIM_CCMR1_OC1M                      ((uint16_t)0x0070)            /*!<OC1M[2:0] bits (Output Compare 1 Mode)       */
+#define  TIM_CCMR1_OC1M_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR1_OC1M_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR1_OC1M_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_CCMR1_OC1CE                     ((uint16_t)0x0080)            /*!<Output Compare 1Clear Enable                 */
+
+#define  TIM_CCMR1_CC2S                      ((uint16_t)0x0300)            /*!<CC2S[1:0] bits (Capture/Compare 2 Selection) */
+#define  TIM_CCMR1_CC2S_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_CCMR1_CC2S_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_OC2FE                     ((uint16_t)0x0400)            /*!<Output Compare 2 Fast enable                 */
+#define  TIM_CCMR1_OC2PE                     ((uint16_t)0x0800)            /*!<Output Compare 2 Preload enable              */
+
+#define  TIM_CCMR1_OC2M                      ((uint16_t)0x7000)            /*!<OC2M[2:0] bits (Output Compare 2 Mode)       */
+#define  TIM_CCMR1_OC2M_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR1_OC2M_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR1_OC2M_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+
+#define  TIM_CCMR1_OC2CE                     ((uint16_t)0x8000)            /*!<Output Compare 2 Clear Enable */
+
+/*----------------------------------------------------------------------------*/
+
+#define  TIM_CCMR1_IC1PSC                    ((uint16_t)0x000C)            /*!<IC1PSC[1:0] bits (Input Capture 1 Prescaler) */
+#define  TIM_CCMR1_IC1PSC_0                  ((uint16_t)0x0004)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC1PSC_1                  ((uint16_t)0x0008)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_IC1F                      ((uint16_t)0x00F0)            /*!<IC1F[3:0] bits (Input Capture 1 Filter)      */
+#define  TIM_CCMR1_IC1F_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC1F_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR1_IC1F_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+#define  TIM_CCMR1_IC1F_3                    ((uint16_t)0x0080)            /*!<Bit 3 */
+
+#define  TIM_CCMR1_IC2PSC                    ((uint16_t)0x0C00)            /*!<IC2PSC[1:0] bits (Input Capture 2 Prescaler)  */
+#define  TIM_CCMR1_IC2PSC_0                  ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC2PSC_1                  ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  TIM_CCMR1_IC2F                      ((uint16_t)0xF000)            /*!<IC2F[3:0] bits (Input Capture 2 Filter)       */
+#define  TIM_CCMR1_IC2F_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR1_IC2F_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR1_IC2F_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+#define  TIM_CCMR1_IC2F_3                    ((uint16_t)0x8000)            /*!<Bit 3 */
+
+/******************  Bit definition for TIM_CCMR2 register  *******************/
+#define  TIM_CCMR2_CC3S                      ((uint16_t)0x0003)            /*!<CC3S[1:0] bits (Capture/Compare 3 Selection)  */
+#define  TIM_CCMR2_CC3S_0                    ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_CCMR2_CC3S_1                    ((uint16_t)0x0002)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_OC3FE                     ((uint16_t)0x0004)            /*!<Output Compare 3 Fast enable           */
+#define  TIM_CCMR2_OC3PE                     ((uint16_t)0x0008)            /*!<Output Compare 3 Preload enable        */
+
+#define  TIM_CCMR2_OC3M                      ((uint16_t)0x0070)            /*!<OC3M[2:0] bits (Output Compare 3 Mode) */
+#define  TIM_CCMR2_OC3M_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR2_OC3M_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR2_OC3M_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+
+#define  TIM_CCMR2_OC3CE                     ((uint16_t)0x0080)            /*!<Output Compare 3 Clear Enable */
+
+#define  TIM_CCMR2_CC4S                      ((uint16_t)0x0300)            /*!<CC4S[1:0] bits (Capture/Compare 4 Selection) */
+#define  TIM_CCMR2_CC4S_0                    ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_CCMR2_CC4S_1                    ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_OC4FE                     ((uint16_t)0x0400)            /*!<Output Compare 4 Fast enable    */
+#define  TIM_CCMR2_OC4PE                     ((uint16_t)0x0800)            /*!<Output Compare 4 Preload enable */
+
+#define  TIM_CCMR2_OC4M                      ((uint16_t)0x7000)            /*!<OC4M[2:0] bits (Output Compare 4 Mode) */
+#define  TIM_CCMR2_OC4M_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR2_OC4M_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR2_OC4M_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+
+#define  TIM_CCMR2_OC4CE                     ((uint16_t)0x8000)            /*!<Output Compare 4 Clear Enable */
+
+/*----------------------------------------------------------------------------*/
+
+#define  TIM_CCMR2_IC3PSC                    ((uint16_t)0x000C)            /*!<IC3PSC[1:0] bits (Input Capture 3 Prescaler) */
+#define  TIM_CCMR2_IC3PSC_0                  ((uint16_t)0x0004)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC3PSC_1                  ((uint16_t)0x0008)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_IC3F                      ((uint16_t)0x00F0)            /*!<IC3F[3:0] bits (Input Capture 3 Filter) */
+#define  TIM_CCMR2_IC3F_0                    ((uint16_t)0x0010)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC3F_1                    ((uint16_t)0x0020)            /*!<Bit 1 */
+#define  TIM_CCMR2_IC3F_2                    ((uint16_t)0x0040)            /*!<Bit 2 */
+#define  TIM_CCMR2_IC3F_3                    ((uint16_t)0x0080)            /*!<Bit 3 */
+
+#define  TIM_CCMR2_IC4PSC                    ((uint16_t)0x0C00)            /*!<IC4PSC[1:0] bits (Input Capture 4 Prescaler) */
+#define  TIM_CCMR2_IC4PSC_0                  ((uint16_t)0x0400)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC4PSC_1                  ((uint16_t)0x0800)            /*!<Bit 1 */
+
+#define  TIM_CCMR2_IC4F                      ((uint16_t)0xF000)            /*!<IC4F[3:0] bits (Input Capture 4 Filter) */
+#define  TIM_CCMR2_IC4F_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  TIM_CCMR2_IC4F_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+#define  TIM_CCMR2_IC4F_2                    ((uint16_t)0x4000)            /*!<Bit 2 */
+#define  TIM_CCMR2_IC4F_3                    ((uint16_t)0x8000)            /*!<Bit 3 */
+
+/*******************  Bit definition for TIM_CCER register  *******************/
+#define  TIM_CCER_CC1E                       ((uint16_t)0x0001)            /*!<Capture/Compare 1 output enable                 */
+#define  TIM_CCER_CC1P                       ((uint16_t)0x0002)            /*!<Capture/Compare 1 output Polarity               */
+#define  TIM_CCER_CC1NE                      ((uint16_t)0x0004)            /*!<Capture/Compare 1 Complementary output enable   */
+#define  TIM_CCER_CC1NP                      ((uint16_t)0x0008)            /*!<Capture/Compare 1 Complementary output Polarity */
+#define  TIM_CCER_CC2E                       ((uint16_t)0x0010)            /*!<Capture/Compare 2 output enable                 */
+#define  TIM_CCER_CC2P                       ((uint16_t)0x0020)            /*!<Capture/Compare 2 output Polarity               */
+#define  TIM_CCER_CC2NE                      ((uint16_t)0x0040)            /*!<Capture/Compare 2 Complementary output enable   */
+#define  TIM_CCER_CC2NP                      ((uint16_t)0x0080)            /*!<Capture/Compare 2 Complementary output Polarity */
+#define  TIM_CCER_CC3E                       ((uint16_t)0x0100)            /*!<Capture/Compare 3 output enable                 */
+#define  TIM_CCER_CC3P                       ((uint16_t)0x0200)            /*!<Capture/Compare 3 output Polarity               */
+#define  TIM_CCER_CC3NE                      ((uint16_t)0x0400)            /*!<Capture/Compare 3 Complementary output enable   */
+#define  TIM_CCER_CC3NP                      ((uint16_t)0x0800)            /*!<Capture/Compare 3 Complementary output Polarity */
+#define  TIM_CCER_CC4E                       ((uint16_t)0x1000)            /*!<Capture/Compare 4 output enable                 */
+#define  TIM_CCER_CC4P                       ((uint16_t)0x2000)            /*!<Capture/Compare 4 output Polarity               */
+#define  TIM_CCER_CC4NP                      ((uint16_t)0x8000)            /*!<Capture/Compare 4 Complementary output Polarity */
+
+/*******************  Bit definition for TIM_CNT register  ********************/
+#define  TIM_CNT_CNT                         ((uint16_t)0xFFFF)            /*!<Counter Value            */
+
+/*******************  Bit definition for TIM_PSC register  ********************/
+#define  TIM_PSC_PSC                         ((uint16_t)0xFFFF)            /*!<Prescaler Value          */
+
+/*******************  Bit definition for TIM_ARR register  ********************/
+#define  TIM_ARR_ARR                         ((uint16_t)0xFFFF)            /*!<actual auto-reload Value */
+
+/*******************  Bit definition for TIM_RCR register  ********************/
+#define  TIM_RCR_REP                         ((uint8_t)0xFF)               /*!<Repetition Counter Value */
+
+/*******************  Bit definition for TIM_CCR1 register  *******************/
+#define  TIM_CCR1_CCR1                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 1 Value  */
+
+/*******************  Bit definition for TIM_CCR2 register  *******************/
+#define  TIM_CCR2_CCR2                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 2 Value  */
+
+/*******************  Bit definition for TIM_CCR3 register  *******************/
+#define  TIM_CCR3_CCR3                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 3 Value  */
+
+/*******************  Bit definition for TIM_CCR4 register  *******************/
+#define  TIM_CCR4_CCR4                       ((uint16_t)0xFFFF)            /*!<Capture/Compare 4 Value  */
+
+/*******************  Bit definition for TIM_BDTR register  *******************/
+#define  TIM_BDTR_DTG                        ((uint16_t)0x00FF)            /*!<DTG[0:7] bits (Dead-Time Generator set-up) */
+#define  TIM_BDTR_DTG_0                      ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_BDTR_DTG_1                      ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  TIM_BDTR_DTG_2                      ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  TIM_BDTR_DTG_3                      ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  TIM_BDTR_DTG_4                      ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  TIM_BDTR_DTG_5                      ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  TIM_BDTR_DTG_6                      ((uint16_t)0x0040)            /*!<Bit 6 */
+#define  TIM_BDTR_DTG_7                      ((uint16_t)0x0080)            /*!<Bit 7 */
+
+#define  TIM_BDTR_LOCK                       ((uint16_t)0x0300)            /*!<LOCK[1:0] bits (Lock Configuration) */
+#define  TIM_BDTR_LOCK_0                     ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_BDTR_LOCK_1                     ((uint16_t)0x0200)            /*!<Bit 1 */
+
+#define  TIM_BDTR_OSSI                       ((uint16_t)0x0400)            /*!<Off-State Selection for Idle mode */
+#define  TIM_BDTR_OSSR                       ((uint16_t)0x0800)            /*!<Off-State Selection for Run mode  */
+#define  TIM_BDTR_BKE                        ((uint16_t)0x1000)            /*!<Break enable                      */
+#define  TIM_BDTR_BKP                        ((uint16_t)0x2000)            /*!<Break Polarity                    */
+#define  TIM_BDTR_AOE                        ((uint16_t)0x4000)            /*!<Automatic Output enable           */
+#define  TIM_BDTR_MOE                        ((uint16_t)0x8000)            /*!<Main Output enable                */
+
+/*******************  Bit definition for TIM_DCR register  ********************/
+#define  TIM_DCR_DBA                         ((uint16_t)0x001F)            /*!<DBA[4:0] bits (DMA Base Address) */
+#define  TIM_DCR_DBA_0                       ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  TIM_DCR_DBA_1                       ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  TIM_DCR_DBA_2                       ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  TIM_DCR_DBA_3                       ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  TIM_DCR_DBA_4                       ((uint16_t)0x0010)            /*!<Bit 4 */
+
+#define  TIM_DCR_DBL                         ((uint16_t)0x1F00)            /*!<DBL[4:0] bits (DMA Burst Length) */
+#define  TIM_DCR_DBL_0                       ((uint16_t)0x0100)            /*!<Bit 0 */
+#define  TIM_DCR_DBL_1                       ((uint16_t)0x0200)            /*!<Bit 1 */
+#define  TIM_DCR_DBL_2                       ((uint16_t)0x0400)            /*!<Bit 2 */
+#define  TIM_DCR_DBL_3                       ((uint16_t)0x0800)            /*!<Bit 3 */
+#define  TIM_DCR_DBL_4                       ((uint16_t)0x1000)            /*!<Bit 4 */
+
+/*******************  Bit definition for TIM_DMAR register  *******************/
+#define  TIM_DMAR_DMAB                       ((uint16_t)0xFFFF)            /*!<DMA register for burst accesses                    */
+
+/*******************  Bit definition for TIM_OR register  *********************/
+#define TIM_OR_TI4_RMP                       ((uint16_t)0x00C0)            /*!<TI4_RMP[1:0] bits (TIM5 Input 4 remap)             */
+#define TIM_OR_TI4_RMP_0                     ((uint16_t)0x0040)            /*!<Bit 0 */
+#define TIM_OR_TI4_RMP_1                     ((uint16_t)0x0080)            /*!<Bit 1 */
+#define TIM_OR_ITR1_RMP                      ((uint16_t)0x0C00)            /*!<ITR1_RMP[1:0] bits (TIM2 Internal trigger 1 remap) */
+#define TIM_OR_ITR1_RMP_0                    ((uint16_t)0x0400)            /*!<Bit 0 */
+#define TIM_OR_ITR1_RMP_1                    ((uint16_t)0x0800)            /*!<Bit 1 */
+
+
+/******************************************************************************/
+/*                                                                            */
+/*         Universal Synchronous Asynchronous Receiver Transmitter            */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for USART_SR register  *******************/
+#define  USART_SR_PE                         ((uint16_t)0x0001)            /*!<Parity Error                 */
+#define  USART_SR_FE                         ((uint16_t)0x0002)            /*!<Framing Error                */
+#define  USART_SR_NE                         ((uint16_t)0x0004)            /*!<Noise Error Flag             */
+#define  USART_SR_ORE                        ((uint16_t)0x0008)            /*!<OverRun Error                */
+#define  USART_SR_IDLE                       ((uint16_t)0x0010)            /*!<IDLE line detected           */
+#define  USART_SR_RXNE                       ((uint16_t)0x0020)            /*!<Read Data Register Not Empty */
+#define  USART_SR_TC                         ((uint16_t)0x0040)            /*!<Transmission Complete        */
+#define  USART_SR_TXE                        ((uint16_t)0x0080)            /*!<Transmit Data Register Empty */
+#define  USART_SR_LBD                        ((uint16_t)0x0100)            /*!<LIN Break Detection Flag     */
+#define  USART_SR_CTS                        ((uint16_t)0x0200)            /*!<CTS Flag                     */
+
+/*******************  Bit definition for USART_DR register  *******************/
+#define  USART_DR_DR                         ((uint16_t)0x01FF)            /*!<Data value */
+
+/******************  Bit definition for USART_BRR register  *******************/
+#define  USART_BRR_DIV_Fraction              ((uint16_t)0x000F)            /*!<Fraction of USARTDIV */
+#define  USART_BRR_DIV_Mantissa              ((uint16_t)0xFFF0)            /*!<Mantissa of USARTDIV */
+
+/******************  Bit definition for USART_CR1 register  *******************/
+#define  USART_CR1_SBK                       ((uint16_t)0x0001)            /*!<Send Break                             */
+#define  USART_CR1_RWU                       ((uint16_t)0x0002)            /*!<Receiver wakeup                        */
+#define  USART_CR1_RE                        ((uint16_t)0x0004)            /*!<Receiver Enable                        */
+#define  USART_CR1_TE                        ((uint16_t)0x0008)            /*!<Transmitter Enable                     */
+#define  USART_CR1_IDLEIE                    ((uint16_t)0x0010)            /*!<IDLE Interrupt Enable                  */
+#define  USART_CR1_RXNEIE                    ((uint16_t)0x0020)            /*!<RXNE Interrupt Enable                  */
+#define  USART_CR1_TCIE                      ((uint16_t)0x0040)            /*!<Transmission Complete Interrupt Enable */
+#define  USART_CR1_TXEIE                     ((uint16_t)0x0080)            /*!<PE Interrupt Enable                    */
+#define  USART_CR1_PEIE                      ((uint16_t)0x0100)            /*!<PE Interrupt Enable                    */
+#define  USART_CR1_PS                        ((uint16_t)0x0200)            /*!<Parity Selection                       */
+#define  USART_CR1_PCE                       ((uint16_t)0x0400)            /*!<Parity Control Enable                  */
+#define  USART_CR1_WAKE                      ((uint16_t)0x0800)            /*!<Wakeup method                          */
+#define  USART_CR1_M                         ((uint16_t)0x1000)            /*!<Word length                            */
+#define  USART_CR1_UE                        ((uint16_t)0x2000)            /*!<USART Enable                           */
+#define  USART_CR1_OVER8                     ((uint16_t)0x8000)            /*!<USART Oversampling by 8 enable         */
+
+/******************  Bit definition for USART_CR2 register  *******************/
+#define  USART_CR2_ADD                       ((uint16_t)0x000F)            /*!<Address of the USART node            */
+#define  USART_CR2_LBDL                      ((uint16_t)0x0020)            /*!<LIN Break Detection Length           */
+#define  USART_CR2_LBDIE                     ((uint16_t)0x0040)            /*!<LIN Break Detection Interrupt Enable */
+#define  USART_CR2_LBCL                      ((uint16_t)0x0100)            /*!<Last Bit Clock pulse                 */
+#define  USART_CR2_CPHA                      ((uint16_t)0x0200)            /*!<Clock Phase                          */
+#define  USART_CR2_CPOL                      ((uint16_t)0x0400)            /*!<Clock Polarity                       */
+#define  USART_CR2_CLKEN                     ((uint16_t)0x0800)            /*!<Clock Enable                         */
+
+#define  USART_CR2_STOP                      ((uint16_t)0x3000)            /*!<STOP[1:0] bits (STOP bits) */
+#define  USART_CR2_STOP_0                    ((uint16_t)0x1000)            /*!<Bit 0 */
+#define  USART_CR2_STOP_1                    ((uint16_t)0x2000)            /*!<Bit 1 */
+
+#define  USART_CR2_LINEN                     ((uint16_t)0x4000)            /*!<LIN mode enable */
+
+/******************  Bit definition for USART_CR3 register  *******************/
+#define  USART_CR3_EIE                       ((uint16_t)0x0001)            /*!<Error Interrupt Enable      */
+#define  USART_CR3_IREN                      ((uint16_t)0x0002)            /*!<IrDA mode Enable            */
+#define  USART_CR3_IRLP                      ((uint16_t)0x0004)            /*!<IrDA Low-Power              */
+#define  USART_CR3_HDSEL                     ((uint16_t)0x0008)            /*!<Half-Duplex Selection       */
+#define  USART_CR3_NACK                      ((uint16_t)0x0010)            /*!<Smartcard NACK enable       */
+#define  USART_CR3_SCEN                      ((uint16_t)0x0020)            /*!<Smartcard mode enable       */
+#define  USART_CR3_DMAR                      ((uint16_t)0x0040)            /*!<DMA Enable Receiver         */
+#define  USART_CR3_DMAT                      ((uint16_t)0x0080)            /*!<DMA Enable Transmitter      */
+#define  USART_CR3_RTSE                      ((uint16_t)0x0100)            /*!<RTS Enable                  */
+#define  USART_CR3_CTSE                      ((uint16_t)0x0200)            /*!<CTS Enable                  */
+#define  USART_CR3_CTSIE                     ((uint16_t)0x0400)            /*!<CTS Interrupt Enable        */
+#define  USART_CR3_ONEBIT                    ((uint16_t)0x0800)            /*!<USART One bit method enable */
+
+/******************  Bit definition for USART_GTPR register  ******************/
+#define  USART_GTPR_PSC                      ((uint16_t)0x00FF)            /*!<PSC[7:0] bits (Prescaler value) */
+#define  USART_GTPR_PSC_0                    ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  USART_GTPR_PSC_1                    ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  USART_GTPR_PSC_2                    ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  USART_GTPR_PSC_3                    ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  USART_GTPR_PSC_4                    ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  USART_GTPR_PSC_5                    ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  USART_GTPR_PSC_6                    ((uint16_t)0x0040)            /*!<Bit 6 */
+#define  USART_GTPR_PSC_7                    ((uint16_t)0x0080)            /*!<Bit 7 */
+
+#define  USART_GTPR_GT                       ((uint16_t)0xFF00)            /*!<Guard time value */
+
+/******************************************************************************/
+/*                                                                            */
+/*                            Window WATCHDOG                                 */
+/*                                                                            */
+/******************************************************************************/
+/*******************  Bit definition for WWDG_CR register  ********************/
+#define  WWDG_CR_T                           ((uint8_t)0x7F)               /*!<T[6:0] bits (7-Bit counter (MSB to LSB)) */
+#define  WWDG_CR_T0                          ((uint8_t)0x01)               /*!<Bit 0 */
+#define  WWDG_CR_T1                          ((uint8_t)0x02)               /*!<Bit 1 */
+#define  WWDG_CR_T2                          ((uint8_t)0x04)               /*!<Bit 2 */
+#define  WWDG_CR_T3                          ((uint8_t)0x08)               /*!<Bit 3 */
+#define  WWDG_CR_T4                          ((uint8_t)0x10)               /*!<Bit 4 */
+#define  WWDG_CR_T5                          ((uint8_t)0x20)               /*!<Bit 5 */
+#define  WWDG_CR_T6                          ((uint8_t)0x40)               /*!<Bit 6 */
+
+#define  WWDG_CR_WDGA                        ((uint8_t)0x80)               /*!<Activation bit */
+
+/*******************  Bit definition for WWDG_CFR register  *******************/
+#define  WWDG_CFR_W                          ((uint16_t)0x007F)            /*!<W[6:0] bits (7-bit window value) */
+#define  WWDG_CFR_W0                         ((uint16_t)0x0001)            /*!<Bit 0 */
+#define  WWDG_CFR_W1                         ((uint16_t)0x0002)            /*!<Bit 1 */
+#define  WWDG_CFR_W2                         ((uint16_t)0x0004)            /*!<Bit 2 */
+#define  WWDG_CFR_W3                         ((uint16_t)0x0008)            /*!<Bit 3 */
+#define  WWDG_CFR_W4                         ((uint16_t)0x0010)            /*!<Bit 4 */
+#define  WWDG_CFR_W5                         ((uint16_t)0x0020)            /*!<Bit 5 */
+#define  WWDG_CFR_W6                         ((uint16_t)0x0040)            /*!<Bit 6 */
+
+#define  WWDG_CFR_WDGTB                      ((uint16_t)0x0180)            /*!<WDGTB[1:0] bits (Timer Base) */
+#define  WWDG_CFR_WDGTB0                     ((uint16_t)0x0080)            /*!<Bit 0 */
+#define  WWDG_CFR_WDGTB1                     ((uint16_t)0x0100)            /*!<Bit 1 */
+
+#define  WWDG_CFR_EWI                        ((uint16_t)0x0200)            /*!<Early Wakeup Interrupt */
+
+/*******************  Bit definition for WWDG_SR register  ********************/
+#define  WWDG_SR_EWIF                        ((uint8_t)0x01)               /*!<Early Wakeup Interrupt Flag */
+
+
+/******************************************************************************/
+/*                                                                            */
+/*                                DBG                                         */
+/*                                                                            */
+/******************************************************************************/
+/********************  Bit definition for DBGMCU_IDCODE register  *************/
+#define  DBGMCU_IDCODE_DEV_ID                ((uint32_t)0x00000FFF)
+#define  DBGMCU_IDCODE_REV_ID                ((uint32_t)0xFFFF0000)
+
+/********************  Bit definition for DBGMCU_CR register  *****************/
+#define  DBGMCU_CR_DBG_SLEEP                 ((uint32_t)0x00000001)
+#define  DBGMCU_CR_DBG_STOP                  ((uint32_t)0x00000002)
+#define  DBGMCU_CR_DBG_STANDBY               ((uint32_t)0x00000004)
+#define  DBGMCU_CR_TRACE_IOEN                ((uint32_t)0x00000020)
+
+#define  DBGMCU_CR_TRACE_MODE                ((uint32_t)0x000000C0)
+#define  DBGMCU_CR_TRACE_MODE_0              ((uint32_t)0x00000040)/*!<Bit 0 */
+#define  DBGMCU_CR_TRACE_MODE_1              ((uint32_t)0x00000080)/*!<Bit 1 */
+
+/********************  Bit definition for DBGMCU_APB1_FZ register  ************/
+#define  DBGMCU_APB1_FZ_DBG_TIM2_STOP            ((uint32_t)0x00000001)
+#define  DBGMCU_APB1_FZ_DBG_TIM3_STOP            ((uint32_t)0x00000002)
+#define  DBGMCU_APB1_FZ_DBG_TIM4_STOP            ((uint32_t)0x00000004)
+#define  DBGMCU_APB1_FZ_DBG_TIM5_STOP            ((uint32_t)0x00000008)
+#define  DBGMCU_APB1_FZ_DBG_TIM6_STOP            ((uint32_t)0x00000010)
+#define  DBGMCU_APB1_FZ_DBG_TIM7_STOP            ((uint32_t)0x00000020)
+#define  DBGMCU_APB1_FZ_DBG_TIM12_STOP           ((uint32_t)0x00000040)
+#define  DBGMCU_APB1_FZ_DBG_TIM13_STOP           ((uint32_t)0x00000080)
+#define  DBGMCU_APB1_FZ_DBG_TIM14_STOP           ((uint32_t)0x00000100)
+#define  DBGMCU_APB1_FZ_DBG_RTC_STOP             ((uint32_t)0x00000400)
+#define  DBGMCU_APB1_FZ_DBG_WWDG_STOP            ((uint32_t)0x00000800)
+#define  DBGMCU_APB1_FZ_DBG_IWDG_STOP            ((uint32_t)0x00001000)
+#define  DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT   ((uint32_t)0x00200000)
+#define  DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT   ((uint32_t)0x00400000)
+#define  DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT   ((uint32_t)0x00800000)
+#define  DBGMCU_APB1_FZ_DBG_CAN1_STOP            ((uint32_t)0x02000000)
+#define  DBGMCU_APB1_FZ_DBG_CAN2_STOP            ((uint32_t)0x04000000)
+/* Old IWDGSTOP bit definition, maintained for legacy purpose */
+#define  DBGMCU_APB1_FZ_DBG_IWDEG_STOP           DBGMCU_APB1_FZ_DBG_IWDG_STOP
+
+/********************  Bit definition for DBGMCU_APB1_FZ register  ************/
+#define  DBGMCU_APB1_FZ_DBG_TIM1_STOP        ((uint32_t)0x00000001)
+#define  DBGMCU_APB1_FZ_DBG_TIM8_STOP        ((uint32_t)0x00000002)
+#define  DBGMCU_APB1_FZ_DBG_TIM9_STOP        ((uint32_t)0x00010000)
+#define  DBGMCU_APB1_FZ_DBG_TIM10_STOP       ((uint32_t)0x00020000)
+#define  DBGMCU_APB1_FZ_DBG_TIM11_STOP       ((uint32_t)0x00040000)
+
+/******************************************************************************/
+/*                                                                            */
+/*                Ethernet MAC Registers bits definitions                     */
+/*                                                                            */
+/******************************************************************************/
+/* Bit definition for Ethernet MAC Control Register register */
+#define ETH_MACCR_WD      ((uint32_t)0x00800000)  /* Watchdog disable */
+#define ETH_MACCR_JD      ((uint32_t)0x00400000)  /* Jabber disable */
+#define ETH_MACCR_IFG     ((uint32_t)0x000E0000)  /* Inter-frame gap */
+#define ETH_MACCR_IFG_96Bit     ((uint32_t)0x00000000)  /* Minimum IFG between frames during transmission is 96Bit */
+  #define ETH_MACCR_IFG_88Bit     ((uint32_t)0x00020000)  /* Minimum IFG between frames during transmission is 88Bit */
+  #define ETH_MACCR_IFG_80Bit     ((uint32_t)0x00040000)  /* Minimum IFG between frames during transmission is 80Bit */
+  #define ETH_MACCR_IFG_72Bit     ((uint32_t)0x00060000)  /* Minimum IFG between frames during transmission is 72Bit */
+  #define ETH_MACCR_IFG_64Bit     ((uint32_t)0x00080000)  /* Minimum IFG between frames during transmission is 64Bit */        
+  #define ETH_MACCR_IFG_56Bit     ((uint32_t)0x000A0000)  /* Minimum IFG between frames during transmission is 56Bit */
+  #define ETH_MACCR_IFG_48Bit     ((uint32_t)0x000C0000)  /* Minimum IFG between frames during transmission is 48Bit */
+  #define ETH_MACCR_IFG_40Bit     ((uint32_t)0x000E0000)  /* Minimum IFG between frames during transmission is 40Bit */              
+#define ETH_MACCR_CSD     ((uint32_t)0x00010000)  /* Carrier sense disable (during transmission) */
+#define ETH_MACCR_FES     ((uint32_t)0x00004000)  /* Fast ethernet speed */
+#define ETH_MACCR_ROD     ((uint32_t)0x00002000)  /* Receive own disable */
+#define ETH_MACCR_LM      ((uint32_t)0x00001000)  /* loopback mode */
+#define ETH_MACCR_DM      ((uint32_t)0x00000800)  /* Duplex mode */
+#define ETH_MACCR_IPCO    ((uint32_t)0x00000400)  /* IP Checksum offload */
+#define ETH_MACCR_RD      ((uint32_t)0x00000200)  /* Retry disable */
+#define ETH_MACCR_APCS    ((uint32_t)0x00000080)  /* Automatic Pad/CRC stripping */
+#define ETH_MACCR_BL      ((uint32_t)0x00000060)  /* Back-off limit: random integer number (r) of slot time delays before rescheduling
+                                                       a transmission attempt during retries after a collision: 0 =< r <2^k */
+  #define ETH_MACCR_BL_10    ((uint32_t)0x00000000)  /* k = min (n, 10) */
+  #define ETH_MACCR_BL_8     ((uint32_t)0x00000020)  /* k = min (n, 8) */
+  #define ETH_MACCR_BL_4     ((uint32_t)0x00000040)  /* k = min (n, 4) */
+  #define ETH_MACCR_BL_1     ((uint32_t)0x00000060)  /* k = min (n, 1) */ 
+#define ETH_MACCR_DC      ((uint32_t)0x00000010)  /* Defferal check */
+#define ETH_MACCR_TE      ((uint32_t)0x00000008)  /* Transmitter enable */
+#define ETH_MACCR_RE      ((uint32_t)0x00000004)  /* Receiver enable */
+
+/* Bit definition for Ethernet MAC Frame Filter Register */
+#define ETH_MACFFR_RA     ((uint32_t)0x80000000)  /* Receive all */ 
+#define ETH_MACFFR_HPF    ((uint32_t)0x00000400)  /* Hash or perfect filter */ 
+#define ETH_MACFFR_SAF    ((uint32_t)0x00000200)  /* Source address filter enable */ 
+#define ETH_MACFFR_SAIF   ((uint32_t)0x00000100)  /* SA inverse filtering */ 
+#define ETH_MACFFR_PCF    ((uint32_t)0x000000C0)  /* Pass control frames: 3 cases */
+  #define ETH_MACFFR_PCF_BlockAll                ((uint32_t)0x00000040)  /* MAC filters all control frames from reaching the application */
+  #define ETH_MACFFR_PCF_ForwardAll              ((uint32_t)0x00000080)  /* MAC forwards all control frames to application even if they fail the Address Filter */
+  #define ETH_MACFFR_PCF_ForwardPassedAddrFilter ((uint32_t)0x000000C0)  /* MAC forwards control frames that pass the Address Filter. */ 
+#define ETH_MACFFR_BFD    ((uint32_t)0x00000020)  /* Broadcast frame disable */ 
+#define ETH_MACFFR_PAM    ((uint32_t)0x00000010)  /* Pass all mutlicast */ 
+#define ETH_MACFFR_DAIF   ((uint32_t)0x00000008)  /* DA Inverse filtering */ 
+#define ETH_MACFFR_HM     ((uint32_t)0x00000004)  /* Hash multicast */ 
+#define ETH_MACFFR_HU     ((uint32_t)0x00000002)  /* Hash unicast */
+#define ETH_MACFFR_PM     ((uint32_t)0x00000001)  /* Promiscuous mode */
+
+/* Bit definition for Ethernet MAC Hash Table High Register */
+#define ETH_MACHTHR_HTH   ((uint32_t)0xFFFFFFFF)  /* Hash table high */
+
+/* Bit definition for Ethernet MAC Hash Table Low Register */
+#define ETH_MACHTLR_HTL   ((uint32_t)0xFFFFFFFF)  /* Hash table low */
+
+/* Bit definition for Ethernet MAC MII Address Register */
+#define ETH_MACMIIAR_PA   ((uint32_t)0x0000F800)  /* Physical layer address */ 
+#define ETH_MACMIIAR_MR   ((uint32_t)0x000007C0)  /* MII register in the selected PHY */ 
+#define ETH_MACMIIAR_CR   ((uint32_t)0x0000001C)  /* CR clock range: 6 cases */ 
+  #define ETH_MACMIIAR_CR_Div42   ((uint32_t)0x00000000)  /* HCLK:60-100 MHz; MDC clock= HCLK/42 */
+  #define ETH_MACMIIAR_CR_Div62   ((uint32_t)0x00000004)  /* HCLK:100-150 MHz; MDC clock= HCLK/62 */
+  #define ETH_MACMIIAR_CR_Div16   ((uint32_t)0x00000008)  /* HCLK:20-35 MHz; MDC clock= HCLK/16 */
+  #define ETH_MACMIIAR_CR_Div26   ((uint32_t)0x0000000C)  /* HCLK:35-60 MHz; MDC clock= HCLK/26 */
+  #define ETH_MACMIIAR_CR_Div102  ((uint32_t)0x00000010)  /* HCLK:150-168 MHz; MDC clock= HCLK/102 */  
+#define ETH_MACMIIAR_MW   ((uint32_t)0x00000002)  /* MII write */ 
+#define ETH_MACMIIAR_MB   ((uint32_t)0x00000001)  /* MII busy */ 
+  
+/* Bit definition for Ethernet MAC MII Data Register */
+#define ETH_MACMIIDR_MD   ((uint32_t)0x0000FFFF)  /* MII data: read/write data from/to PHY */
+
+/* Bit definition for Ethernet MAC Flow Control Register */
+#define ETH_MACFCR_PT     ((uint32_t)0xFFFF0000)  /* Pause time */
+#define ETH_MACFCR_ZQPD   ((uint32_t)0x00000080)  /* Zero-quanta pause disable */
+#define ETH_MACFCR_PLT    ((uint32_t)0x00000030)  /* Pause low threshold: 4 cases */
+  #define ETH_MACFCR_PLT_Minus4   ((uint32_t)0x00000000)  /* Pause time minus 4 slot times */
+  #define ETH_MACFCR_PLT_Minus28  ((uint32_t)0x00000010)  /* Pause time minus 28 slot times */
+  #define ETH_MACFCR_PLT_Minus144 ((uint32_t)0x00000020)  /* Pause time minus 144 slot times */
+  #define ETH_MACFCR_PLT_Minus256 ((uint32_t)0x00000030)  /* Pause time minus 256 slot times */      
+#define ETH_MACFCR_UPFD   ((uint32_t)0x00000008)  /* Unicast pause frame detect */
+#define ETH_MACFCR_RFCE   ((uint32_t)0x00000004)  /* Receive flow control enable */
+#define ETH_MACFCR_TFCE   ((uint32_t)0x00000002)  /* Transmit flow control enable */
+#define ETH_MACFCR_FCBBPA ((uint32_t)0x00000001)  /* Flow control busy/backpressure activate */
+
+/* Bit definition for Ethernet MAC VLAN Tag Register */
+#define ETH_MACVLANTR_VLANTC ((uint32_t)0x00010000)  /* 12-bit VLAN tag comparison */
+#define ETH_MACVLANTR_VLANTI ((uint32_t)0x0000FFFF)  /* VLAN tag identifier (for receive frames) */
+
+/* Bit definition for Ethernet MAC Remote Wake-UpFrame Filter Register */ 
+#define ETH_MACRWUFFR_D   ((uint32_t)0xFFFFFFFF)  /* Wake-up frame filter register data */
+/* Eight sequential Writes to this address (offset 0x28) will write all Wake-UpFrame Filter Registers.
+   Eight sequential Reads from this address (offset 0x28) will read all Wake-UpFrame Filter Registers. */
+/* Wake-UpFrame Filter Reg0 : Filter 0 Byte Mask
+   Wake-UpFrame Filter Reg1 : Filter 1 Byte Mask
+   Wake-UpFrame Filter Reg2 : Filter 2 Byte Mask
+   Wake-UpFrame Filter Reg3 : Filter 3 Byte Mask
+   Wake-UpFrame Filter Reg4 : RSVD - Filter3 Command - RSVD - Filter2 Command - 
+                              RSVD - Filter1 Command - RSVD - Filter0 Command
+   Wake-UpFrame Filter Re5 : Filter3 Offset - Filter2 Offset - Filter1 Offset - Filter0 Offset
+   Wake-UpFrame Filter Re6 : Filter1 CRC16 - Filter0 CRC16
+   Wake-UpFrame Filter Re7 : Filter3 CRC16 - Filter2 CRC16 */
+
+/* Bit definition for Ethernet MAC PMT Control and Status Register */ 
+#define ETH_MACPMTCSR_WFFRPR ((uint32_t)0x80000000)  /* Wake-Up Frame Filter Register Pointer Reset */
+#define ETH_MACPMTCSR_GU     ((uint32_t)0x00000200)  /* Global Unicast */
+#define ETH_MACPMTCSR_WFR    ((uint32_t)0x00000040)  /* Wake-Up Frame Received */
+#define ETH_MACPMTCSR_MPR    ((uint32_t)0x00000020)  /* Magic Packet Received */
+#define ETH_MACPMTCSR_WFE    ((uint32_t)0x00000004)  /* Wake-Up Frame Enable */
+#define ETH_MACPMTCSR_MPE    ((uint32_t)0x00000002)  /* Magic Packet Enable */
+#define ETH_MACPMTCSR_PD     ((uint32_t)0x00000001)  /* Power Down */
+
+/* Bit definition for Ethernet MAC Status Register */
+#define ETH_MACSR_TSTS      ((uint32_t)0x00000200)  /* Time stamp trigger status */
+#define ETH_MACSR_MMCTS     ((uint32_t)0x00000040)  /* MMC transmit status */
+#define ETH_MACSR_MMMCRS    ((uint32_t)0x00000020)  /* MMC receive status */
+#define ETH_MACSR_MMCS      ((uint32_t)0x00000010)  /* MMC status */
+#define ETH_MACSR_PMTS      ((uint32_t)0x00000008)  /* PMT status */
+
+/* Bit definition for Ethernet MAC Interrupt Mask Register */
+#define ETH_MACIMR_TSTIM     ((uint32_t)0x00000200)  /* Time stamp trigger interrupt mask */
+#define ETH_MACIMR_PMTIM     ((uint32_t)0x00000008)  /* PMT interrupt mask */
+
+/* Bit definition for Ethernet MAC Address0 High Register */
+#define ETH_MACA0HR_MACA0H   ((uint32_t)0x0000FFFF)  /* MAC address0 high */
+
+/* Bit definition for Ethernet MAC Address0 Low Register */
+#define ETH_MACA0LR_MACA0L   ((uint32_t)0xFFFFFFFF)  /* MAC address0 low */
+
+/* Bit definition for Ethernet MAC Address1 High Register */
+#define ETH_MACA1HR_AE       ((uint32_t)0x80000000)  /* Address enable */
+#define ETH_MACA1HR_SA       ((uint32_t)0x40000000)  /* Source address */
+#define ETH_MACA1HR_MBC      ((uint32_t)0x3F000000)  /* Mask byte control: bits to mask for comparison of the MAC Address bytes */
+  #define ETH_MACA1HR_MBC_HBits15_8    ((uint32_t)0x20000000)  /* Mask MAC Address high reg bits [15:8] */
+  #define ETH_MACA1HR_MBC_HBits7_0     ((uint32_t)0x10000000)  /* Mask MAC Address high reg bits [7:0] */
+  #define ETH_MACA1HR_MBC_LBits31_24   ((uint32_t)0x08000000)  /* Mask MAC Address low reg bits [31:24] */
+  #define ETH_MACA1HR_MBC_LBits23_16   ((uint32_t)0x04000000)  /* Mask MAC Address low reg bits [23:16] */
+  #define ETH_MACA1HR_MBC_LBits15_8    ((uint32_t)0x02000000)  /* Mask MAC Address low reg bits [15:8] */
+  #define ETH_MACA1HR_MBC_LBits7_0     ((uint32_t)0x01000000)  /* Mask MAC Address low reg bits [7:0] */ 
+#define ETH_MACA1HR_MACA1H   ((uint32_t)0x0000FFFF)  /* MAC address1 high */
+
+/* Bit definition for Ethernet MAC Address1 Low Register */
+#define ETH_MACA1LR_MACA1L   ((uint32_t)0xFFFFFFFF)  /* MAC address1 low */
+
+/* Bit definition for Ethernet MAC Address2 High Register */
+#define ETH_MACA2HR_AE       ((uint32_t)0x80000000)  /* Address enable */
+#define ETH_MACA2HR_SA       ((uint32_t)0x40000000)  /* Source address */
+#define ETH_MACA2HR_MBC      ((uint32_t)0x3F000000)  /* Mask byte control */
+  #define ETH_MACA2HR_MBC_HBits15_8    ((uint32_t)0x20000000)  /* Mask MAC Address high reg bits [15:8] */
+  #define ETH_MACA2HR_MBC_HBits7_0     ((uint32_t)0x10000000)  /* Mask MAC Address high reg bits [7:0] */
+  #define ETH_MACA2HR_MBC_LBits31_24   ((uint32_t)0x08000000)  /* Mask MAC Address low reg bits [31:24] */
+  #define ETH_MACA2HR_MBC_LBits23_16   ((uint32_t)0x04000000)  /* Mask MAC Address low reg bits [23:16] */
+  #define ETH_MACA2HR_MBC_LBits15_8    ((uint32_t)0x02000000)  /* Mask MAC Address low reg bits [15:8] */
+  #define ETH_MACA2HR_MBC_LBits7_0     ((uint32_t)0x01000000)  /* Mask MAC Address low reg bits [70] */
+#define ETH_MACA2HR_MACA2H   ((uint32_t)0x0000FFFF)  /* MAC address1 high */
+
+/* Bit definition for Ethernet MAC Address2 Low Register */
+#define ETH_MACA2LR_MACA2L   ((uint32_t)0xFFFFFFFF)  /* MAC address2 low */
+
+/* Bit definition for Ethernet MAC Address3 High Register */
+#define ETH_MACA3HR_AE       ((uint32_t)0x80000000)  /* Address enable */
+#define ETH_MACA3HR_SA       ((uint32_t)0x40000000)  /* Source address */
+#define ETH_MACA3HR_MBC      ((uint32_t)0x3F000000)  /* Mask byte control */
+  #define ETH_MACA3HR_MBC_HBits15_8    ((uint32_t)0x20000000)  /* Mask MAC Address high reg bits [15:8] */
+  #define ETH_MACA3HR_MBC_HBits7_0     ((uint32_t)0x10000000)  /* Mask MAC Address high reg bits [7:0] */
+  #define ETH_MACA3HR_MBC_LBits31_24   ((uint32_t)0x08000000)  /* Mask MAC Address low reg bits [31:24] */
+  #define ETH_MACA3HR_MBC_LBits23_16   ((uint32_t)0x04000000)  /* Mask MAC Address low reg bits [23:16] */
+  #define ETH_MACA3HR_MBC_LBits15_8    ((uint32_t)0x02000000)  /* Mask MAC Address low reg bits [15:8] */
+  #define ETH_MACA3HR_MBC_LBits7_0     ((uint32_t)0x01000000)  /* Mask MAC Address low reg bits [70] */
+#define ETH_MACA3HR_MACA3H   ((uint32_t)0x0000FFFF)  /* MAC address3 high */
+
+/* Bit definition for Ethernet MAC Address3 Low Register */
+#define ETH_MACA3LR_MACA3L   ((uint32_t)0xFFFFFFFF)  /* MAC address3 low */
+
+/******************************************************************************/
+/*                Ethernet MMC Registers bits definition                      */
+/******************************************************************************/
+
+/* Bit definition for Ethernet MMC Contol Register */
+#define ETH_MMCCR_MCFHP      ((uint32_t)0x00000020)  /* MMC counter Full-Half preset */
+#define ETH_MMCCR_MCP        ((uint32_t)0x00000010)  /* MMC counter preset */
+#define ETH_MMCCR_MCF        ((uint32_t)0x00000008)  /* MMC Counter Freeze */
+#define ETH_MMCCR_ROR        ((uint32_t)0x00000004)  /* Reset on Read */
+#define ETH_MMCCR_CSR        ((uint32_t)0x00000002)  /* Counter Stop Rollover */
+#define ETH_MMCCR_CR         ((uint32_t)0x00000001)  /* Counters Reset */
+
+/* Bit definition for Ethernet MMC Receive Interrupt Register */
+#define ETH_MMCRIR_RGUFS     ((uint32_t)0x00020000)  /* Set when Rx good unicast frames counter reaches half the maximum value */
+#define ETH_MMCRIR_RFAES     ((uint32_t)0x00000040)  /* Set when Rx alignment error counter reaches half the maximum value */
+#define ETH_MMCRIR_RFCES     ((uint32_t)0x00000020)  /* Set when Rx crc error counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Transmit Interrupt Register */
+#define ETH_MMCTIR_TGFS      ((uint32_t)0x00200000)  /* Set when Tx good frame count counter reaches half the maximum value */
+#define ETH_MMCTIR_TGFMSCS   ((uint32_t)0x00008000)  /* Set when Tx good multi col counter reaches half the maximum value */
+#define ETH_MMCTIR_TGFSCS    ((uint32_t)0x00004000)  /* Set when Tx good single col counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Receive Interrupt Mask Register */
+#define ETH_MMCRIMR_RGUFM    ((uint32_t)0x00020000)  /* Mask the interrupt when Rx good unicast frames counter reaches half the maximum value */
+#define ETH_MMCRIMR_RFAEM    ((uint32_t)0x00000040)  /* Mask the interrupt when when Rx alignment error counter reaches half the maximum value */
+#define ETH_MMCRIMR_RFCEM    ((uint32_t)0x00000020)  /* Mask the interrupt when Rx crc error counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Transmit Interrupt Mask Register */
+#define ETH_MMCTIMR_TGFM     ((uint32_t)0x00200000)  /* Mask the interrupt when Tx good frame count counter reaches half the maximum value */
+#define ETH_MMCTIMR_TGFMSCM  ((uint32_t)0x00008000)  /* Mask the interrupt when Tx good multi col counter reaches half the maximum value */
+#define ETH_MMCTIMR_TGFSCM   ((uint32_t)0x00004000)  /* Mask the interrupt when Tx good single col counter reaches half the maximum value */
+
+/* Bit definition for Ethernet MMC Transmitted Good Frames after Single Collision Counter Register */
+#define ETH_MMCTGFSCCR_TGFSCC     ((uint32_t)0xFFFFFFFF)  /* Number of successfully transmitted frames after a single collision in Half-duplex mode. */
+
+/* Bit definition for Ethernet MMC Transmitted Good Frames after More than a Single Collision Counter Register */
+#define ETH_MMCTGFMSCCR_TGFMSCC   ((uint32_t)0xFFFFFFFF)  /* Number of successfully transmitted frames after more than a single collision in Half-duplex mode. */
+
+/* Bit definition for Ethernet MMC Transmitted Good Frames Counter Register */
+#define ETH_MMCTGFCR_TGFC    ((uint32_t)0xFFFFFFFF)  /* Number of good frames transmitted. */
+
+/* Bit definition for Ethernet MMC Received Frames with CRC Error Counter Register */
+#define ETH_MMCRFCECR_RFCEC  ((uint32_t)0xFFFFFFFF)  /* Number of frames received with CRC error. */
+
+/* Bit definition for Ethernet MMC Received Frames with Alignement Error Counter Register */
+#define ETH_MMCRFAECR_RFAEC  ((uint32_t)0xFFFFFFFF)  /* Number of frames received with alignment (dribble) error */
+
+/* Bit definition for Ethernet MMC Received Good Unicast Frames Counter Register */
+#define ETH_MMCRGUFCR_RGUFC  ((uint32_t)0xFFFFFFFF)  /* Number of good unicast frames received. */
+
+/******************************************************************************/
+/*               Ethernet PTP Registers bits definition                       */
+/******************************************************************************/
+
+/* Bit definition for Ethernet PTP Time Stamp Contol Register */
+#define ETH_PTPTSCR_TSCNT       ((uint32_t)0x00030000)  /* Time stamp clock node type */
+#define ETH_PTPTSSR_TSSMRME     ((uint32_t)0x00008000)  /* Time stamp snapshot for message relevant to master enable */
+#define ETH_PTPTSSR_TSSEME      ((uint32_t)0x00004000)  /* Time stamp snapshot for event message enable */
+#define ETH_PTPTSSR_TSSIPV4FE   ((uint32_t)0x00002000)  /* Time stamp snapshot for IPv4 frames enable */
+#define ETH_PTPTSSR_TSSIPV6FE   ((uint32_t)0x00001000)  /* Time stamp snapshot for IPv6 frames enable */
+#define ETH_PTPTSSR_TSSPTPOEFE  ((uint32_t)0x00000800)  /* Time stamp snapshot for PTP over ethernet frames enable */
+#define ETH_PTPTSSR_TSPTPPSV2E  ((uint32_t)0x00000400)  /* Time stamp PTP packet snooping for version2 format enable */
+#define ETH_PTPTSSR_TSSSR       ((uint32_t)0x00000200)  /* Time stamp Sub-seconds rollover */
+#define ETH_PTPTSSR_TSSARFE     ((uint32_t)0x00000100)  /* Time stamp snapshot for all received frames enable */
+
+#define ETH_PTPTSCR_TSARU    ((uint32_t)0x00000020)  /* Addend register update */
+#define ETH_PTPTSCR_TSITE    ((uint32_t)0x00000010)  /* Time stamp interrupt trigger enable */
+#define ETH_PTPTSCR_TSSTU    ((uint32_t)0x00000008)  /* Time stamp update */
+#define ETH_PTPTSCR_TSSTI    ((uint32_t)0x00000004)  /* Time stamp initialize */
+#define ETH_PTPTSCR_TSFCU    ((uint32_t)0x00000002)  /* Time stamp fine or coarse update */
+#define ETH_PTPTSCR_TSE      ((uint32_t)0x00000001)  /* Time stamp enable */
+
+/* Bit definition for Ethernet PTP Sub-Second Increment Register */
+#define ETH_PTPSSIR_STSSI    ((uint32_t)0x000000FF)  /* System time Sub-second increment value */
+
+/* Bit definition for Ethernet PTP Time Stamp High Register */
+#define ETH_PTPTSHR_STS      ((uint32_t)0xFFFFFFFF)  /* System Time second */
+
+/* Bit definition for Ethernet PTP Time Stamp Low Register */
+#define ETH_PTPTSLR_STPNS    ((uint32_t)0x80000000)  /* System Time Positive or negative time */
+#define ETH_PTPTSLR_STSS     ((uint32_t)0x7FFFFFFF)  /* System Time sub-seconds */
+
+/* Bit definition for Ethernet PTP Time Stamp High Update Register */
+#define ETH_PTPTSHUR_TSUS    ((uint32_t)0xFFFFFFFF)  /* Time stamp update seconds */
+
+/* Bit definition for Ethernet PTP Time Stamp Low Update Register */
+#define ETH_PTPTSLUR_TSUPNS  ((uint32_t)0x80000000)  /* Time stamp update Positive or negative time */
+#define ETH_PTPTSLUR_TSUSS   ((uint32_t)0x7FFFFFFF)  /* Time stamp update sub-seconds */
+
+/* Bit definition for Ethernet PTP Time Stamp Addend Register */
+#define ETH_PTPTSAR_TSA      ((uint32_t)0xFFFFFFFF)  /* Time stamp addend */
+
+/* Bit definition for Ethernet PTP Target Time High Register */
+#define ETH_PTPTTHR_TTSH     ((uint32_t)0xFFFFFFFF)  /* Target time stamp high */
+
+/* Bit definition for Ethernet PTP Target Time Low Register */
+#define ETH_PTPTTLR_TTSL     ((uint32_t)0xFFFFFFFF)  /* Target time stamp low */
+
+/* Bit definition for Ethernet PTP Time Stamp Status Register */
+#define ETH_PTPTSSR_TSTTR    ((uint32_t)0x00000020)  /* Time stamp target time reached */
+#define ETH_PTPTSSR_TSSO     ((uint32_t)0x00000010)  /* Time stamp seconds overflow */
+
+/******************************************************************************/
+/*                 Ethernet DMA Registers bits definition                     */
+/******************************************************************************/
+
+/* Bit definition for Ethernet DMA Bus Mode Register */
+#define ETH_DMABMR_AAB       ((uint32_t)0x02000000)  /* Address-Aligned beats */
+#define ETH_DMABMR_FPM        ((uint32_t)0x01000000)  /* 4xPBL mode */
+#define ETH_DMABMR_USP       ((uint32_t)0x00800000)  /* Use separate PBL */
+#define ETH_DMABMR_RDP       ((uint32_t)0x007E0000)  /* RxDMA PBL */
+  #define ETH_DMABMR_RDP_1Beat    ((uint32_t)0x00020000)  /* maximum number of beats to be transferred in one RxDMA transaction is 1 */
+  #define ETH_DMABMR_RDP_2Beat    ((uint32_t)0x00040000)  /* maximum number of beats to be transferred in one RxDMA transaction is 2 */
+  #define ETH_DMABMR_RDP_4Beat    ((uint32_t)0x00080000)  /* maximum number of beats to be transferred in one RxDMA transaction is 4 */
+  #define ETH_DMABMR_RDP_8Beat    ((uint32_t)0x00100000)  /* maximum number of beats to be transferred in one RxDMA transaction is 8 */
+  #define ETH_DMABMR_RDP_16Beat   ((uint32_t)0x00200000)  /* maximum number of beats to be transferred in one RxDMA transaction is 16 */
+  #define ETH_DMABMR_RDP_32Beat   ((uint32_t)0x00400000)  /* maximum number of beats to be transferred in one RxDMA transaction is 32 */                
+  #define ETH_DMABMR_RDP_4xPBL_4Beat   ((uint32_t)0x01020000)  /* maximum number of beats to be transferred in one RxDMA transaction is 4 */
+  #define ETH_DMABMR_RDP_4xPBL_8Beat   ((uint32_t)0x01040000)  /* maximum number of beats to be transferred in one RxDMA transaction is 8 */
+  #define ETH_DMABMR_RDP_4xPBL_16Beat  ((uint32_t)0x01080000)  /* maximum number of beats to be transferred in one RxDMA transaction is 16 */
+  #define ETH_DMABMR_RDP_4xPBL_32Beat  ((uint32_t)0x01100000)  /* maximum number of beats to be transferred in one RxDMA transaction is 32 */
+  #define ETH_DMABMR_RDP_4xPBL_64Beat  ((uint32_t)0x01200000)  /* maximum number of beats to be transferred in one RxDMA transaction is 64 */
+  #define ETH_DMABMR_RDP_4xPBL_128Beat ((uint32_t)0x01400000)  /* maximum number of beats to be transferred in one RxDMA transaction is 128 */  
+#define ETH_DMABMR_FB        ((uint32_t)0x00010000)  /* Fixed Burst */
+#define ETH_DMABMR_RTPR      ((uint32_t)0x0000C000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_1_1     ((uint32_t)0x00000000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_2_1     ((uint32_t)0x00004000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_3_1     ((uint32_t)0x00008000)  /* Rx Tx priority ratio */
+  #define ETH_DMABMR_RTPR_4_1     ((uint32_t)0x0000C000)  /* Rx Tx priority ratio */  
+#define ETH_DMABMR_PBL    ((uint32_t)0x00003F00)  /* Programmable burst length */
+  #define ETH_DMABMR_PBL_1Beat    ((uint32_t)0x00000100)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 1 */
+  #define ETH_DMABMR_PBL_2Beat    ((uint32_t)0x00000200)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 2 */
+  #define ETH_DMABMR_PBL_4Beat    ((uint32_t)0x00000400)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */
+  #define ETH_DMABMR_PBL_8Beat    ((uint32_t)0x00000800)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */
+  #define ETH_DMABMR_PBL_16Beat   ((uint32_t)0x00001000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */
+  #define ETH_DMABMR_PBL_32Beat   ((uint32_t)0x00002000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */                
+  #define ETH_DMABMR_PBL_4xPBL_4Beat   ((uint32_t)0x01000100)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */
+  #define ETH_DMABMR_PBL_4xPBL_8Beat   ((uint32_t)0x01000200)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */
+  #define ETH_DMABMR_PBL_4xPBL_16Beat  ((uint32_t)0x01000400)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */
+  #define ETH_DMABMR_PBL_4xPBL_32Beat  ((uint32_t)0x01000800)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */
+  #define ETH_DMABMR_PBL_4xPBL_64Beat  ((uint32_t)0x01001000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 64 */
+  #define ETH_DMABMR_PBL_4xPBL_128Beat ((uint32_t)0x01002000)  /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 128 */
+#define ETH_DMABMR_EDE       ((uint32_t)0x00000080)  /* Enhanced Descriptor Enable */
+#define ETH_DMABMR_DSL       ((uint32_t)0x0000007C)  /* Descriptor Skip Length */
+#define ETH_DMABMR_DA        ((uint32_t)0x00000002)  /* DMA arbitration scheme */
+#define ETH_DMABMR_SR        ((uint32_t)0x00000001)  /* Software reset */
+
+/* Bit definition for Ethernet DMA Transmit Poll Demand Register */
+#define ETH_DMATPDR_TPD      ((uint32_t)0xFFFFFFFF)  /* Transmit poll demand */
+
+/* Bit definition for Ethernet DMA Receive Poll Demand Register */
+#define ETH_DMARPDR_RPD      ((uint32_t)0xFFFFFFFF)  /* Receive poll demand  */
+
+/* Bit definition for Ethernet DMA Receive Descriptor List Address Register */
+#define ETH_DMARDLAR_SRL     ((uint32_t)0xFFFFFFFF)  /* Start of receive list */
+
+/* Bit definition for Ethernet DMA Transmit Descriptor List Address Register */
+#define ETH_DMATDLAR_STL     ((uint32_t)0xFFFFFFFF)  /* Start of transmit list */
+
+/* Bit definition for Ethernet DMA Status Register */
+#define ETH_DMASR_TSTS       ((uint32_t)0x20000000)  /* Time-stamp trigger status */
+#define ETH_DMASR_PMTS       ((uint32_t)0x10000000)  /* PMT status */
+#define ETH_DMASR_MMCS       ((uint32_t)0x08000000)  /* MMC status */
+#define ETH_DMASR_EBS        ((uint32_t)0x03800000)  /* Error bits status */
+  /* combination with EBS[2:0] for GetFlagStatus function */
+  #define ETH_DMASR_EBS_DescAccess      ((uint32_t)0x02000000)  /* Error bits 0-data buffer, 1-desc. access */
+  #define ETH_DMASR_EBS_ReadTransf      ((uint32_t)0x01000000)  /* Error bits 0-write trnsf, 1-read transfr */
+  #define ETH_DMASR_EBS_DataTransfTx    ((uint32_t)0x00800000)  /* Error bits 0-Rx DMA, 1-Tx DMA */
+#define ETH_DMASR_TPS         ((uint32_t)0x00700000)  /* Transmit process state */
+  #define ETH_DMASR_TPS_Stopped         ((uint32_t)0x00000000)  /* Stopped - Reset or Stop Tx Command issued  */
+  #define ETH_DMASR_TPS_Fetching        ((uint32_t)0x00100000)  /* Running - fetching the Tx descriptor */
+  #define ETH_DMASR_TPS_Waiting         ((uint32_t)0x00200000)  /* Running - waiting for status */
+  #define ETH_DMASR_TPS_Reading         ((uint32_t)0x00300000)  /* Running - reading the data from host memory */
+  #define ETH_DMASR_TPS_Suspended       ((uint32_t)0x00600000)  /* Suspended - Tx Descriptor unavailabe */
+  #define ETH_DMASR_TPS_Closing         ((uint32_t)0x00700000)  /* Running - closing Rx descriptor */
+#define ETH_DMASR_RPS         ((uint32_t)0x000E0000)  /* Receive process state */
+  #define ETH_DMASR_RPS_Stopped         ((uint32_t)0x00000000)  /* Stopped - Reset or Stop Rx Command issued */
+  #define ETH_DMASR_RPS_Fetching        ((uint32_t)0x00020000)  /* Running - fetching the Rx descriptor */
+  #define ETH_DMASR_RPS_Waiting         ((uint32_t)0x00060000)  /* Running - waiting for packet */
+  #define ETH_DMASR_RPS_Suspended       ((uint32_t)0x00080000)  /* Suspended - Rx Descriptor unavailable */
+  #define ETH_DMASR_RPS_Closing         ((uint32_t)0x000A0000)  /* Running - closing descriptor */
+  #define ETH_DMASR_RPS_Queuing         ((uint32_t)0x000E0000)  /* Running - queuing the recieve frame into host memory */
+#define ETH_DMASR_NIS        ((uint32_t)0x00010000)  /* Normal interrupt summary */
+#define ETH_DMASR_AIS        ((uint32_t)0x00008000)  /* Abnormal interrupt summary */
+#define ETH_DMASR_ERS        ((uint32_t)0x00004000)  /* Early receive status */
+#define ETH_DMASR_FBES       ((uint32_t)0x00002000)  /* Fatal bus error status */
+#define ETH_DMASR_ETS        ((uint32_t)0x00000400)  /* Early transmit status */
+#define ETH_DMASR_RWTS       ((uint32_t)0x00000200)  /* Receive watchdog timeout status */
+#define ETH_DMASR_RPSS       ((uint32_t)0x00000100)  /* Receive process stopped status */
+#define ETH_DMASR_RBUS       ((uint32_t)0x00000080)  /* Receive buffer unavailable status */
+#define ETH_DMASR_RS         ((uint32_t)0x00000040)  /* Receive status */
+#define ETH_DMASR_TUS        ((uint32_t)0x00000020)  /* Transmit underflow status */
+#define ETH_DMASR_ROS        ((uint32_t)0x00000010)  /* Receive overflow status */
+#define ETH_DMASR_TJTS       ((uint32_t)0x00000008)  /* Transmit jabber timeout status */
+#define ETH_DMASR_TBUS       ((uint32_t)0x00000004)  /* Transmit buffer unavailable status */
+#define ETH_DMASR_TPSS       ((uint32_t)0x00000002)  /* Transmit process stopped status */
+#define ETH_DMASR_TS         ((uint32_t)0x00000001)  /* Transmit status */
+
+/* Bit definition for Ethernet DMA Operation Mode Register */
+#define ETH_DMAOMR_DTCEFD    ((uint32_t)0x04000000)  /* Disable Dropping of TCP/IP checksum error frames */
+#define ETH_DMAOMR_RSF       ((uint32_t)0x02000000)  /* Receive store and forward */
+#define ETH_DMAOMR_DFRF      ((uint32_t)0x01000000)  /* Disable flushing of received frames */
+#define ETH_DMAOMR_TSF       ((uint32_t)0x00200000)  /* Transmit store and forward */
+#define ETH_DMAOMR_FTF       ((uint32_t)0x00100000)  /* Flush transmit FIFO */
+#define ETH_DMAOMR_TTC       ((uint32_t)0x0001C000)  /* Transmit threshold control */
+  #define ETH_DMAOMR_TTC_64Bytes       ((uint32_t)0x00000000)  /* threshold level of the MTL Transmit FIFO is 64 Bytes */
+  #define ETH_DMAOMR_TTC_128Bytes      ((uint32_t)0x00004000)  /* threshold level of the MTL Transmit FIFO is 128 Bytes */
+  #define ETH_DMAOMR_TTC_192Bytes      ((uint32_t)0x00008000)  /* threshold level of the MTL Transmit FIFO is 192 Bytes */
+  #define ETH_DMAOMR_TTC_256Bytes      ((uint32_t)0x0000C000)  /* threshold level of the MTL Transmit FIFO is 256 Bytes */
+  #define ETH_DMAOMR_TTC_40Bytes       ((uint32_t)0x00010000)  /* threshold level of the MTL Transmit FIFO is 40 Bytes */
+  #define ETH_DMAOMR_TTC_32Bytes       ((uint32_t)0x00014000)  /* threshold level of the MTL Transmit FIFO is 32 Bytes */
+  #define ETH_DMAOMR_TTC_24Bytes       ((uint32_t)0x00018000)  /* threshold level of the MTL Transmit FIFO is 24 Bytes */
+  #define ETH_DMAOMR_TTC_16Bytes       ((uint32_t)0x0001C000)  /* threshold level of the MTL Transmit FIFO is 16 Bytes */
+#define ETH_DMAOMR_ST        ((uint32_t)0x00002000)  /* Start/stop transmission command */
+#define ETH_DMAOMR_FEF       ((uint32_t)0x00000080)  /* Forward error frames */
+#define ETH_DMAOMR_FUGF      ((uint32_t)0x00000040)  /* Forward undersized good frames */
+#define ETH_DMAOMR_RTC       ((uint32_t)0x00000018)  /* receive threshold control */
+  #define ETH_DMAOMR_RTC_64Bytes       ((uint32_t)0x00000000)  /* threshold level of the MTL Receive FIFO is 64 Bytes */
+  #define ETH_DMAOMR_RTC_32Bytes       ((uint32_t)0x00000008)  /* threshold level of the MTL Receive FIFO is 32 Bytes */
+  #define ETH_DMAOMR_RTC_96Bytes       ((uint32_t)0x00000010)  /* threshold level of the MTL Receive FIFO is 96 Bytes */
+  #define ETH_DMAOMR_RTC_128Bytes      ((uint32_t)0x00000018)  /* threshold level of the MTL Receive FIFO is 128 Bytes */
+#define ETH_DMAOMR_OSF       ((uint32_t)0x00000004)  /* operate on second frame */
+#define ETH_DMAOMR_SR        ((uint32_t)0x00000002)  /* Start/stop receive */
+
+/* Bit definition for Ethernet DMA Interrupt Enable Register */
+#define ETH_DMAIER_NISE      ((uint32_t)0x00010000)  /* Normal interrupt summary enable */
+#define ETH_DMAIER_AISE      ((uint32_t)0x00008000)  /* Abnormal interrupt summary enable */
+#define ETH_DMAIER_ERIE      ((uint32_t)0x00004000)  /* Early receive interrupt enable */
+#define ETH_DMAIER_FBEIE     ((uint32_t)0x00002000)  /* Fatal bus error interrupt enable */
+#define ETH_DMAIER_ETIE      ((uint32_t)0x00000400)  /* Early transmit interrupt enable */
+#define ETH_DMAIER_RWTIE     ((uint32_t)0x00000200)  /* Receive watchdog timeout interrupt enable */
+#define ETH_DMAIER_RPSIE     ((uint32_t)0x00000100)  /* Receive process stopped interrupt enable */
+#define ETH_DMAIER_RBUIE     ((uint32_t)0x00000080)  /* Receive buffer unavailable interrupt enable */
+#define ETH_DMAIER_RIE       ((uint32_t)0x00000040)  /* Receive interrupt enable */
+#define ETH_DMAIER_TUIE      ((uint32_t)0x00000020)  /* Transmit Underflow interrupt enable */
+#define ETH_DMAIER_ROIE      ((uint32_t)0x00000010)  /* Receive Overflow interrupt enable */
+#define ETH_DMAIER_TJTIE     ((uint32_t)0x00000008)  /* Transmit jabber timeout interrupt enable */
+#define ETH_DMAIER_TBUIE     ((uint32_t)0x00000004)  /* Transmit buffer unavailable interrupt enable */
+#define ETH_DMAIER_TPSIE     ((uint32_t)0x00000002)  /* Transmit process stopped interrupt enable */
+#define ETH_DMAIER_TIE       ((uint32_t)0x00000001)  /* Transmit interrupt enable */
+
+/* Bit definition for Ethernet DMA Missed Frame and Buffer Overflow Counter Register */
+#define ETH_DMAMFBOCR_OFOC   ((uint32_t)0x10000000)  /* Overflow bit for FIFO overflow counter */
+#define ETH_DMAMFBOCR_MFA    ((uint32_t)0x0FFE0000)  /* Number of frames missed by the application */
+#define ETH_DMAMFBOCR_OMFC   ((uint32_t)0x00010000)  /* Overflow bit for missed frame counter */
+#define ETH_DMAMFBOCR_MFC    ((uint32_t)0x0000FFFF)  /* Number of frames missed by the controller */
+
+/* Bit definition for Ethernet DMA Current Host Transmit Descriptor Register */
+#define ETH_DMACHTDR_HTDAP   ((uint32_t)0xFFFFFFFF)  /* Host transmit descriptor address pointer */
+
+/* Bit definition for Ethernet DMA Current Host Receive Descriptor Register */
+#define ETH_DMACHRDR_HRDAP   ((uint32_t)0xFFFFFFFF)  /* Host receive descriptor address pointer */
+
+/* Bit definition for Ethernet DMA Current Host Transmit Buffer Address Register */
+#define ETH_DMACHTBAR_HTBAP  ((uint32_t)0xFFFFFFFF)  /* Host transmit buffer address pointer */
+
+/* Bit definition for Ethernet DMA Current Host Receive Buffer Address Register */
+#define ETH_DMACHRBAR_HRBAP  ((uint32_t)0xFFFFFFFF)  /* Host receive buffer address pointer */
+
+/**
+  *
+  */
+
+ /**
+  * @}
+  */ 
+
+#ifdef USE_STDPERIPH_DRIVER
+  #include "stm32f4xx_conf.h"
+#endif /* USE_STDPERIPH_DRIVER */
+
+/** @addtogroup Exported_macro
+  * @{
+  */
+
+#define SET_BIT(REG, BIT)     ((REG) |= (BIT))
+
+#define CLEAR_BIT(REG, BIT)   ((REG) &= ~(BIT))
+
+#define READ_BIT(REG, BIT)    ((REG) & (BIT))
+
+#define CLEAR_REG(REG)        ((REG) = (0x0))
+
+#define WRITE_REG(REG, VAL)   ((REG) = (VAL))
+
+#define READ_REG(REG)         ((REG))
+
+#define MODIFY_REG(REG, CLEARMASK, SETMASK)  WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
+
+/**
+  * @}
+  */
+
+#ifdef __cplusplus
+}
+#endif /* __cplusplus */
+
+#endif /* __STM32F4xx_H */
+
+/**
+  * @}
+  */
+
+  /**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Include/system_stm32f4xx.h b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Include/system_stm32f4xx.h
new file mode 100644
index 0000000000000000000000000000000000000000..675593a84d13f52ee3ef97937c92f87e20f89c67
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Include/system_stm32f4xx.h
@@ -0,0 +1,105 @@
+/**
+  ******************************************************************************
+  * @file    system_stm32f4xx.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.       
+  ******************************************************************************  
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/** @addtogroup CMSIS
+  * @{
+  */
+
+/** @addtogroup stm32f4xx_system
+  * @{
+  */  
+  
+/**
+  * @brief Define to prevent recursive inclusion
+  */
+#ifndef __SYSTEM_STM32F4XX_H
+#define __SYSTEM_STM32F4XX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif 
+
+/** @addtogroup STM32F4xx_System_Includes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+
+/** @addtogroup STM32F4xx_System_Exported_types
+  * @{
+  */
+
+extern uint32_t SystemCoreClock;          /*!< System Clock Frequency (Core Clock) */
+
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Exported_Constants
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Exported_Functions
+  * @{
+  */
+  
+extern void SystemInit(void);
+extern void SystemCoreClockUpdate(void);
+/**
+  * @}
+  */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F4XX_H */
+
+/**
+  * @}
+  */
+  
+/**
+  * @}
+  */  
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Release_Notes.html b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Release_Notes.html
new file mode 100644
index 0000000000000000000000000000000000000000..ed2756014f205f3c982f59d3721295adf4f9f82d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Release_Notes.html
@@ -0,0 +1,192 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html xmlns:v="urn:schemas-microsoft-com:vml" xmlns:o="urn:schemas-microsoft-com:office:office" xmlns:w="urn:schemas-microsoft-com:office:word" xmlns="http://www.w3.org/TR/REC-html40"><head>
+
+
+
+<meta http-equiv="Content-Type" content="text/html; charset=iso-8859-1">
+<link rel="File-List" href="Library_files/filelist.xml">
+<link rel="Edit-Time-Data" href="Library_files/editdata.mso"><!--[if !mso]> <style> v\:* {behavior:url(#default#VML);} o\:* {behavior:url(#default#VML);} w\:* {behavior:url(#default#VML);} .shape {behavior:url(#default#VML);} </style> <![endif]--><title>Release Notes for STM32F4xx CMSIS</title><!--[if gte mso 9]><xml> <o:DocumentProperties> <o:Author>STMicroelectronics</o:Author> <o:LastAuthor>STMicroelectronics</o:LastAuthor> <o:Revision>37</o:Revision> <o:TotalTime>136</o:TotalTime> <o:Created>2009-02-27T19:26:00Z</o:Created> <o:LastSaved>2009-03-01T17:56:00Z</o:LastSaved> <o:Pages>1</o:Pages> <o:Words>522</o:Words> <o:Characters>2977</o:Characters> <o:Company>STMicroelectronics</o:Company> <o:Lines>24</o:Lines> <o:Paragraphs>6</o:Paragraphs> <o:CharactersWithSpaces>3493</o:CharactersWithSpaces> <o:Version>11.6568</o:Version> </o:DocumentProperties> </xml><![endif]--><!--[if gte mso 9]><xml> <w:WordDocument> <w:Zoom>110</w:Zoom> <w:ValidateAgainstSchemas/> <w:SaveIfXMLInvalid>false</w:SaveIfXMLInvalid> <w:IgnoreMixedContent>false</w:IgnoreMixedContent> <w:AlwaysShowPlaceholderText>false</w:AlwaysShowPlaceholderText> <w:BrowserLevel>MicrosoftInternetExplorer4</w:BrowserLevel> </w:WordDocument> </xml><![endif]--><!--[if gte mso 9]><xml> <w:LatentStyles DefLockedState="false" LatentStyleCount="156"> </w:LatentStyles> </xml><![endif]-->
+
+
+
+<style>
+<!--
+/* Style Definitions */
+p.MsoNormal, li.MsoNormal, div.MsoNormal
+{mso-style-parent:"";
+margin:0in;
+margin-bottom:.0001pt;
+mso-pagination:widow-orphan;
+font-size:12.0pt;
+font-family:"Times New Roman";
+mso-fareast-font-family:"Times New Roman";}
+h2
+{mso-style-next:Normal;
+margin-top:12.0pt;
+margin-right:0in;
+margin-bottom:3.0pt;
+margin-left:0in;
+mso-pagination:widow-orphan;
+page-break-after:avoid;
+mso-outline-level:2;
+font-size:14.0pt;
+font-family:Arial;
+font-weight:bold;
+font-style:italic;}
+a:link, span.MsoHyperlink
+{color:blue;
+text-decoration:underline;
+text-underline:single;}
+a:visited, span.MsoHyperlinkFollowed
+{color:blue;
+text-decoration:underline;
+text-underline:single;}
+p
+{mso-margin-top-alt:auto;
+margin-right:0in;
+mso-margin-bottom-alt:auto;
+margin-left:0in;
+mso-pagination:widow-orphan;
+font-size:12.0pt;
+font-family:"Times New Roman";
+mso-fareast-font-family:"Times New Roman";}
+@page Section1
+{size:8.5in 11.0in;
+margin:1.0in 1.25in 1.0in 1.25in;
+mso-header-margin:.5in;
+mso-footer-margin:.5in;
+mso-paper-source:0;}
+div.Section1
+{page:Section1;}
+-->
+</style><!--[if gte mso 10]> <style> /* Style Definitions */ table.MsoNormalTable {mso-style-name:"Table Normal"; mso-tstyle-rowband-size:0; mso-tstyle-colband-size:0; mso-style-noshow:yes; mso-style-parent:""; mso-padding-alt:0in 5.4pt 0in 5.4pt; mso-para-margin:0in; mso-para-margin-bottom:.0001pt; mso-pagination:widow-orphan; font-size:10.0pt; font-family:"Times New Roman"; mso-ansi-language:#0400; mso-fareast-language:#0400; mso-bidi-language:#0400;} </style> <![endif]--><!--[if gte mso 9]><xml> <o:shapedefaults v:ext="edit" spidmax="5122"/> </xml><![endif]--><!--[if gte mso 9]><xml> <o:shapelayout v:ext="edit"> <o:idmap v:ext="edit" data="1"/> </o:shapelayout></xml><![endif]--></head>
+<body style="" lang="EN-US" link="blue" vlink="blue">
+<div class="Section1">
+<p class="MsoNormal"><span style="font-family: Arial;"><o:p><br>
+</o:p></span></p>
+<div align="center">
+<table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+<tbody>
+<tr style="">
+<td style="padding: 0cm;" valign="top">
+<table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+<tbody>
+          <tr>
+            <td style="vertical-align: top;"><span style="font-size: 8pt; font-family: Arial; color: blue;"><a href="../../../../../Release_Notes.html">Back to Release page</a></span></td>
+          </tr>
+<tr style="">
+<td style="padding: 1.5pt;">
+<h1 style="margin-bottom: 18pt; text-align: center;" align="center"><span style="font-size: 20pt; font-family: Verdana; color: rgb(51, 102, 255);">Release
+Notes for STM32F4xx CMSIS</span><span style="font-size: 20pt; font-family: Verdana;"><o:p></o:p></span></h1>
+<p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: Arial; color: black;">Copyright 2013 STMicroelectronics</span><span style="color: black;"><u1:p></u1:p><o:p></o:p></span></p>
+<p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: Arial; color: black;"><img alt="" id="_x0000_i1025" src="../../../../../_htmresc/logo.bmp" style="border: 0px solid ; width: 86px; height: 65px;"></span><span style="font-size: 10pt;"><o:p></o:p></span></p>
+</td>
+</tr>
+</tbody>
+</table>
+<p class="MsoNormal"><span style="font-family: Arial; display: none;"><o:p>&nbsp;</o:p></span></p>
+<table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" width="900">
+<tbody>
+<tr>
+<td style="padding: 0cm;" valign="top">
+<h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><span style="font-size: 12pt; color: white;">Contents<o:p></o:p></span></h2>
+<ol style="margin-top: 0cm;" start="1" type="1">
+<li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><a href="#History">STM32F4xx&nbsp;CMSIS
+update History</a><o:p></o:p></span></li>
+<li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><a href="#License">License</a><o:p></o:p></span></li>
+</ol>
+<span style="font-family: &quot;Times New Roman&quot;;"></span>
+<h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="History"></a><span style="font-size: 12pt; color: white;">STM32F4xx CMSIS
+update History</span></h2><span style="font-weight: bold;"></span><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 181px;"><span style="font-size: 10pt; color: white; font-family: Arial;">V1.3.0 / 08-November-2013</span></h3>
+<p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b><u><span style="font-size: 10pt; color: black; font-family: Verdana;">Main 
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add
+support of&nbsp;<span style="font-weight: bold;"></span><span style="font-weight: bold;">STM32F401xExx</span> devices</span><span style="font-size: 10pt; font-family: Verdana;"></span></p></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update startup files&nbsp;<span style="font-weight: bold; font-style: italic;"></span></span><span style="font-size: 10pt; font-family: Verdana;"></span><span style="font-size: 10pt; font-family: Verdana;">"<span style="font-weight: bold; font-style: italic;">startup_stm32f401xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"></span><span style="font-size: 10pt; font-family: Verdana;">&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;"></span></span><span style="font-size: 10pt; font-family: Verdana;">for</span><span style="font-size: 10pt; font-family: Verdana;"> EWARM, MDK-ARM, TrueSTUDIO and Ride toolchains: Add SPI4 interrupt handler entry in the vector table</span>
+</li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 181px;"><span style="font-size: 10pt; color: white; font-family: Arial;">V1.2.1 / 
+19-September-2013</span></h3>
+<p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b><u><span style="font-size: 10pt; color: black; font-family: Verdana;">Main 
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: Verdana;">system_stm32f4xx.c</span><span style="font-size: 10pt; font-family: Verdana;"> : Update FMC SDRAM configuration (RBURST mode activation)<br></span></p></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update startup files&nbsp;<span style="font-weight: bold; font-style: italic;"></span></span><span style="font-size: 10pt; font-family: Verdana;"></span><span style="font-size: 10pt; font-family: Verdana;">"<span style="font-weight: bold; font-style: italic;">startup_stm32f427_437xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"> and </span><span style="font-size: 10pt; font-family: Verdana;">"<span style="font-weight: bold; font-style: italic;">startup_stm32f429_439xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"></span><span style="font-size: 10pt; font-family: Verdana;">&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;"></span></span><span style="font-size: 10pt; font-family: Verdana;"> </span><span style="font-size: 10pt; font-family: Verdana;">for TrueSTUDIO and Ride toolchains and maintain the old name of startup files for legacy purpose</span>
+</li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 181px;"><span style="font-size: 10pt; color: white; font-family: Arial;">V1.2.0 / 
+11-September-2013</span></h3>
+<p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b><u><span style="font-size: 10pt; color: black; font-family: Verdana;">Main 
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add
+support of <span style="font-weight: bold;">STM32F429/439xx</span> and <span style="font-weight: bold;">STM32F401xCxx</span> devices</span></p></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Update definition of <span style="font-weight: bold;">STM32F427/437xx</span> devices : </span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">extension
+of the features to include system clock up to 180MHz, dual bank Flash, reduced
+STOP Mode current, SAI, PCROP, SDRAM and DMA2D</span></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx.h</span><span style="font-size: 10pt; font-family: Verdana;"><br></span><span style="font-size: 10pt; font-family: Verdana;"></span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add the following device defines :</span></li><ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">"#define STM32F40_41xxx" for all&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold;">STM32405/415/407/417xx</span></span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold;">&nbsp;</span>devices</span></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">"#define STM32F427_437xx" for all&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold;">STM32F427/437xx </span>devices</span></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">"#define STM32F429_439xx" for all&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold;">STM32F429/439xx </span>devices</span></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">"#define STM32F401xx" for all&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold;">STM32F401xx&nbsp;</span>devices</span></li></ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Maintain the old device define for legacy purpose</span></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update IRQ handler enumeration structure to support all STM32F4xx Family devices. &nbsp;</span></li></ul>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add new startup files "<span style="font-weight: bold; font-style: italic;">startup_stm32f40_41xxx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;">,</span><span style="font-size: 10pt; font-family: Verdana;">"<span style="font-weight: bold; font-style: italic;">startup_stm32f427_437xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;">,&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">"<span style="font-weight: bold; font-style: italic;">startup_stm32f429_439xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"></span><span style="font-size: 10pt; font-family: Verdana;"> and&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">"<span style="font-weight: bold; font-style: italic;">startup_stm32f401xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"></span><span style="font-size: 10pt; font-family: Verdana;"> </span><span style="font-size: 10pt; font-family: Verdana;">for all toolchains and maintain the old name for startup files for legacy purpose</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">system_stm32f4xx.c</span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update the&nbsp;system configuration to support all&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">STM32F4xx Family devices. &nbsp;</span>
+</li></ul></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; width: 167px; margin-right: 500pt;"><span style="font-size: 10pt; color: white; font-family: Arial;">V1.1.0 / 
+11-January-2013</span></h3>
+<p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b><u><span style="font-size: 10pt; color: black; font-family: Verdana;">Main 
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Official release for&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold;">STM32F427x/437x</span> devices.</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx.h</span><span style="font-size: 10pt; font-family: Verdana;"><br></span><span style="font-size: 10pt; font-family: Verdana;"></span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update product define: replace 
+"#define STM32F4XX" by "#define STM32F40XX" for STM32F40x/41x devices</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">&nbsp;Add new product define: "#define 
+STM32F427X" for&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">STM32F427x/437x</span><span style="font-size: 10pt; font-family: Verdana;"> devices.</span></li></ul>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add new startup files "<span style="font-weight: bold; font-style: italic;">startup_stm32f427x.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"> </span><span style="font-size: 10pt; font-family: Verdana;">for all toolchains</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">rename startup files "<span style="font-weight: bold; font-style: italic;">startup_stm32f4xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"> by </span><span style="font-size: 10pt; font-family: Verdana;">"<span style="font-weight: bold; font-style: italic;">startup_stm32f40xx.s</span>"</span><span style="font-size: 10pt; font-family: Verdana;"> </span><span style="font-size: 10pt; font-family: Verdana;">for all toolchains</span> 
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">system_stm32f4xx.c</span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Prefetch Buffer enabled</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add reference to STM32F427x/437x 
+devices and STM324x7I_EVAL board</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">SystemInit_ExtMemCtl() 
+function<br></span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add configuration of missing FSMC 
+address and data lines <br></span></li></ul>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Change memory type to SRAM instead 
+of PSRAM (PSRAM is available only on STM324xG-EVAL RevA) and update timing 
+values</span></li></ul></li></ul></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 167px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.2 / 05-March-2012<o:p></o:p></span></h3>
+            <p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+
+            <ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">All source files:&nbsp;license disclaimer text update and add link to the License file on ST Internet.</span></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 176px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.1 / 28-December-2011<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">All source files: update disclaimer to add reference to the&nbsp;new license agreement</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx.h</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"></span><span style="font-size: 10pt; font-family: Verdana;">Correct&nbsp;bit definition: </span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">RCC_AHB2RSTR_<span style="font-weight: bold;">HSAH</span>RST</span>&nbsp;changed to <span style="font-style: italic;">RCC_AHB2RSTR_<span style="font-weight: bold;">HASH</span>RST</span></span></li></ul></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 200px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0 / 30-September-2011<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">First official release for&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;">STM32F40x/41x</span> devices</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add startup file for <span style="font-style: italic;">TASKING</span> toolchain</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">system_stm32f4xx.c: driver's&nbsp;comments update</span></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 200px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0RC2 / 26-September-2011<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Official version (V1.0.0) Release Candidate2&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">for <span style="font-weight: bold; font-style: italic;">STM32F40x/41x</span> devices</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx.h</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add define for Cortex-M4 revision&nbsp;<span style="font-style: italic;">__CM4_REV</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Correct <span style="font-style: italic;">RCC_CFGR_PPRE2_DIV16</span> bit&nbsp;(in&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">RCC_CFGR</span><span style="font-size: 10pt; font-family: Verdana;"> register) value to&nbsp;0x0000E000</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Correct some&nbsp;bits definition to be in line with naming used in the Reference Manual </span><span style="font-size: 10pt; font-family: Verdana;"> (RM0090)</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">GPIO_<span style="font-weight: bold;">OTYPER</span>_IDR_x</span> changed to <span style="font-style: italic;">GPIO_<span style="font-weight: bold;">IDR</span>_IDR_x</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">GPIO_<span style="font-weight: bold;">OTYPER</span>_ODR_x</span> changed to <span style="font-style: italic;">GPIO_<span style="font-weight: bold;">ODR</span>_ODR_x</span></span><span style="font-size: 10pt; font-family: Verdana;"></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">SYSCFG_PMC_MII_RMII</span> changed to&nbsp;</span><span style="font-size: 10pt; font-family: Verdana; font-style: italic;">SYSCFG_PMC_MII_RMII<span style="font-weight: bold;">_SEL</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">RCC_APB2RSTR_SPI1</span> changed to&nbsp;<span style="font-style: italic;">RCC_APB2RSTR_SPI1<span style="font-weight: bold;">RST</span></span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">DBGMCU_APB1_FZ_DBG_IWD<span style="font-weight: bold;">E</span>G_STOP</span> changed to&nbsp;<span style="font-style: italic;">DBGMCU_APB1_FZ_DBG_IWDG_STOP</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">PWR_CR_PMODE</span> changed to&nbsp;<span style="font-style: italic;">PWR_CR_VOS</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">PWR_CSR_REGRDY</span> changed to&nbsp;<span style="font-style: italic;">PWR_CSR_VOSRDY</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add new define <span style="font-style: italic;">RCC_AHB1ENR_CCMDATARAMEN</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add new defines&nbsp;<span style="font-style: italic;">SRAM2_BASE, CCMDATARAM_BASE </span>and<span style="font-style: italic;"> BKPSRAM_BASE</span></span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">GPIO_TypeDef structure: in the comment change AFR[2] address mapping&nbsp;to <span style="font-style: italic;">0x20-0x24</span> instead of <span style="font-style: italic;">0x24-0x28</span></span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">system_stm32f4xx.c</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">SystemInit()</span>: add code to enable the FPU</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">SetSysClock()</span>: change <span style="font-style: italic;">PWR_CR_PMODE</span> by&nbsp;<span style="font-style: italic;">PWR_CR_VOS</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">SystemInit_ExtMemCtl()</span>: remove commented values</span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">startup (for all compilers)</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Delete code used to enable the FPU (moved to system_stm32f4xx.c file)</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">File&#8217;s header updated</span></li></ul></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 176px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0RC1 / 25-August-2011<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Official version (V1.0.0) Release Candidate1 for <span style="font-weight: bold; font-style: italic;">STM32F4xx devices</span></span></li></ul><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold;"></span><span style="font-weight: bold; font-style: italic;"></span></span>
+
+<ul style="margin-top: 0in;" type="disc">
+</ul>
+<h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="License"></a><span style="font-size: 12pt; color: white;">License<o:p></o:p></span></h2>
+
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use this&nbsp;</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">package</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"> except in compliance with the License. You may obtain a copy of the License at:<br><br></span></p><div style="text-align: center;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp; <a target="_blank" href="http://www.st.com/software_license_agreement_liberty_v2">http://www.st.com/software_license_agreement_liberty_v2</a></span><br><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"></span></div><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"><br>Unless
+required by applicable law or agreed to in writing, software
+distributed under the License is distributed on an "AS IS" BASIS, <br>WITHOUT
+WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See
+the License for the specific language governing permissions and
+limitations under the License.</span>
+<div class="MsoNormal" style="text-align: center;" align="center"><span style="color: black;">
+<hr align="center" size="2" width="100%"></span></div>
+<p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt; text-align: center;" align="center"><span style="font-size: 10pt; font-family: Verdana; color: black;">For
+complete documentation on </span><span style="font-size: 10pt; font-family: Verdana;">STM32<span style="color: black;"> Microcontrollers
+visit </span><u><span style="color: blue;"><a href="http://www.st.com/internet/mcu/family/141.jsp" target="_blank">www.st.com/STM32</a></span></u></span><span style="color: black;"><o:p></o:p></span></p>
+</td>
+</tr>
+</tbody>
+</table>
+<p class="MsoNormal"><span style="font-size: 10pt;"><o:p></o:p></span></p>
+</td>
+</tr>
+</tbody>
+</table>
+</div>
+<p class="MsoNormal"><o:p>&nbsp;</o:p></p>
+</div>
+</body></html>
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Source/startup_stm32f40xx.s b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Source/startup_stm32f40xx.s
new file mode 100644
index 0000000000000000000000000000000000000000..bdfea9cf62900fc77b40c3743f728a5b3d1b29bb
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Source/startup_stm32f40xx.s
@@ -0,0 +1,516 @@
+/**
+  ******************************************************************************
+  * @file      startup_stm32f40xx.s
+  * @author    MCD Application Team
+  * @version   V1.3.0
+  * @date      08-November-2013
+  * @brief     STM32F40xxx/41xxx Devices vector table for RIDE7 toolchain.
+  *            Same as startup_stm32f40xx.s and maintained for legacy purpose             
+  *            This module performs:
+  *                - Set the initial SP
+  *                - Set the initial PC == Reset_Handler,
+  *                - Set the vector table entries with the exceptions ISR address
+  *                - Configure the clock system and the external SRAM mounted on 
+  *                  STM324xG-EVAL board to be used as data memory (optional, 
+  *                  to be enabled by user)
+  *                - Branches to main in the C library (which eventually
+  *                  calls main()).
+  *            After Reset the Cortex-M4 processor is in Thread mode,
+  *            priority is Privileged, and the Stack is set to Main.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+    
+  .syntax unified
+  .cpu cortex-m3
+  .fpu softvfp
+  .thumb
+
+.global  g_pfnVectors
+.global  Default_Handler
+
+/* start address for the initialization values of the .data section. 
+defined in linker script */
+.word  _sidata
+/* start address for the .data section. defined in linker script */  
+.word  _sdata
+/* end address for the .data section. defined in linker script */
+.word  _edata
+/* start address for the .bss section. defined in linker script */
+.word  _sbss
+/* end address for the .bss section. defined in linker script */
+.word  _ebss
+/* stack used for SystemInit_ExtMemCtl; always internal RAM used */
+
+/**
+ * @brief  This is the code that gets called when the processor first
+ *          starts execution following a reset event. Only the absolutely
+ *          necessary set is performed, after which the application
+ *          supplied main() routine is called. 
+ * @param  None
+ * @retval : None
+*/
+
+    .section  .text.Reset_Handler
+  .weak  Reset_Handler
+  .type  Reset_Handler, %function
+Reset_Handler:  
+
+/* Copy the data segment initializers from flash to SRAM */  
+  movs  r1, #0
+  b  LoopCopyDataInit
+
+CopyDataInit:
+  ldr  r3, =_sidata
+  ldr  r3, [r3, r1]
+  str  r3, [r0, r1]
+  adds  r1, r1, #4
+    
+LoopCopyDataInit:
+  ldr  r0, =_sdata
+  ldr  r3, =_edata
+  adds  r2, r0, r1
+  cmp  r2, r3
+  bcc  CopyDataInit
+  ldr  r2, =_sbss
+  b  LoopFillZerobss
+/* Zero fill the bss segment. */  
+FillZerobss:
+  movs  r3, #0
+  str  r3, [r2], #4
+    
+LoopFillZerobss:
+  ldr  r3, = _ebss
+  cmp  r2, r3
+  bcc  FillZerobss
+
+/* Call the clock system intitialization function.*/
+  bl  SystemInit   
+/* Call the application's entry point.*/
+  bl  main
+  bx  lr    
+.size  Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief  This is the code that gets called when the processor receives an 
+ *         unexpected interrupt.  This simply enters an infinite loop, preserving
+ *         the system state for examination by a debugger.
+ * @param  None     
+ * @retval None       
+*/
+    .section  .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+  b  Infinite_Loop
+  .size  Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M3. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+* 
+*******************************************************************************/
+   .section  .isr_vector,"a",%progbits
+  .type  g_pfnVectors, %object
+  .size  g_pfnVectors, .-g_pfnVectors
+    
+    
+g_pfnVectors:
+  .word  _estack
+  .word  Reset_Handler
+  .word  NMI_Handler
+  .word  HardFault_Handler
+  .word  MemManage_Handler
+  .word  BusFault_Handler
+  .word  UsageFault_Handler
+  .word  0
+  .word  0
+  .word  0
+  .word  0
+  .word  SVC_Handler
+  .word  DebugMon_Handler
+  .word  0
+  .word  PendSV_Handler
+  .word  SysTick_Handler
+  
+  /* External Interrupts */
+  .word     WWDG_IRQHandler                   /* Window WatchDog              */                                        
+  .word     PVD_IRQHandler                    /* PVD through EXTI Line detection */                        
+  .word     TAMP_STAMP_IRQHandler             /* Tamper and TimeStamps through the EXTI line */            
+  .word     RTC_WKUP_IRQHandler               /* RTC Wakeup through the EXTI line */                      
+  .word     FLASH_IRQHandler                  /* FLASH                        */                                          
+  .word     RCC_IRQHandler                    /* RCC                          */                                            
+  .word     EXTI0_IRQHandler                  /* EXTI Line0                   */                        
+  .word     EXTI1_IRQHandler                  /* EXTI Line1                   */                          
+  .word     EXTI2_IRQHandler                  /* EXTI Line2                   */                          
+  .word     EXTI3_IRQHandler                  /* EXTI Line3                   */                          
+  .word     EXTI4_IRQHandler                  /* EXTI Line4                   */                          
+  .word     DMA1_Stream0_IRQHandler           /* DMA1 Stream 0                */                  
+  .word     DMA1_Stream1_IRQHandler           /* DMA1 Stream 1                */                   
+  .word     DMA1_Stream2_IRQHandler           /* DMA1 Stream 2                */                   
+  .word     DMA1_Stream3_IRQHandler           /* DMA1 Stream 3                */                   
+  .word     DMA1_Stream4_IRQHandler           /* DMA1 Stream 4                */                   
+  .word     DMA1_Stream5_IRQHandler           /* DMA1 Stream 5                */                   
+  .word     DMA1_Stream6_IRQHandler           /* DMA1 Stream 6                */                   
+  .word     ADC_IRQHandler                    /* ADC1, ADC2 and ADC3s         */                   
+  .word     CAN1_TX_IRQHandler                /* CAN1 TX                      */                         
+  .word     CAN1_RX0_IRQHandler               /* CAN1 RX0                     */                          
+  .word     CAN1_RX1_IRQHandler               /* CAN1 RX1                     */                          
+  .word     CAN1_SCE_IRQHandler               /* CAN1 SCE                     */                          
+  .word     EXTI9_5_IRQHandler                /* External Line[9:5]s          */                          
+  .word     TIM1_BRK_TIM9_IRQHandler          /* TIM1 Break and TIM9          */         
+  .word     TIM1_UP_TIM10_IRQHandler          /* TIM1 Update and TIM10        */         
+  .word     TIM1_TRG_COM_TIM11_IRQHandler     /* TIM1 Trigger and Commutation and TIM11 */
+  .word     TIM1_CC_IRQHandler                /* TIM1 Capture Compare         */                          
+  .word     TIM2_IRQHandler                   /* TIM2                         */                   
+  .word     TIM3_IRQHandler                   /* TIM3                         */                   
+  .word     TIM4_IRQHandler                   /* TIM4                         */                   
+  .word     I2C1_EV_IRQHandler                /* I2C1 Event                   */                          
+  .word     I2C1_ER_IRQHandler                /* I2C1 Error                   */                          
+  .word     I2C2_EV_IRQHandler                /* I2C2 Event                   */                          
+  .word     I2C2_ER_IRQHandler                /* I2C2 Error                   */                            
+  .word     SPI1_IRQHandler                   /* SPI1                         */                   
+  .word     SPI2_IRQHandler                   /* SPI2                         */                   
+  .word     USART1_IRQHandler                 /* USART1                       */                   
+  .word     USART2_IRQHandler                 /* USART2                       */                   
+  .word     USART3_IRQHandler                 /* USART3                       */                   
+  .word     EXTI15_10_IRQHandler              /* External Line[15:10]s        */                          
+  .word     RTC_Alarm_IRQHandler              /* RTC Alarm (A and B) through EXTI Line */                 
+  .word     OTG_FS_WKUP_IRQHandler            /* USB OTG FS Wakeup through EXTI line */                       
+  .word     TIM8_BRK_TIM12_IRQHandler         /* TIM8 Break and TIM12         */         
+  .word     TIM8_UP_TIM13_IRQHandler          /* TIM8 Update and TIM13        */         
+  .word     TIM8_TRG_COM_TIM14_IRQHandler     /* TIM8 Trigger and Commutation and TIM14 */
+  .word     TIM8_CC_IRQHandler                /* TIM8 Capture Compare         */                          
+  .word     DMA1_Stream7_IRQHandler           /* DMA1 Stream7                 */                          
+  .word     FSMC_IRQHandler                   /* FSMC                         */                   
+  .word     SDIO_IRQHandler                   /* SDIO                         */                   
+  .word     TIM5_IRQHandler                   /* TIM5                         */                   
+  .word     SPI3_IRQHandler                   /* SPI3                         */                   
+  .word     UART4_IRQHandler                  /* UART4                        */                   
+  .word     UART5_IRQHandler                  /* UART5                        */                   
+  .word     TIM6_DAC_IRQHandler               /* TIM6 and DAC1&2 underrun errors */                   
+  .word     TIM7_IRQHandler                   /* TIM7                         */
+  .word     DMA2_Stream0_IRQHandler           /* DMA2 Stream 0                */                   
+  .word     DMA2_Stream1_IRQHandler           /* DMA2 Stream 1                */                   
+  .word     DMA2_Stream2_IRQHandler           /* DMA2 Stream 2                */                   
+  .word     DMA2_Stream3_IRQHandler           /* DMA2 Stream 3                */                   
+  .word     DMA2_Stream4_IRQHandler           /* DMA2 Stream 4                */                   
+  .word     ETH_IRQHandler                    /* Ethernet                     */                   
+  .word     ETH_WKUP_IRQHandler               /* Ethernet Wakeup through EXTI line */                     
+  .word     CAN2_TX_IRQHandler                /* CAN2 TX                      */                          
+  .word     CAN2_RX0_IRQHandler               /* CAN2 RX0                     */                          
+  .word     CAN2_RX1_IRQHandler               /* CAN2 RX1                     */                          
+  .word     CAN2_SCE_IRQHandler               /* CAN2 SCE                     */                          
+  .word     OTG_FS_IRQHandler                 /* USB OTG FS                   */                   
+  .word     DMA2_Stream5_IRQHandler           /* DMA2 Stream 5                */                   
+  .word     DMA2_Stream6_IRQHandler           /* DMA2 Stream 6                */                   
+  .word     DMA2_Stream7_IRQHandler           /* DMA2 Stream 7                */                   
+  .word     USART6_IRQHandler                 /* USART6                       */                    
+  .word     I2C3_EV_IRQHandler                /* I2C3 event                   */                          
+  .word     I2C3_ER_IRQHandler                /* I2C3 error                   */                          
+  .word     OTG_HS_EP1_OUT_IRQHandler         /* USB OTG HS End Point 1 Out   */                   
+  .word     OTG_HS_EP1_IN_IRQHandler          /* USB OTG HS End Point 1 In    */                   
+  .word     OTG_HS_WKUP_IRQHandler            /* USB OTG HS Wakeup through EXTI */                         
+  .word     OTG_HS_IRQHandler                 /* USB OTG HS                   */                   
+  .word     DCMI_IRQHandler                   /* DCMI                         */                   
+  .word     CRYP_IRQHandler                   /* CRYP crypto                  */                   
+  .word     HASH_RNG_IRQHandler               /* Hash and Rng                 */
+  .word     FPU_IRQHandler                    /* FPU                          */                         
+                            
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler. 
+* As they are weak aliases, any function with the same name will override 
+* this definition.
+* 
+*******************************************************************************/
+   .weak      NMI_Handler
+   .thumb_set NMI_Handler,Default_Handler
+  
+   .weak      HardFault_Handler
+   .thumb_set HardFault_Handler,Default_Handler
+  
+   .weak      MemManage_Handler
+   .thumb_set MemManage_Handler,Default_Handler
+  
+   .weak      BusFault_Handler
+   .thumb_set BusFault_Handler,Default_Handler
+
+   .weak      UsageFault_Handler
+   .thumb_set UsageFault_Handler,Default_Handler
+
+   .weak      SVC_Handler
+   .thumb_set SVC_Handler,Default_Handler
+
+   .weak      DebugMon_Handler
+   .thumb_set DebugMon_Handler,Default_Handler
+
+   .weak      PendSV_Handler
+   .thumb_set PendSV_Handler,Default_Handler
+
+   .weak      SysTick_Handler
+   .thumb_set SysTick_Handler,Default_Handler              
+  
+   .weak      WWDG_IRQHandler                   
+   .thumb_set WWDG_IRQHandler,Default_Handler      
+                  
+   .weak      PVD_IRQHandler      
+   .thumb_set PVD_IRQHandler,Default_Handler
+               
+   .weak      TAMP_STAMP_IRQHandler            
+   .thumb_set TAMP_STAMP_IRQHandler,Default_Handler
+            
+   .weak      RTC_WKUP_IRQHandler                  
+   .thumb_set RTC_WKUP_IRQHandler,Default_Handler
+            
+   .weak      FLASH_IRQHandler         
+   .thumb_set FLASH_IRQHandler,Default_Handler
+                  
+   .weak      RCC_IRQHandler      
+   .thumb_set RCC_IRQHandler,Default_Handler
+                  
+   .weak      EXTI0_IRQHandler         
+   .thumb_set EXTI0_IRQHandler,Default_Handler
+                  
+   .weak      EXTI1_IRQHandler         
+   .thumb_set EXTI1_IRQHandler,Default_Handler
+                     
+   .weak      EXTI2_IRQHandler         
+   .thumb_set EXTI2_IRQHandler,Default_Handler 
+                 
+   .weak      EXTI3_IRQHandler         
+   .thumb_set EXTI3_IRQHandler,Default_Handler
+                        
+   .weak      EXTI4_IRQHandler         
+   .thumb_set EXTI4_IRQHandler,Default_Handler
+                  
+   .weak      DMA1_Stream0_IRQHandler               
+   .thumb_set DMA1_Stream0_IRQHandler,Default_Handler
+         
+   .weak      DMA1_Stream1_IRQHandler               
+   .thumb_set DMA1_Stream1_IRQHandler,Default_Handler
+                  
+   .weak      DMA1_Stream2_IRQHandler               
+   .thumb_set DMA1_Stream2_IRQHandler,Default_Handler
+                  
+   .weak      DMA1_Stream3_IRQHandler               
+   .thumb_set DMA1_Stream3_IRQHandler,Default_Handler 
+                 
+   .weak      DMA1_Stream4_IRQHandler              
+   .thumb_set DMA1_Stream4_IRQHandler,Default_Handler
+                  
+   .weak      DMA1_Stream5_IRQHandler               
+   .thumb_set DMA1_Stream5_IRQHandler,Default_Handler
+                  
+   .weak      DMA1_Stream6_IRQHandler               
+   .thumb_set DMA1_Stream6_IRQHandler,Default_Handler
+                  
+   .weak      ADC_IRQHandler      
+   .thumb_set ADC_IRQHandler,Default_Handler
+               
+   .weak      CAN1_TX_IRQHandler   
+   .thumb_set CAN1_TX_IRQHandler,Default_Handler
+            
+   .weak      CAN1_RX0_IRQHandler                  
+   .thumb_set CAN1_RX0_IRQHandler,Default_Handler
+                           
+   .weak      CAN1_RX1_IRQHandler                  
+   .thumb_set CAN1_RX1_IRQHandler,Default_Handler
+            
+   .weak      CAN1_SCE_IRQHandler                  
+   .thumb_set CAN1_SCE_IRQHandler,Default_Handler
+            
+   .weak      EXTI9_5_IRQHandler   
+   .thumb_set EXTI9_5_IRQHandler,Default_Handler
+            
+   .weak      TIM1_BRK_TIM9_IRQHandler            
+   .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler
+            
+   .weak      TIM1_UP_TIM10_IRQHandler            
+   .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler
+      
+   .weak      TIM1_TRG_COM_TIM11_IRQHandler      
+   .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler
+      
+   .weak      TIM1_CC_IRQHandler   
+   .thumb_set TIM1_CC_IRQHandler,Default_Handler
+                  
+   .weak      TIM2_IRQHandler            
+   .thumb_set TIM2_IRQHandler,Default_Handler
+                  
+   .weak      TIM3_IRQHandler            
+   .thumb_set TIM3_IRQHandler,Default_Handler
+                  
+   .weak      TIM4_IRQHandler            
+   .thumb_set TIM4_IRQHandler,Default_Handler
+                  
+   .weak      I2C1_EV_IRQHandler   
+   .thumb_set I2C1_EV_IRQHandler,Default_Handler
+                     
+   .weak      I2C1_ER_IRQHandler   
+   .thumb_set I2C1_ER_IRQHandler,Default_Handler
+                     
+   .weak      I2C2_EV_IRQHandler   
+   .thumb_set I2C2_EV_IRQHandler,Default_Handler
+                  
+   .weak      I2C2_ER_IRQHandler   
+   .thumb_set I2C2_ER_IRQHandler,Default_Handler
+                           
+   .weak      SPI1_IRQHandler            
+   .thumb_set SPI1_IRQHandler,Default_Handler
+                        
+   .weak      SPI2_IRQHandler            
+   .thumb_set SPI2_IRQHandler,Default_Handler
+                  
+   .weak      USART1_IRQHandler      
+   .thumb_set USART1_IRQHandler,Default_Handler
+                     
+   .weak      USART2_IRQHandler      
+   .thumb_set USART2_IRQHandler,Default_Handler
+                     
+   .weak      USART3_IRQHandler      
+   .thumb_set USART3_IRQHandler,Default_Handler
+                  
+   .weak      EXTI15_10_IRQHandler               
+   .thumb_set EXTI15_10_IRQHandler,Default_Handler
+               
+   .weak      RTC_Alarm_IRQHandler               
+   .thumb_set RTC_Alarm_IRQHandler,Default_Handler
+            
+   .weak      OTG_FS_WKUP_IRQHandler         
+   .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
+            
+   .weak      TIM8_BRK_TIM12_IRQHandler         
+   .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler
+         
+   .weak      TIM8_UP_TIM13_IRQHandler            
+   .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler
+         
+   .weak      TIM8_TRG_COM_TIM14_IRQHandler      
+   .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler
+      
+   .weak      TIM8_CC_IRQHandler   
+   .thumb_set TIM8_CC_IRQHandler,Default_Handler
+                  
+   .weak      DMA1_Stream7_IRQHandler               
+   .thumb_set DMA1_Stream7_IRQHandler,Default_Handler
+                     
+   .weak      FSMC_IRQHandler            
+   .thumb_set FSMC_IRQHandler,Default_Handler
+                     
+   .weak      SDIO_IRQHandler            
+   .thumb_set SDIO_IRQHandler,Default_Handler
+                     
+   .weak      TIM5_IRQHandler            
+   .thumb_set TIM5_IRQHandler,Default_Handler
+                     
+   .weak      SPI3_IRQHandler            
+   .thumb_set SPI3_IRQHandler,Default_Handler
+                     
+   .weak      UART4_IRQHandler         
+   .thumb_set UART4_IRQHandler,Default_Handler
+                  
+   .weak      UART5_IRQHandler         
+   .thumb_set UART5_IRQHandler,Default_Handler
+                  
+   .weak      TIM6_DAC_IRQHandler                  
+   .thumb_set TIM6_DAC_IRQHandler,Default_Handler
+               
+   .weak      TIM7_IRQHandler            
+   .thumb_set TIM7_IRQHandler,Default_Handler
+         
+   .weak      DMA2_Stream0_IRQHandler               
+   .thumb_set DMA2_Stream0_IRQHandler,Default_Handler
+               
+   .weak      DMA2_Stream1_IRQHandler               
+   .thumb_set DMA2_Stream1_IRQHandler,Default_Handler
+                  
+   .weak      DMA2_Stream2_IRQHandler               
+   .thumb_set DMA2_Stream2_IRQHandler,Default_Handler
+            
+   .weak      DMA2_Stream3_IRQHandler               
+   .thumb_set DMA2_Stream3_IRQHandler,Default_Handler
+            
+   .weak      DMA2_Stream4_IRQHandler               
+   .thumb_set DMA2_Stream4_IRQHandler,Default_Handler
+            
+   .weak      ETH_IRQHandler      
+   .thumb_set ETH_IRQHandler,Default_Handler
+                  
+   .weak      ETH_WKUP_IRQHandler                  
+   .thumb_set ETH_WKUP_IRQHandler,Default_Handler
+            
+   .weak      CAN2_TX_IRQHandler   
+   .thumb_set CAN2_TX_IRQHandler,Default_Handler
+                           
+   .weak      CAN2_RX0_IRQHandler                  
+   .thumb_set CAN2_RX0_IRQHandler,Default_Handler
+                           
+   .weak      CAN2_RX1_IRQHandler                  
+   .thumb_set CAN2_RX1_IRQHandler,Default_Handler
+                           
+   .weak      CAN2_SCE_IRQHandler                  
+   .thumb_set CAN2_SCE_IRQHandler,Default_Handler
+                           
+   .weak      OTG_FS_IRQHandler      
+   .thumb_set OTG_FS_IRQHandler,Default_Handler
+                     
+   .weak      DMA2_Stream5_IRQHandler               
+   .thumb_set DMA2_Stream5_IRQHandler,Default_Handler
+                  
+   .weak      DMA2_Stream6_IRQHandler               
+   .thumb_set DMA2_Stream6_IRQHandler,Default_Handler
+                  
+   .weak      DMA2_Stream7_IRQHandler               
+   .thumb_set DMA2_Stream7_IRQHandler,Default_Handler
+                  
+   .weak      USART6_IRQHandler      
+   .thumb_set USART6_IRQHandler,Default_Handler
+                        
+   .weak      I2C3_EV_IRQHandler   
+   .thumb_set I2C3_EV_IRQHandler,Default_Handler
+                        
+   .weak      I2C3_ER_IRQHandler   
+   .thumb_set I2C3_ER_IRQHandler,Default_Handler
+                        
+   .weak      OTG_HS_EP1_OUT_IRQHandler         
+   .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler
+               
+   .weak      OTG_HS_EP1_IN_IRQHandler            
+   .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler
+               
+   .weak      OTG_HS_WKUP_IRQHandler         
+   .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler
+            
+   .weak      OTG_HS_IRQHandler      
+   .thumb_set OTG_HS_IRQHandler,Default_Handler
+                  
+   .weak      DCMI_IRQHandler            
+   .thumb_set DCMI_IRQHandler,Default_Handler
+                     
+   .weak      CRYP_IRQHandler            
+   .thumb_set CRYP_IRQHandler,Default_Handler
+               
+   .weak      HASH_RNG_IRQHandler                  
+   .thumb_set HASH_RNG_IRQHandler,Default_Handler   
+
+   .weak      FPU_IRQHandler                  
+   .thumb_set FPU_IRQHandler,Default_Handler 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Source/system_stm32f4xx.c b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Source/system_stm32f4xx.c
new file mode 100644
index 0000000000000000000000000000000000000000..4498f53c18f58f26c208a195335b6fa05ee915e6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/CMSIS/STM32F4xx/Source/system_stm32f4xx.c
@@ -0,0 +1,922 @@
+/**
+  ******************************************************************************
+  * @file    system_stm32f4xx.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
+  *          This file contains the system clock configuration for STM32F4xx devices.
+  *             
+  * 1.  This file provides two functions and one global variable to be called from 
+  *     user application:
+  *      - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+  *                      and Divider factors, AHB/APBx prescalers and Flash settings),
+  *                      depending on the configuration made in the clock xls tool. 
+  *                      This function is called at startup just after reset and 
+  *                      before branch to main program. This call is made inside
+  *                      the "startup_stm32f4xx.s" file.
+  *
+  *      - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+  *                                  by the user application to setup the SysTick 
+  *                                  timer or configure other parameters.
+  *                                     
+  *      - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+  *                                 be called whenever the core clock is changed
+  *                                 during program execution.
+  *
+  * 2. After each device reset the HSI (16 MHz) is used as system clock source.
+  *    Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
+  *    configure the system clock before to branch to main program.
+  *
+  * 3. If the system clock source selected by user fails to startup, the SystemInit()
+  *    function will do nothing and HSI still used as system clock source. User can 
+  *    add some code to deal with this issue inside the SetSysClock() function.
+  *
+  * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
+  *    in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
+  *    through PLL, and you are using different crystal you have to adapt the HSE
+  *    value to your own configuration.
+  *
+  * 5. This file configures the system clock as follows:
+  *=============================================================================
+  *=============================================================================
+  *                    Supported STM32F40xxx/41xxx devices
+  *-----------------------------------------------------------------------------
+  *        System Clock source                    | PLL (HSE)
+  *-----------------------------------------------------------------------------
+  *        SYSCLK(Hz)                             | 168000000
+  *-----------------------------------------------------------------------------
+  *        HCLK(Hz)                               | 168000000
+  *-----------------------------------------------------------------------------
+  *        AHB Prescaler                          | 1
+  *-----------------------------------------------------------------------------
+  *        APB1 Prescaler                         | 4
+  *-----------------------------------------------------------------------------
+  *        APB2 Prescaler                         | 2
+  *-----------------------------------------------------------------------------
+  *        HSE Frequency(Hz)                      | 25000000
+  *-----------------------------------------------------------------------------
+  *        PLL_M                                  | 25
+  *-----------------------------------------------------------------------------
+  *        PLL_N                                  | 336
+  *-----------------------------------------------------------------------------
+  *        PLL_P                                  | 2
+  *-----------------------------------------------------------------------------
+  *        PLL_Q                                  | 7
+  *-----------------------------------------------------------------------------
+  *        PLLI2S_N                               | NA
+  *-----------------------------------------------------------------------------
+  *        PLLI2S_R                               | NA
+  *-----------------------------------------------------------------------------
+  *        I2S input clock                        | NA
+  *-----------------------------------------------------------------------------
+  *        VDD(V)                                 | 3.3
+  *-----------------------------------------------------------------------------
+  *        Main regulator output voltage          | Scale1 mode
+  *-----------------------------------------------------------------------------
+  *        Flash Latency(WS)                      | 5
+  *-----------------------------------------------------------------------------
+  *        Prefetch Buffer                        | ON
+  *-----------------------------------------------------------------------------
+  *        Instruction cache                      | ON
+  *-----------------------------------------------------------------------------
+  *        Data cache                             | ON
+  *-----------------------------------------------------------------------------
+  *        Require 48MHz for USB OTG FS,          | Disabled
+  *        SDIO and RNG clock                     |
+  *-----------------------------------------------------------------------------
+  *=============================================================================
+  *=============================================================================
+  *                    Supported STM32F42xxx/43xxx devices
+  *-----------------------------------------------------------------------------
+  *        System Clock source                    | PLL (HSE)
+  *-----------------------------------------------------------------------------
+  *        SYSCLK(Hz)                             | 180000000
+  *-----------------------------------------------------------------------------
+  *        HCLK(Hz)                               | 180000000
+  *-----------------------------------------------------------------------------
+  *        AHB Prescaler                          | 1
+  *-----------------------------------------------------------------------------
+  *        APB1 Prescaler                         | 4
+  *-----------------------------------------------------------------------------
+  *        APB2 Prescaler                         | 2
+  *-----------------------------------------------------------------------------
+  *        HSE Frequency(Hz)                      | 25000000
+  *-----------------------------------------------------------------------------
+  *        PLL_M                                  | 25
+  *-----------------------------------------------------------------------------
+  *        PLL_N                                  | 360
+  *-----------------------------------------------------------------------------
+  *        PLL_P                                  | 2
+  *-----------------------------------------------------------------------------
+  *        PLL_Q                                  | 7
+  *-----------------------------------------------------------------------------
+  *        PLLI2S_N                               | NA
+  *-----------------------------------------------------------------------------
+  *        PLLI2S_R                               | NA
+  *-----------------------------------------------------------------------------
+  *        I2S input clock                        | NA
+  *-----------------------------------------------------------------------------
+  *        VDD(V)                                 | 3.3
+  *-----------------------------------------------------------------------------
+  *        Main regulator output voltage          | Scale1 mode
+  *-----------------------------------------------------------------------------
+  *        Flash Latency(WS)                      | 5
+  *-----------------------------------------------------------------------------
+  *        Prefetch Buffer                        | ON
+  *-----------------------------------------------------------------------------
+  *        Instruction cache                      | ON
+  *-----------------------------------------------------------------------------
+  *        Data cache                             | ON
+  *-----------------------------------------------------------------------------
+  *        Require 48MHz for USB OTG FS,          | Disabled
+  *        SDIO and RNG clock                     |
+  *-----------------------------------------------------------------------------
+  *=============================================================================
+  *=============================================================================
+  *                         Supported STM32F401xx devices
+  *-----------------------------------------------------------------------------
+  *        System Clock source                    | PLL (HSE)
+  *-----------------------------------------------------------------------------
+  *        SYSCLK(Hz)                             | 84000000
+  *-----------------------------------------------------------------------------
+  *        HCLK(Hz)                               | 84000000
+  *-----------------------------------------------------------------------------
+  *        AHB Prescaler                          | 1
+  *-----------------------------------------------------------------------------
+  *        APB1 Prescaler                         | 2
+  *-----------------------------------------------------------------------------
+  *        APB2 Prescaler                         | 1
+  *-----------------------------------------------------------------------------
+  *        HSE Frequency(Hz)                      | 25000000
+  *-----------------------------------------------------------------------------
+  *        PLL_M                                  | 25
+  *-----------------------------------------------------------------------------
+  *        PLL_N                                  | 336
+  *-----------------------------------------------------------------------------
+  *        PLL_P                                  | 4
+  *-----------------------------------------------------------------------------
+  *        PLL_Q                                  | 7
+  *-----------------------------------------------------------------------------
+  *        PLLI2S_N                               | NA
+  *-----------------------------------------------------------------------------
+  *        PLLI2S_R                               | NA
+  *-----------------------------------------------------------------------------
+  *        I2S input clock                        | NA
+  *-----------------------------------------------------------------------------
+  *        VDD(V)                                 | 3.3
+  *-----------------------------------------------------------------------------
+  *        Main regulator output voltage          | Scale1 mode
+  *-----------------------------------------------------------------------------
+  *        Flash Latency(WS)                      | 2
+  *-----------------------------------------------------------------------------
+  *        Prefetch Buffer                        | ON
+  *-----------------------------------------------------------------------------
+  *        Instruction cache                      | ON
+  *-----------------------------------------------------------------------------
+  *        Data cache                             | ON
+  *-----------------------------------------------------------------------------
+  *        Require 48MHz for USB OTG FS,          | Disabled
+  *        SDIO and RNG clock                     |
+  *-----------------------------------------------------------------------------
+  *=============================================================================      
+  ****************************************************************************** 
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/** @addtogroup CMSIS
+  * @{
+  */
+
+/** @addtogroup stm32f4xx_system
+  * @{
+  */  
+  
+/** @addtogroup STM32F4xx_System_Private_Includes
+  * @{
+  */
+
+#include "stm32f4xx.h"
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Private_Defines
+  * @{
+  */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
+     on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory  */
+     
+#if defined (STM32F40_41xxx) || defined (STM32F427_437xx) || defined (STM32F429_439xx)
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+/* #define DATA_IN_ExtSDRAM */
+#endif /* STM32F427_437x || STM32F429_439xx */ 
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+     Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET  0x00 /*!< Vector Table base offset field. 
+                                   This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/************************* PLL Parameters *************************************/
+/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
+#define PLL_M      8
+/* USB OTG FS, SDIO and RNG Clock =  PLL_VCO / PLLQ */
+#define PLL_Q      7
+
+#if defined (STM32F40_41xxx)
+#define PLL_N      336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P      2
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define PLL_N      360
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P      2
+#endif /* STM32F427_437x || STM32F429_439xx */
+
+#if defined (STM32F401xx)
+#define PLL_N      336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P      4
+#endif /* STM32F401xx */
+
+/******************************************************************************/
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Private_Variables
+  * @{
+  */
+
+#if defined (STM32F40_41xxx)
+  uint32_t SystemCoreClock = 168000000;
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+  uint32_t SystemCoreClock = 180000000;
+#endif /* STM32F427_437x || STM32F429_439xx */
+
+#if defined (STM32F401xx)
+  uint32_t SystemCoreClock = 84000000;
+#endif /* STM32F401xx */
+
+  __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
+  * @{
+  */
+
+static void SetSysClock(void);
+
+#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+static void SystemInit_ExtMemCtl(void); 
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F4xx_System_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Setup the microcontroller system
+  *         Initialize the Embedded Flash Interface, the PLL and update the 
+  *         SystemFrequency variable.
+  * @param  None
+  * @retval None
+  */
+void SystemInit(void)
+{
+  /* FPU settings ------------------------------------------------------------*/
+  #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+    SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2));  /* set CP10 and CP11 Full Access */
+  #endif
+  /* Reset the RCC clock configuration to the default reset state ------------*/
+  /* Set HSION bit */
+  RCC->CR |= (uint32_t)0x00000001;
+
+  /* Reset CFGR register */
+  RCC->CFGR = 0x00000000;
+
+  /* Reset HSEON, CSSON and PLLON bits */
+  RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+  /* Reset PLLCFGR register */
+  RCC->PLLCFGR = 0x24003010;
+
+  /* Reset HSEBYP bit */
+  RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+  /* Disable all interrupts */
+  RCC->CIR = 0x00000000;
+
+#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+  SystemInit_ExtMemCtl(); 
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+         
+  /* Configure the System clock source, PLL Multiplier and Divider factors, 
+     AHB/APBx prescalers and Flash settings ----------------------------------*/
+  SetSysClock();
+}
+
+/**
+   * @brief  Update SystemCoreClock variable according to Clock Register Values.
+  *         The SystemCoreClock variable contains the core clock (HCLK), it can
+  *         be used by the user application to setup the SysTick timer or configure
+  *         other parameters.
+  *           
+  * @note   Each time the core clock (HCLK) changes, this function must be called
+  *         to update SystemCoreClock variable value. Otherwise, any configuration
+  *         based on this variable will be incorrect.         
+  *     
+  * @note   - The system frequency computed by this function is not the real 
+  *           frequency in the chip. It is calculated based on the predefined 
+  *           constant and the selected clock source:
+  *             
+  *           - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+  *                                              
+  *           - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+  *                          
+  *           - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) 
+  *             or HSI_VALUE(*) multiplied/divided by the PLL factors.
+  *         
+  *         (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
+  *             16 MHz) but the real value may vary depending on the variations
+  *             in voltage and temperature.   
+  *    
+  *         (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
+  *              25 MHz), user has to ensure that HSE_VALUE is same as the real
+  *              frequency of the crystal used. Otherwise, this function may
+  *              have wrong result.
+  *                
+  *         - The result of this function could be not correct when using fractional
+  *           value for HSE crystal.
+  *     
+  * @param  None
+  * @retval None
+  */
+void SystemCoreClockUpdate(void)
+{
+  uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+  
+  /* Get SYSCLK source -------------------------------------------------------*/
+  tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+  switch (tmp)
+  {
+    case 0x00:  /* HSI used as system clock source */
+      SystemCoreClock = HSI_VALUE;
+      break;
+    case 0x04:  /* HSE used as system clock source */
+      SystemCoreClock = HSE_VALUE;
+      break;
+    case 0x08:  /* PLL used as system clock source */
+
+      /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+         SYSCLK = PLL_VCO / PLL_P
+         */    
+      pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+      pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+      
+      if (pllsource != 0)
+      {
+        /* HSE used as PLL clock source */
+        pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+      }
+      else
+      {
+        /* HSI used as PLL clock source */
+        pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);      
+      }
+
+      pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+      SystemCoreClock = pllvco/pllp;
+      break;
+    default:
+      SystemCoreClock = HSI_VALUE;
+      break;
+  }
+  /* Compute HCLK frequency --------------------------------------------------*/
+  /* Get HCLK prescaler */
+  tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+  /* HCLK frequency */
+  SystemCoreClock >>= tmp;
+}
+
+/**
+  * @brief  Configures the System clock source, PLL Multiplier and Divider factors, 
+  *         AHB/APBx prescalers and Flash settings
+  * @Note   This function should be called only once the RCC clock configuration  
+  *         is reset to the default reset state (done in SystemInit() function).   
+  * @param  None
+  * @retval None
+  */
+static void SetSysClock(void)
+{
+/******************************************************************************/
+/*            PLL (clocked by HSE) used as System clock source                */
+/******************************************************************************/
+  __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+  
+  /* Enable HSE */
+  RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+ 
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC->CR & RCC_CR_HSERDY;
+    StartUpCounter++;
+  } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+  if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+  {
+    HSEStatus = (uint32_t)0x01;
+  }
+  else
+  {
+    HSEStatus = (uint32_t)0x00;
+  }
+
+  if (HSEStatus == (uint32_t)0x01)
+  {
+    /* Select regulator voltage output Scale 1 mode */
+    RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+    PWR->CR |= PWR_CR_VOS;
+
+    /* HCLK = SYSCLK / 1*/
+    RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+#if defined (STM32F40_41xxx) || defined (STM32F427_437xx) || defined (STM32F429_439xx)      
+    /* PCLK2 = HCLK / 2*/
+    RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
+    
+    /* PCLK1 = HCLK / 4*/
+    RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx */
+
+#if defined (STM32F401xx)
+    /* PCLK2 = HCLK / 2*/
+    RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+    
+    /* PCLK1 = HCLK / 4*/
+    RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+#endif /* STM32F401xx */
+   
+    /* Configure the main PLL */
+    RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+                   (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+
+    /* Enable the main PLL */
+    RCC->CR |= RCC_CR_PLLON;
+
+    /* Wait till the main PLL is ready */
+    while((RCC->CR & RCC_CR_PLLRDY) == 0)
+    {
+    }
+   
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+    /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
+    PWR->CR |= PWR_CR_ODEN;
+    while((PWR->CSR & PWR_CSR_ODRDY) == 0)
+    {
+    }
+    PWR->CR |= PWR_CR_ODSWEN;
+    while((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
+    {
+    }      
+    /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+    FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F427_437x || STM32F429_439xx  */
+
+#if defined (STM32F40_41xxx)     
+    /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+    FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F40_41xxx  */
+
+#if defined (STM32F401xx)
+    /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+    FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+#endif /* STM32F401xx */
+
+    /* Select the main PLL as system clock source */
+    RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+    RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+    /* Wait till the main PLL is used as system clock source */
+    while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+    {
+    }
+  }
+  else
+  { /* If HSE fails to start-up, the application will have wrong clock
+         configuration. User can add here some code to deal with this error */
+  }
+
+}
+
+/**
+  * @brief  Setup the external memory controller. Called in startup_stm32f4xx.s 
+  *          before jump to __main
+  * @param  None
+  * @retval None
+  */ 
+#ifdef DATA_IN_ExtSRAM
+/**
+  * @brief  Setup the external memory controller.
+  *         Called in startup_stm32f4xx.s before jump to main.
+  *         This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
+  *         This SRAM will be used as program data memory (including heap and stack).
+  * @param  None
+  * @retval None
+  */
+void SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+--------------+
+ +                       SRAM pins assignment                               +
+ +-------------------+--------------------+------------------+--------------+
+ | PD0  <-> FMC_D2  | PE0  <-> FMC_NBL0 | PF0  <-> FMC_A0 | PG0 <-> FMC_A10 | 
+ | PD1  <-> FMC_D3  | PE1  <-> FMC_NBL1 | PF1  <-> FMC_A1 | PG1 <-> FMC_A11 | 
+ | PD4  <-> FMC_NOE | PE3  <-> FMC_A19  | PF2  <-> FMC_A2 | PG2 <-> FMC_A12 | 
+ | PD5  <-> FMC_NWE | PE4  <-> FMC_A20  | PF3  <-> FMC_A3 | PG3 <-> FMC_A13 | 
+ | PD8  <-> FMC_D13 | PE7  <-> FMC_D4   | PF4  <-> FMC_A4 | PG4 <-> FMC_A14 | 
+ | PD9  <-> FMC_D14 | PE8  <-> FMC_D5   | PF5  <-> FMC_A5 | PG5 <-> FMC_A15 | 
+ | PD10 <-> FMC_D15 | PE9  <-> FMC_D6   | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 | 
+ | PD11 <-> FMC_A16 | PE10 <-> FMC_D7   | PF13 <-> FMC_A7 |-----------------+
+ | PD12 <-> FMC_A17 | PE11 <-> FMC_D8   | PF14 <-> FMC_A8 | 
+ | PD13 <-> FMC_A18 | PE12 <-> FMC_D9   | PF15 <-> FMC_A9 | 
+ | PD14 <-> FMC_D0  | PE13 <-> FMC_D10  |-----------------+
+ | PD15 <-> FMC_D1  | PE14 <-> FMC_D11  |
+ |                  | PE15 <-> FMC_D12  |
+ +------------------+------------------+
+*/
+   /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+  RCC->AHB1ENR   |= 0x00000078;
+  
+  /* Connect PDx pins to FMC Alternate function */
+  GPIOD->AFR[0]  = 0x00cc00cc;
+  GPIOD->AFR[1]  = 0xcccccccc;
+  /* Configure PDx pins in Alternate function mode */  
+  GPIOD->MODER   = 0xaaaa0a0a;
+  /* Configure PDx pins speed to 100 MHz */  
+  GPIOD->OSPEEDR = 0xffff0f0f;
+  /* Configure PDx pins Output type to push-pull */  
+  GPIOD->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PDx pins */ 
+  GPIOD->PUPDR   = 0x00000000;
+
+  /* Connect PEx pins to FMC Alternate function */
+  GPIOE->AFR[0]  = 0xcccccccc;
+  GPIOE->AFR[1]  = 0xcccccccc;
+  /* Configure PEx pins in Alternate function mode */ 
+  GPIOE->MODER   = 0xaaaaaaaa;
+  /* Configure PEx pins speed to 100 MHz */ 
+  GPIOE->OSPEEDR = 0xffffffff;
+  /* Configure PEx pins Output type to push-pull */  
+  GPIOE->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PEx pins */ 
+  GPIOE->PUPDR   = 0x00000000;
+
+  /* Connect PFx pins to FMC Alternate function */
+  GPIOF->AFR[0]  = 0x00cccccc;
+  GPIOF->AFR[1]  = 0xcccc0000;
+  /* Configure PFx pins in Alternate function mode */   
+  GPIOF->MODER   = 0xaa000aaa;
+  /* Configure PFx pins speed to 100 MHz */ 
+  GPIOF->OSPEEDR = 0xff000fff;
+  /* Configure PFx pins Output type to push-pull */  
+  GPIOF->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PFx pins */ 
+  GPIOF->PUPDR   = 0x00000000;
+
+  /* Connect PGx pins to FMC Alternate function */
+  GPIOG->AFR[0]  = 0x00cccccc;
+  GPIOG->AFR[1]  = 0x000000c0;
+  /* Configure PGx pins in Alternate function mode */ 
+  GPIOG->MODER   = 0x00080aaa;
+  /* Configure PGx pins speed to 100 MHz */ 
+  GPIOG->OSPEEDR = 0x000c0fff;
+  /* Configure PGx pins Output type to push-pull */  
+  GPIOG->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PGx pins */ 
+  GPIOG->PUPDR   = 0x00000000;
+  
+/*-- FMC Configuration ------------------------------------------------------*/
+  /* Enable the FMC/FSMC interface clock */
+  RCC->AHB3ENR         |= 0x00000001;
+  
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+  /* Configure and enable Bank1_SRAM2 */
+  FMC_Bank1->BTCR[2]  = 0x00001011;
+  FMC_Bank1->BTCR[3]  = 0x00000201;
+  FMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F427_437xx || STM32F429_439xx */ 
+
+#if defined (STM32F40_41xxx)
+  /* Configure and enable Bank1_SRAM2 */
+  FSMC_Bank1->BTCR[2]  = 0x00001011;
+  FSMC_Bank1->BTCR[3]  = 0x00000201;
+  FSMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif  /* STM32F40_41xxx */
+
+/*
+  Bank1_SRAM2 is configured as follow:
+  In case of FSMC configuration 
+  NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
+  NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
+  NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
+  NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
+  NORSRAMTimingStructure.FSMC_CLKDivision = 0;
+  NORSRAMTimingStructure.FSMC_DataLatency = 0;
+  NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
+
+  FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+  FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+  FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+  FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+  FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+  FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;  
+  FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+  FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+  FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+  FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+  FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+  FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+  FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+  FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+  FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
+
+  In case of FMC configuration   
+  NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
+  NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
+  NORSRAMTimingStructure.FMC_DataSetupTime = 2;
+  NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
+  NORSRAMTimingStructure.FMC_CLKDivision = 0;
+  NORSRAMTimingStructure.FMC_DataLatency = 0;
+  NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
+
+  FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
+  FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
+  FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
+  FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
+  FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
+  FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;  
+  FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
+  FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
+  FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
+  FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
+  FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
+  FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
+  FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
+  FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
+  FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+  FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
+*/
+  
+}
+#endif /* DATA_IN_ExtSRAM */
+  
+#ifdef DATA_IN_ExtSDRAM
+/**
+  * @brief  Setup the external memory controller.
+  *         Called in startup_stm32f4xx.s before jump to main.
+  *         This function configures the external SDRAM mounted on STM324x9I_EVAL board
+  *         This SDRAM will be used as program data memory (including heap and stack).
+  * @param  None
+  * @retval None
+  */
+void SystemInit_ExtMemCtl(void)
+{
+  register uint32_t tmpreg = 0, timeout = 0xFFFF;
+  register uint32_t index;
+
+  /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface 
+      clock */
+  RCC->AHB1ENR |= 0x000001FC;
+  
+  /* Connect PCx pins to FMC Alternate function */
+  GPIOC->AFR[0]  = 0x0000000c;
+  GPIOC->AFR[1]  = 0x00007700;
+  /* Configure PCx pins in Alternate function mode */  
+  GPIOC->MODER   = 0x00a00002;
+  /* Configure PCx pins speed to 50 MHz */  
+  GPIOC->OSPEEDR = 0x00a00002;
+  /* Configure PCx pins Output type to push-pull */  
+  GPIOC->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PCx pins */ 
+  GPIOC->PUPDR   = 0x00500000;
+  
+  /* Connect PDx pins to FMC Alternate function */
+  GPIOD->AFR[0]  = 0x000000CC;
+  GPIOD->AFR[1]  = 0xCC000CCC;
+  /* Configure PDx pins in Alternate function mode */  
+  GPIOD->MODER   = 0xA02A000A;
+  /* Configure PDx pins speed to 50 MHz */  
+  GPIOD->OSPEEDR = 0xA02A000A;
+  /* Configure PDx pins Output type to push-pull */  
+  GPIOD->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PDx pins */ 
+  GPIOD->PUPDR   = 0x00000000;
+
+  /* Connect PEx pins to FMC Alternate function */
+  GPIOE->AFR[0]  = 0xC00000CC;
+  GPIOE->AFR[1]  = 0xCCCCCCCC;
+  /* Configure PEx pins in Alternate function mode */ 
+  GPIOE->MODER   = 0xAAAA800A;
+  /* Configure PEx pins speed to 50 MHz */ 
+  GPIOE->OSPEEDR = 0xAAAA800A;
+  /* Configure PEx pins Output type to push-pull */  
+  GPIOE->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PEx pins */ 
+  GPIOE->PUPDR   = 0x00000000;
+
+  /* Connect PFx pins to FMC Alternate function */
+  GPIOF->AFR[0]  = 0xcccccccc;
+  GPIOF->AFR[1]  = 0xcccccccc;
+  /* Configure PFx pins in Alternate function mode */   
+  GPIOF->MODER   = 0xAA800AAA;
+  /* Configure PFx pins speed to 50 MHz */ 
+  GPIOF->OSPEEDR = 0xAA800AAA;
+  /* Configure PFx pins Output type to push-pull */  
+  GPIOF->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PFx pins */ 
+  GPIOF->PUPDR   = 0x00000000;
+
+  /* Connect PGx pins to FMC Alternate function */
+  GPIOG->AFR[0]  = 0xcccccccc;
+  GPIOG->AFR[1]  = 0xcccccccc;
+  /* Configure PGx pins in Alternate function mode */ 
+  GPIOG->MODER   = 0xaaaaaaaa;
+  /* Configure PGx pins speed to 50 MHz */ 
+  GPIOG->OSPEEDR = 0xaaaaaaaa;
+  /* Configure PGx pins Output type to push-pull */  
+  GPIOG->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PGx pins */ 
+  GPIOG->PUPDR   = 0x00000000;
+  
+  /* Connect PHx pins to FMC Alternate function */
+  GPIOH->AFR[0]  = 0x00C0CC00;
+  GPIOH->AFR[1]  = 0xCCCCCCCC;
+  /* Configure PHx pins in Alternate function mode */ 
+  GPIOH->MODER   = 0xAAAA08A0;
+  /* Configure PHx pins speed to 50 MHz */ 
+  GPIOH->OSPEEDR = 0xAAAA08A0;
+  /* Configure PHx pins Output type to push-pull */  
+  GPIOH->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PHx pins */ 
+  GPIOH->PUPDR   = 0x00000000;
+  
+  /* Connect PIx pins to FMC Alternate function */
+  GPIOI->AFR[0]  = 0xCCCCCCCC;
+  GPIOI->AFR[1]  = 0x00000CC0;
+  /* Configure PIx pins in Alternate function mode */ 
+  GPIOI->MODER   = 0x0028AAAA;
+  /* Configure PIx pins speed to 50 MHz */ 
+  GPIOI->OSPEEDR = 0x0028AAAA;
+  /* Configure PIx pins Output type to push-pull */  
+  GPIOI->OTYPER  = 0x00000000;
+  /* No pull-up, pull-down for PIx pins */ 
+  GPIOI->PUPDR   = 0x00000000;
+  
+/*-- FMC Configuration ------------------------------------------------------*/
+  /* Enable the FMC interface clock */
+  RCC->AHB3ENR |= 0x00000001;
+  
+  /* Configure and enable SDRAM bank1 */
+  FMC_Bank5_6->SDCR[0] = 0x000039D0;
+  FMC_Bank5_6->SDTR[0] = 0x01115351;      
+  
+  /* SDRAM initialization sequence */
+  /* Clock enable command */
+  FMC_Bank5_6->SDCMR = 0x00000011; 
+  tmpreg = FMC_Bank5_6->SDSR & 0x00000020; 
+  while((tmpreg != 0) & (timeout-- > 0))
+  {
+    tmpreg = FMC_Bank5_6->SDSR & 0x00000020; 
+  }
+  
+  /* Delay */
+  for (index = 0; index<1000; index++);
+  
+  /* PALL command */
+  FMC_Bank5_6->SDCMR = 0x00000012;           
+  timeout = 0xFFFF;
+  while((tmpreg != 0) & (timeout-- > 0))
+  {
+  tmpreg = FMC_Bank5_6->SDSR & 0x00000020; 
+  }
+  
+  /* Auto refresh command */
+  FMC_Bank5_6->SDCMR = 0x00000073;
+  timeout = 0xFFFF;
+  while((tmpreg != 0) & (timeout-- > 0))
+  {
+  tmpreg = FMC_Bank5_6->SDSR & 0x00000020; 
+  }
+ 
+  /* MRD register program */
+  FMC_Bank5_6->SDCMR = 0x00046014;
+  timeout = 0xFFFF;
+  while((tmpreg != 0) & (timeout-- > 0))
+  {
+  tmpreg = FMC_Bank5_6->SDSR & 0x00000020; 
+  } 
+  
+  /* Set refresh count */
+  tmpreg = FMC_Bank5_6->SDRTR;
+  FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
+  
+  /* Disable write protection */
+  tmpreg = FMC_Bank5_6->SDCR[0]; 
+  FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
+  
+/*
+  Bank1_SDRAM is configured as follow:
+
+  FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;      
+  FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;  
+  FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;        
+  FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;         
+  FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;      
+  FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;                
+  FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;               
+
+  FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
+  FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
+  FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
+  FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
+  FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
+  FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3; 
+  FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
+  FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
+  FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
+  FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
+  FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
+*/
+  
+}
+#endif /* DATA_IN_ExtSDRAM */
+
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+  
+/**
+  * @}
+  */    
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/FatFS/00history.txt b/crazyflie-firmware-src/src/lib/FatFS/00history.txt
new file mode 100644
index 0000000000000000000000000000000000000000..49aac282b2312104a756c14c98b62d895884f382
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/00history.txt
@@ -0,0 +1,279 @@
+----------------------------------------------------------------------------
+  Revision history of FatFs module
+----------------------------------------------------------------------------
+
+R0.00 (February 26, 2006)
+
+  Prototype.
+
+
+
+R0.01 (April 29, 2006)
+
+  The first release.
+
+
+
+R0.02 (June 01, 2006)
+
+  Added FAT12 support.
+  Removed unbuffered mode.
+  Fixed a problem on small (<32M) partition.
+
+
+
+R0.02a (June 10, 2006)
+
+  Added a configuration option (_FS_MINIMUM).
+
+
+
+R0.03 (September 22, 2006)
+
+  Added f_rename().
+  Changed option _FS_MINIMUM to _FS_MINIMIZE.
+
+
+
+R0.03a (December 11, 2006)
+
+  Improved cluster scan algorithm to write files fast.
+  Fixed f_mkdir() creates incorrect directory on FAT32.
+
+
+
+R0.04 (February 04, 2007)
+
+  Added f_mkfs().
+  Supported multiple drive system.
+  Changed some interfaces for multiple drive system.
+  Changed f_mountdrv() to f_mount().
+
+
+
+R0.04a (April 01, 2007)
+
+  Supported multiple partitions on a physical drive.
+  Added a capability of extending file size to f_lseek().
+  Added minimization level 3.
+  Fixed an endian sensitive code in f_mkfs().
+
+
+
+R0.04b (May 05, 2007)
+
+  Added a configuration option _USE_NTFLAG.
+  Added FSINFO support.
+  Fixed DBCS name can result FR_INVALID_NAME.
+  Fixed short seek (<= csize) collapses the file object.
+
+
+
+R0.05 (August 25, 2007)
+
+  Changed arguments of f_read(), f_write() and f_mkfs().
+  Fixed f_mkfs() on FAT32 creates incorrect FSINFO.
+  Fixed f_mkdir() on FAT32 creates incorrect directory.
+
+
+
+R0.05a (February 03, 2008)
+
+  Added f_truncate() and f_utime().
+  Fixed off by one error at FAT sub-type determination.
+  Fixed btr in f_read() can be mistruncated.
+  Fixed cached sector is not flushed when create and close without write.
+
+
+
+R0.06 (April 01, 2008)
+
+  Added fputc(), fputs(), fprintf() and fgets().
+  Improved performance of f_lseek() on moving to the same or following cluster.
+
+
+
+R0.07 (April 01, 2009)
+
+  Merged Tiny-FatFs as a configuration option. (_FS_TINY)
+  Added long file name feature. (_USE_LFN)
+  Added multiple code page feature. (_CODE_PAGE)
+  Added re-entrancy for multitask operation. (_FS_REENTRANT)
+  Added auto cluster size selection to f_mkfs().
+  Added rewind option to f_readdir().
+  Changed result code of critical errors.
+  Renamed string functions to avoid name collision.
+
+
+
+R0.07a (April 14, 2009)
+
+  Septemberarated out OS dependent code on reentrant cfg.
+  Added multiple sector size feature.
+
+
+
+R0.07c (June 21, 2009)
+
+  Fixed f_unlink() can return FR_OK on error.
+  Fixed wrong cache control in f_lseek().
+  Added relative path feature.
+  Added f_chdir() and f_chdrive().
+  Added proper case conversion to extended character.
+
+
+
+R0.07e (November 03, 2009)
+
+  Septemberarated out configuration options from ff.h to ffconf.h.
+  Fixed f_unlink() fails to remove a sub-directory on _FS_RPATH.
+  Fixed name matching error on the 13 character boundary.
+  Added a configuration option, _LFN_UNICODE.
+  Changed f_readdir() to return the SFN with always upper case on non-LFN cfg.
+
+
+
+R0.08 (May 15, 2010)
+
+  Added a memory configuration option. (_USE_LFN = 3)
+  Added file lock feature. (_FS_SHARE)
+  Added fast seek feature. (_USE_FASTSEEK)
+  Changed some types on the API, XCHAR->TCHAR.
+  Changed .fname in the FILINFO structure on Unicode cfg.
+  String functions support UTF-8 encoding files on Unicode cfg.
+
+
+
+R0.08a (August 16, 2010)
+
+  Added f_getcwd(). (_FS_RPATH = 2)
+  Added sector erase feature. (_USE_ERASE)
+  Moved file lock semaphore table from fs object to the bss.
+  Fixed f_mkfs() creates wrong FAT32 volume.
+
+
+
+R0.08b (January 15, 2011)
+
+  Fast seek feature is also applied to f_read() and f_write().
+  f_lseek() reports required table size on creating CLMP.
+  Extended format syntax of f_printf().
+  Ignores duplicated directory separators in given path name.
+
+
+
+R0.09 (September 06, 2011)
+
+  f_mkfs() supports multiple partition to complete the multiple partition feature.
+  Added f_fdisk().
+
+
+
+R0.09a (August 27, 2012)
+
+  Changed f_open() and f_opendir() reject null object pointer to avoid crash.
+  Changed option name _FS_SHARE to _FS_LOCK.
+  Fixed assertion failure due to OS/2 EA on FAT12/16 volume.
+
+
+
+R0.09b (January 24, 2013)
+
+  Added f_setlabel() and f_getlabel().
+
+
+
+R0.10 (October 02, 2013)
+
+  Added selection of character encoding on the file. (_STRF_ENCODE)
+  Added f_closedir().
+  Added forced full FAT scan for f_getfree(). (_FS_NOFSINFO)
+  Added forced mount feature with changes of f_mount().
+  Improved behavior of volume auto detection.
+  Improved write throughput of f_puts() and f_printf().
+  Changed argument of f_chdrive(), f_mkfs(), disk_read() and disk_write().
+  Fixed f_write() can be truncated when the file size is close to 4GB.
+  Fixed f_open(), f_mkdir() and f_setlabel() can return incorrect value on error.
+
+
+
+R0.10a (January 15, 2014)
+
+  Added arbitrary strings as drive number in the path name. (_STR_VOLUME_ID)
+  Added a configuration option of minimum sector size. (_MIN_SS)
+  2nd argument of f_rename() can have a drive number and it will be ignored.
+  Fixed f_mount() with forced mount fails when drive number is >= 1. (appeared at R0.10)
+  Fixed f_close() invalidates the file object without volume lock.
+  Fixed f_closedir() returns but the volume lock is left acquired. (appeared at R0.10)
+  Fixed creation of an entry with LFN fails on too many SFN collisions. (appeared at R0.07)
+
+
+
+R0.10b (May 19, 2014)
+
+  Fixed a hard error in the disk I/O layer can collapse the directory entry.
+  Fixed LFN entry is not deleted on delete/rename an object with lossy converted SFN. (appeared at R0.07)
+
+
+
+R0.10c (November 09, 2014)
+
+  Added a configuration option for the platforms without RTC. (_FS_NORTC)
+  Changed option name _USE_ERASE to _USE_TRIM.
+  Fixed volume label created by Mac OS X cannot be retrieved with f_getlabel(). (appeared at R0.09b)
+  Fixed a potential problem of FAT access that can appear on disk error.
+  Fixed null pointer dereference on attempting to delete the root direcotry. (appeared at R0.08)
+
+
+
+R0.11 (February 09, 2015)
+
+  Added f_findfirst(), f_findnext() and f_findclose(). (_USE_FIND)
+  Fixed f_unlink() does not remove cluster chain of the file. (appeared at R0.10c)
+  Fixed _FS_NORTC option does not work properly. (appeared at R0.10c)
+
+
+
+R0.11a (September 05, 2015)
+
+  Fixed wrong media change can lead a deadlock at thread-safe configuration.
+  Added code page 771, 860, 861, 863, 864, 865 and 869. (_CODE_PAGE)
+  Removed some code pages actually not exist on the standard systems. (_CODE_PAGE)
+  Fixed errors in the case conversion teble of code page 437 and 850 (ff.c).
+  Fixed errors in the case conversion teble of Unicode (cc*.c).
+
+
+
+R0.12 (April 12, 2016)
+
+  Added support for exFAT file system. (_FS_EXFAT)
+  Added f_expand(). (_USE_EXPAND)
+  Changed some members in FINFO structure and behavior of f_readdir().
+  Added an option _USE_CHMOD.
+  Removed an option _WORD_ACCESS.
+  Fixed errors in the case conversion table of Unicode (cc*.c).
+
+
+
+R0.12a (July 10, 2016)
+
+  Added support for creating exFAT volume with some changes of f_mkfs().
+  Added a file open method FA_OPEN_APPEND. An f_lseek() following f_open() is no longer needed.
+  f_forward() is available regardless of _FS_TINY.
+  Fixed f_mkfs() creates wrong volume. (appeared at R0.12)
+  Fixed wrong memory read in create_name(). (appeared at R0.12)
+  Fixed compilation fails at some configurations, _USE_FASTSEEK and _USE_FORWARD.
+
+
+
+R0.12b (September 04, 2016)
+
+  Improved f_rename() to be able to rename objects with the same name but case.
+  Fixed an error in the case conversion teble of code page 866. (ff.c)
+  Fixed writing data is truncated at the file offset 4GiB on the exFAT volume. (appeared at R0.12)
+  Fixed creating a file in the root directory of exFAT volume can fail. (appeared at R0.12)
+  Fixed f_mkfs() creating exFAT volume with too small cluster size can collapse unallocated memory. (appeared at R0.12)
+  Fixed wrong object name can be returned when read directory at Unicode cfg. (appeared at R0.12)
+  Fixed large file allocation/removing on the exFAT volume collapses allocation bitmap. (appeared at R0.12)
+  Fixed some internal errors in f_expand() and f_lseek(). (appeared at R0.12)
+
diff --git a/crazyflie-firmware-src/src/lib/FatFS/00readme.txt b/crazyflie-firmware-src/src/lib/FatFS/00readme.txt
new file mode 100644
index 0000000000000000000000000000000000000000..42426a4011ac035dae282deb1bf6404ca67e5be4
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/00readme.txt
@@ -0,0 +1,21 @@
+FatFs Module Source Files R0.12a
+
+
+FILES
+
+  00readme.txt This file.
+  history.txt  Revision history.
+  ffconf.h     Configuration file for FatFs module.
+  ff.h         Common include file for FatFs and application module.
+  ff.c         FatFs module.
+  diskio.h     Common include file for FatFs and disk I/O module.
+  diskio.c     An example of glue function to attach existing disk I/O module to FatFs.
+  integer.h    Integer type definitions for FatFs.
+  option       Optional external functions.
+
+
+  Low level disk I/O module is not included in this archive because the FatFs
+  module is only a generic file system layer and not depend on any specific
+  storage device. You have to provide a low level disk I/O module that written
+  to control the target storage device.
+
diff --git a/crazyflie-firmware-src/src/lib/FatFS/ccsbcs.c b/crazyflie-firmware-src/src/lib/FatFS/ccsbcs.c
new file mode 100644
index 0000000000000000000000000000000000000000..d22e37072f4bbb931930277f0efe5fddc1decf06
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/ccsbcs.c
@@ -0,0 +1,388 @@
+/*------------------------------------------------------------------------*/
+/* Unicode - Local code bidirectional converter  (C)ChaN, 2015            */
+/* (SBCS code pages)                                                      */
+/*------------------------------------------------------------------------*/
+/*  437   U.S.
+/   720   Arabic
+/   737   Greek
+/   771   KBL
+/   775   Baltic
+/   850   Latin 1
+/   852   Latin 2
+/   855   Cyrillic
+/   857   Turkish
+/   860   Portuguese
+/   861   Icelandic
+/   862   Hebrew
+/   863   Canadian French
+/   864   Arabic
+/   865   Nordic
+/   866   Russian
+/   869   Greek 2
+*/
+
+#include "ff.h"
+
+
+#if _CODE_PAGE == 437
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP437(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00E4, 0x00E0, 0x00E5, 0x00E7, 0x00EA, 0x00EB, 0x00E8, 0x00EF, 0x00EE, 0x00EC, 0x00C4, 0x00C5,
+	0x00C9, 0x00E6, 0x00C6, 0x00F4, 0x00F6, 0x00F2, 0x00FB, 0x00F9, 0x00FF, 0x00D6, 0x00DC, 0x00A2, 0x00A3, 0x00A5, 0x20A7, 0x0192,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x00F1, 0x00D1, 0x00AA, 0x00BA, 0x00BF, 0x2310, 0x00AC, 0x00BD, 0x00BC, 0x00A1, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x255B, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x03B1, 0x00DF, 0x0393, 0x03C0, 0x03A3, 0x03C3, 0x00B5, 0x03C4, 0x03A6, 0x0398, 0x03A9, 0x03B4, 0x221E, 0x03C6, 0x03B5, 0x2229,
+	0x2261, 0x00B1, 0x2265, 0x2264, 0x2320, 0x2321, 0x00F7, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 720
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP720(0x80-0xFF) to Unicode conversion table */
+	0x0000, 0x0000, 0x00E9, 0x00E2, 0x0000, 0x00E0, 0x0000, 0x00E7, 0x00EA, 0x00EB, 0x00E8, 0x00EF, 0x00EE, 0x0000, 0x0000, 0x0000,
+	0x0000, 0x0651, 0x0652, 0x00F4, 0x00A4, 0x0640, 0x00FB, 0x00F9, 0x0621, 0x0622, 0x0623, 0x0624, 0x00A3, 0x0625, 0x0626, 0x0627,
+	0x0628, 0x0629, 0x062A, 0x062B, 0x062C, 0x062D, 0x062E, 0x062F, 0x0630, 0x0631, 0x0632, 0x0633, 0x0634, 0x0635, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x255B, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x0636, 0x0637, 0x0638, 0x0639, 0x063A, 0x0641, 0x00B5, 0x0642, 0x0643, 0x0644, 0x0645, 0x0646, 0x0647, 0x0648, 0x0649, 0x064A,
+	0x2261, 0x064B, 0x064C, 0x064D, 0x064E, 0x064F, 0x0650, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 737
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP737(0x80-0xFF) to Unicode conversion table */
+	0x0391, 0x0392, 0x0393, 0x0394, 0x0395, 0x0396, 0x0397, 0x0398, 0x0399, 0x039A, 0x039B, 0x039C, 0x039D, 0x039E, 0x039F, 0x03A0,
+	0x03A1, 0x03A3, 0x03A4, 0x03A5, 0x03A6, 0x03A7, 0x03A8, 0x03A9, 0x03B1, 0x03B2, 0x03B3, 0x03B4, 0x03B5, 0x03B6, 0x03B7, 0x03B8,
+	0x03B9, 0x03BA, 0x03BB, 0x03BC, 0x03BD, 0x03BE, 0x03BF, 0x03C0, 0x03C1, 0x03C3, 0x03C2, 0x03C4, 0x03C5, 0x03C6, 0x03C7, 0x03C8,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x255B, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x03C9, 0x03AC, 0x03AD, 0x03AE, 0x03CA, 0x03AF, 0x03CC, 0x03CD, 0x03CB, 0x03CE, 0x0386, 0x0388, 0x0389, 0x038A, 0x038C, 0x038E,
+	0x038F, 0x00B1, 0x2265, 0x2264, 0x03AA, 0x03AB, 0x00F7, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 771
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP771(0x80-0xFF) to Unicode conversion table */
+	0x0410, 0x0411, 0x0412, 0x0413, 0x0414, 0x0415, 0x0416, 0x0417, 0x0418, 0x0419, 0x041A, 0x041B, 0x041C, 0x041D, 0x041E, 0x041F,
+	0x0420, 0x0421, 0x0422, 0x0423, 0x0424, 0x0425, 0x0426, 0x0427, 0x0428, 0x0429, 0x042A, 0x042B, 0x042C, 0x042D, 0x042E, 0x042F,
+	0x0430, 0x0431, 0x0432, 0x0433, 0x0434, 0x0435, 0x0436, 0x0437, 0x0438, 0x0439, 0x043A, 0x043B, 0x043C, 0x043D, 0x043E, 0x043F,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x2558, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x0104, 0x0105, 0x010C, 0x010D,
+	0x0440, 0x0441, 0x0442, 0x0443, 0x0444, 0x0445, 0x0446, 0x0447, 0x0448, 0x0449, 0x044A, 0x044B, 0x044C, 0x044D, 0x044E, 0x044F,
+	0x0118, 0x0119, 0x0116, 0x0117, 0x012E, 0x012F, 0x0160, 0x0161, 0x0172, 0x0173, 0x016A, 0x016B, 0x017D, 0x017E, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 775
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP775(0x80-0xFF) to Unicode conversion table */
+	0x0106, 0x00FC, 0x00E9, 0x0101, 0x00E4, 0x0123, 0x00E5, 0x0107, 0x0142, 0x0113, 0x0156, 0x0157, 0x012B, 0x0179, 0x00C4, 0x00C5,
+	0x00C9, 0x00E6, 0x00C6, 0x014D, 0x00F6, 0x0122, 0x00A2, 0x015A, 0x015B, 0x00D6, 0x00DC, 0x00F8, 0x00A3, 0x00D8, 0x00D7, 0x00A4,
+	0x0100, 0x012A, 0x00F3, 0x017B, 0x017C, 0x017A, 0x201D, 0x00A6, 0x00A9, 0x00AE, 0x00AC, 0x00BD, 0x00BC, 0x0141, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x0104, 0x010C, 0x0118, 0x0116, 0x2563, 0x2551, 0x2557, 0x255D, 0x012E, 0x0160, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x0172, 0x016A, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x017D,
+	0x0105, 0x010D, 0x0119, 0x0117, 0x012F, 0x0161, 0x0173, 0x016B, 0x017E, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x00D3, 0x00DF, 0x014C, 0x0143, 0x00F5, 0x00D5, 0x00B5, 0x0144, 0x0136, 0x0137, 0x013B, 0x013C, 0x0146, 0x0112, 0x0145, 0x2019,
+	0x00AD, 0x00B1, 0x201C, 0x00BE, 0x00B6, 0x00A7, 0x00F7, 0x201E, 0x00B0, 0x2219, 0x00B7, 0x00B9, 0x00B3, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 850
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP850(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00E4, 0x00E0, 0x00E5, 0x00E7, 0x00EA, 0x00EB, 0x00E8, 0x00EF, 0x00EE, 0x00EC, 0x00C4, 0x00C5,
+	0x00C9, 0x00E6, 0x00C6, 0x00F4, 0x00F6, 0x00F2, 0x00FB, 0x00F9, 0x00FF, 0x00D6, 0x00DC, 0x00F8, 0x00A3, 0x00D8, 0x00D7, 0x0192,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x00F1, 0x00D1, 0x00AA, 0x00BA, 0x00BF, 0x00AE, 0x00AC, 0x00BD, 0x00BC, 0x00A1, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x00C1, 0x00C2, 0x00C0, 0x00A9, 0x2563, 0x2551, 0x2557, 0x255D, 0x00A2, 0x00A5, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x00E3, 0x00C3, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x00A4,
+	0x00F0, 0x00D0, 0x00CA, 0x00CB, 0x00C8, 0x0131, 0x00CD, 0x00CE, 0x00CF, 0x2518, 0x250C, 0x2588, 0x2584, 0x00A6, 0x00CC, 0x2580,
+	0x00D3, 0x00DF, 0x00D4, 0x00D2, 0x00F5, 0x00D5, 0x00B5, 0x00FE, 0x00DE, 0x00DA, 0x00DB, 0x00D9, 0x00FD, 0x00DD, 0x00AF, 0x00B4,
+	0x00AD, 0x00B1, 0x2017, 0x00BE, 0x00B6, 0x00A7, 0x00F7, 0x00B8, 0x00B0, 0x00A8, 0x00B7, 0x00B9, 0x00B3, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 852
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP852(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00E4, 0x016F, 0x0107, 0x00E7, 0x0142, 0x00EB, 0x0150, 0x0151, 0x00EE, 0x0179, 0x00C4, 0x0106,
+	0x00C9, 0x0139, 0x013A, 0x00F4, 0x00F6, 0x013D, 0x013E, 0x015A, 0x015B, 0x00D6, 0x00DC, 0x0164, 0x0165, 0x0141, 0x00D7, 0x010D,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x0104, 0x0105, 0x017D, 0x017E, 0x0118, 0x0119, 0x00AC, 0x017A, 0x010C, 0x015F, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x00C1, 0x00C2, 0x011A, 0x015E, 0x2563, 0x2551, 0x2557, 0x255D, 0x017B, 0x017C, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x0102, 0x0103, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x00A4,
+	0x0111, 0x0110, 0x010E, 0x00CB, 0x010F, 0x0147, 0x00CD, 0x00CE, 0x011B, 0x2518, 0x250C, 0x2588, 0x2584, 0x0162, 0x016E, 0x2580,
+	0x00D3, 0x00DF, 0x00D4, 0x0143, 0x0144, 0x0148, 0x0160, 0x0161, 0x0154, 0x00DA, 0x0155, 0x0170, 0x00FD, 0x00DD, 0x0163, 0x00B4,
+	0x00AD, 0x02DD, 0x02DB, 0x02C7, 0x02D8, 0x00A7, 0x00F7, 0x00B8, 0x00B0, 0x00A8, 0x02D9, 0x0171, 0x0158, 0x0159, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 855
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP855(0x80-0xFF) to Unicode conversion table */
+	0x0452, 0x0402, 0x0453, 0x0403, 0x0451, 0x0401, 0x0454, 0x0404, 0x0455, 0x0405, 0x0456, 0x0406, 0x0457, 0x0407, 0x0458, 0x0408,
+	0x0459, 0x0409, 0x045A, 0x040A, 0x045B, 0x040B, 0x045C, 0x040C, 0x045E, 0x040E, 0x045F, 0x040F, 0x044E, 0x042E, 0x044A, 0x042A,
+	0x0430, 0x0410, 0x0431, 0x0411, 0x0446, 0x0426, 0x0434, 0x0414, 0x0435, 0x0415, 0x0444, 0x0424, 0x0433, 0x0413, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x0445, 0x0425, 0x0438, 0x0418, 0x2563, 0x2551, 0x2557, 0x255D, 0x0439, 0x0419, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x043A, 0x041A, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x00A4,
+	0x043B, 0x041B, 0x043C, 0x041C, 0x043D, 0x041D, 0x043E, 0x041E, 0x043F, 0x2518, 0x250C, 0x2588, 0x2584, 0x041F, 0x044F, 0x2580,
+	0x042F, 0x0440, 0x0420, 0x0441, 0x0421, 0x0442, 0x0422, 0x0443, 0x0423, 0x0436, 0x0416, 0x0432, 0x0412, 0x044C, 0x042C, 0x2116,
+	0x00AD, 0x044B, 0x042B, 0x0437, 0x0417, 0x0448, 0x0428, 0x044D, 0x042D, 0x0449, 0x0429, 0x0447, 0x0427, 0x00A7, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 857
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP857(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00E4, 0x00E0, 0x00E5, 0x00E7, 0x00EA, 0x00EB, 0x00E8, 0x00EF, 0x00EE, 0x0131, 0x00C4, 0x00C5,
+	0x00C9, 0x00E6, 0x00C6, 0x00F4, 0x00F6, 0x00F2, 0x00FB, 0x00F9, 0x0130, 0x00D6, 0x00DC, 0x00F8, 0x00A3, 0x00D8, 0x015E, 0x015F,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x00F1, 0x00D1, 0x011E, 0x011F, 0x00BF, 0x00AE, 0x00AC, 0x00BD, 0x00BC, 0x00A1, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x00C1, 0x00C2, 0x00C0, 0x00A9, 0x2563, 0x2551, 0x2557, 0x255D, 0x00A2, 0x00A5, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x00E3, 0x00C3, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x00A4,
+	0x00BA, 0x00AA, 0x00CA, 0x00CB, 0x00C8, 0x0000, 0x00CD, 0x00CE, 0x00CF, 0x2518, 0x250C, 0x2588, 0x2584, 0x00A6, 0x00CC, 0x2580,
+	0x00D3, 0x00DF, 0x00D4, 0x00D2, 0x00F5, 0x00D5, 0x00B5, 0x0000, 0x00D7, 0x00DA, 0x00DB, 0x00D9, 0x00EC, 0x00FF, 0x00AF, 0x00B4,
+	0x00AD, 0x00B1, 0x0000, 0x00BE, 0x00B6, 0x00A7, 0x00F7, 0x00B8, 0x00B0, 0x00A8, 0x00B7, 0x00B9, 0x00B3, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 860
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP860(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00E3, 0x00E0, 0x00C1, 0x00E7, 0x00EA, 0x00CA, 0x00E8, 0x00CD, 0x00D4, 0x00EC, 0x00C3, 0x00C2,
+	0x00C9, 0x00C0, 0x00C8, 0x00F4, 0x00F5, 0x00F2, 0x00DA, 0x00F9, 0x00CC, 0x00D5, 0x00DC, 0x00A2, 0x00A3, 0x00D9, 0x20A7, 0x00D3,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x00F1, 0x00D1, 0x00AA, 0x00BA, 0x00BF, 0x00D2, 0x00AC, 0x00BD, 0x00BC, 0x00A1, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x2558, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x03B1, 0x00DF, 0x0393, 0x03C0, 0x03A3, 0x03C3, 0x00B5, 0x03C4, 0x03A6, 0x0398, 0x03A9, 0x03B4, 0x221E, 0x03C6, 0x03B5, 0x2229,
+	0x2261, 0x00B1, 0x2265, 0x2264, 0x2320, 0x2321, 0x00F7, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 861
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP861(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00E4, 0x00E0, 0x00E6, 0x00E7, 0x00EA, 0x00EB, 0x00E8, 0x00D0, 0x00F0, 0x00DE, 0x00C4, 0x00C5,
+	0x00C9, 0x00E6, 0x00C6, 0x00F4, 0x00F6, 0x00FE, 0x00FB, 0x00DD, 0x00FD, 0x00D6, 0x00DC, 0x00F8, 0x00A3, 0x00D8, 0x20A7, 0x0192,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x00C1, 0x00CD, 0x00D3, 0x00DA, 0x00BF, 0x2310, 0x00AC, 0x00BD, 0x00BC, 0x00A1, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x255B, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x03B1, 0x00DF, 0x0393, 0x03C0, 0x03A3, 0x03C3, 0x00B5, 0x03C4, 0x03A6, 0x0398, 0x03A9, 0x03B4, 0x221E, 0x03C6, 0x03B5, 0x2229,
+	0x2261, 0x00B1, 0x2265, 0x2264, 0x2320, 0x2321, 0x00F7, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 862
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP862(0x80-0xFF) to Unicode conversion table */
+	0x05D0, 0x05D1, 0x05D2, 0x05D3, 0x05D4, 0x05D5, 0x05D6, 0x05D7, 0x05D8, 0x05D9, 0x05DA, 0x05DB, 0x05DC, 0x05DD, 0x05DE, 0x05DF,
+	0x05E0, 0x05E1, 0x05E2, 0x05E3, 0x05E4, 0x05E5, 0x05E6, 0x05E7, 0x05E8, 0x05E9, 0x05EA, 0x00A2, 0x00A3, 0x00A5, 0x20A7, 0x0192,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x00F1, 0x00D1, 0x00AA, 0x00BA, 0x00BF, 0x2310, 0x00AC, 0x00BD, 0x00BC, 0x00A1, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x255B, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x03B1, 0x00DF, 0x0393, 0x03C0, 0x03A3, 0x03C3, 0x00B5, 0x03C4, 0x03A6, 0x0398, 0x03A9, 0x03B4, 0x221E, 0x03C6, 0x03B5, 0x2229,
+	0x2261, 0x00B1, 0x2265, 0x2264, 0x2320, 0x2321, 0x00F7, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 863
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP863(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00C2, 0x00E0, 0x00B6, 0x00E7, 0x00EA, 0x00EB, 0x00E8, 0x00EF, 0x00EE, 0x00EC, 0x2017, 0x00C0,
+	0x00C9, 0x00C8, 0x00CA, 0x00F4, 0x00CB, 0x00CF, 0x00FB, 0x00F9, 0x00A4, 0x00D4, 0x00DC, 0x00A2, 0x00A3, 0x00D9, 0x00DB, 0x0192,
+	0x00A6, 0x00B4, 0x00F3, 0x00FA, 0x00A8, 0x00BB, 0x00B3, 0x00AF, 0x00CE, 0x3210, 0x00AC, 0x00BD, 0x00BC, 0x00BE, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x255B, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x03B1, 0x00DF, 0x0393, 0x03C0, 0x03A3, 0x03C3, 0x00B5, 0x03C4, 0x03A6, 0x0398, 0x03A9, 0x03B4, 0x221E, 0x03C6, 0x03B5, 0x2219,
+	0x2261, 0x00B1, 0x2265, 0x2264, 0x2320, 0x2321, 0x00F7, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 864
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP864(0x80-0xFF) to Unicode conversion table */
+	0x00B0, 0x00B7, 0x2219, 0x221A, 0x2592, 0x2500, 0x2502, 0x253C, 0x2524, 0x252C, 0x251C, 0x2534, 0x2510, 0x250C, 0x2514, 0x2518,
+	0x03B2, 0x221E, 0x03C6, 0x00B1, 0x00BD, 0x00BC, 0x2248, 0x00AB, 0x00BB, 0xFEF7, 0xFEF8, 0x0000, 0x0000, 0xFEFB, 0xFEFC, 0x0000,
+	0x00A0, 0x00AD, 0xFE82, 0x00A3, 0x00A4, 0xFE84, 0x0000, 0x20AC, 0xFE8E, 0xFE8F, 0xFE95, 0xFE99, 0x060C, 0xFE9D, 0xFEA1, 0xFEA5,
+	0x0660, 0x0661, 0x0662, 0x0663, 0x0664, 0x0665, 0x0666, 0x0667, 0x0668, 0x0669, 0xFED1, 0x061B, 0xFEB1, 0xFEB5, 0xFEB9, 0x061F,
+	0x00A2, 0xFE80, 0xFE81, 0xFE83, 0xFE85, 0xFECA, 0xFE8B, 0xFE8D, 0xFE91, 0xFE93, 0xFE97, 0xFE9B, 0xFE9F, 0xFEA3, 0xFEA7, 0xFEA9,
+	0xFEAB, 0xFEAD, 0xFEAF, 0xFEB3, 0xFEB7, 0xFEBB, 0xFEBF, 0xFEC1, 0xFEC5, 0xFECB, 0xFECF, 0x00A6, 0x00AC, 0x00F7, 0x00D7, 0xFEC9,
+	0x0640, 0xFED3, 0xFED7, 0xFEDB, 0xFEDF, 0xFEE3, 0xFEE7, 0xFEEB, 0xFEED, 0xFEEF, 0xFEF3, 0xFEBD, 0xFECC, 0xFECE, 0xFECD, 0xFEE1,
+	0xFE7D, 0x0651, 0xFEE5, 0xFEE9, 0xFEEC, 0xFEF0, 0xFEF2, 0xFED0, 0xFED5, 0xFEF5, 0xFEF6, 0xFEDD, 0xFED9, 0xFEF1, 0x25A0, 0x0000
+};
+
+#elif _CODE_PAGE == 865
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP865(0x80-0xFF) to Unicode conversion table */
+	0x00C7, 0x00FC, 0x00E9, 0x00E2, 0x00E4, 0x00E0, 0x00E5, 0x00E7, 0x00EA, 0x00EB, 0x00E8, 0x00EF, 0x00EE, 0x00EC, 0x00C4, 0x00C5,
+	0x00C5, 0x00E6, 0x00C6, 0x00F4, 0x00F6, 0x00F2, 0x00FB, 0x00F9, 0x00FF, 0x00D6, 0x00DC, 0x00F8, 0x00A3, 0x00D8, 0x20A7, 0x0192,
+	0x00E1, 0x00ED, 0x00F3, 0x00FA, 0x00F1, 0x00D1, 0x00AA, 0x00BA, 0x00BF, 0x2310, 0x00AC, 0x00BD, 0x00BC, 0x00A1, 0x00AB, 0x00A4,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x2558, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x03B1, 0x00DF, 0x0393, 0x03C0, 0x03A3, 0x03C3, 0x00B5, 0x03C4, 0x03A6, 0x0398, 0x03A9, 0x03B4, 0x221E, 0x03C6, 0x03B5, 0x2229,
+	0x2261, 0x00B1, 0x2265, 0x2264, 0x2320, 0x2321, 0x00F7, 0x2248, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x207F, 0x00B2, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 866
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP866(0x80-0xFF) to Unicode conversion table */
+	0x0410, 0x0411, 0x0412, 0x0413, 0x0414, 0x0415, 0x0416, 0x0417, 0x0418, 0x0419, 0x041A, 0x041B, 0x041C, 0x041D, 0x041E, 0x041F,
+	0x0420, 0x0421, 0x0422, 0x0423, 0x0424, 0x0425, 0x0426, 0x0427, 0x0428, 0x0429, 0x042A, 0x042B, 0x042C, 0x042D, 0x042E, 0x042F,
+	0x0430, 0x0431, 0x0432, 0x0433, 0x0434, 0x0435, 0x0436, 0x0437, 0x0438, 0x0439, 0x043A, 0x043B, 0x043C, 0x043D, 0x043E, 0x043F,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x2561, 0x2562, 0x2556, 0x2555, 0x2563, 0x2551, 0x2557, 0x255D, 0x255C, 0x255B, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x255E, 0x255F, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x2567,
+	0x2568, 0x2564, 0x2565, 0x2559, 0x2558, 0x2552, 0x2553, 0x256B, 0x256A, 0x2518, 0x250C, 0x2588, 0x2584, 0x258C, 0x2590, 0x2580,
+	0x0440, 0x0441, 0x0442, 0x0443, 0x0444, 0x0445, 0x0446, 0x0447, 0x0448, 0x0449, 0x044A, 0x044B, 0x044C, 0x044D, 0x044E, 0x044F,
+	0x0401, 0x0451, 0x0404, 0x0454, 0x0407, 0x0457, 0x040E, 0x045E, 0x00B0, 0x2219, 0x00B7, 0x221A, 0x2116, 0x00A4, 0x25A0, 0x00A0
+};
+
+#elif _CODE_PAGE == 869
+#define _TBLDEF 1
+static
+const WCHAR Tbl[] = {	/*  CP869(0x80-0xFF) to Unicode conversion table */
+	0x00B7, 0x00B7, 0x00B7, 0x00B7, 0x00B7, 0x00B7, 0x0386, 0x00B7, 0x00B7, 0x00AC, 0x00A6, 0x2018, 0x2019, 0x0388, 0x2015, 0x0389,
+	0x038A, 0x03AA, 0x038C, 0x00B7, 0x00B7, 0x038E, 0x03AB, 0x00A9, 0x038F, 0x00B2, 0x00B3, 0x03AC, 0x00A3, 0x03AD, 0x03AE, 0x03AF,
+	0x03CA, 0x0390, 0x03CC, 0x03CD, 0x0391, 0x0392, 0x0393, 0x0394, 0x0395, 0x0396, 0x0397, 0x00BD, 0x0398, 0x0399, 0x00AB, 0x00BB,
+	0x2591, 0x2592, 0x2593, 0x2502, 0x2524, 0x039A, 0x039B, 0x039C, 0x039D, 0x2563, 0x2551, 0x2557, 0x255D, 0x039E, 0x039F, 0x2510,
+	0x2514, 0x2534, 0x252C, 0x251C, 0x2500, 0x253C, 0x0A30, 0x03A1, 0x255A, 0x2554, 0x2569, 0x2566, 0x2560, 0x2550, 0x256C, 0x03A3,
+	0x03A4, 0x03A5, 0x03A6, 0x03A7, 0x03A8, 0x03A9, 0x03B1, 0x03B2, 0x03B3, 0x2518, 0x250C, 0x2588, 0x2584, 0x03B4, 0x03B5, 0x2580,
+	0x03B6, 0x03B7, 0x03B8, 0x03B9, 0x03BA, 0x03BB, 0x03BC, 0x03BD, 0x03BE, 0x03BF, 0x03C0, 0x03C1, 0x03C3, 0x03C2, 0x03C4, 0x0384,
+	0x00AD, 0x00B1, 0x03C5, 0x03C6, 0x03C7, 0x00A7, 0x03C8, 0x0385, 0x00B0, 0x00A8, 0x03C9, 0x03CB, 0x03B0, 0x03CE, 0x25A0, 0x00A0
+};
+
+#endif
+
+
+#if !_TBLDEF || !_USE_LFN
+#error This file is not needed at current configuration. Remove from the project.
+#endif
+
+
+
+
+WCHAR ff_convert (	/* Converted character, Returns zero on error */
+	WCHAR	chr,	/* Character code to be converted */
+	UINT	dir		/* 0: Unicode to OEM code, 1: OEM code to Unicode */
+)
+{
+	WCHAR c;
+
+
+	if (chr < 0x80) {	/* ASCII */
+		c = chr;
+
+	} else {
+		if (dir) {		/* OEM code to Unicode */
+			c = (chr >= 0x100) ? 0 : Tbl[chr - 0x80];
+
+		} else {		/* Unicode to OEM code */
+			for (c = 0; c < 0x80; c++) {
+				if (chr == Tbl[c]) break;
+			}
+			c = (c + 0x80) & 0xFF;
+		}
+	}
+
+	return c;
+}
+
+
+
+WCHAR ff_wtoupper (	/* Returns upper converted character */
+	WCHAR chr		/* Unicode character to be upper converted (BMP only) */
+)
+{
+	/* Compressed upper conversion table */
+	static const WCHAR cvt1[] = {	/* U+0000 - U+0FFF */
+		/* Basic Latin */
+		0x0061,0x031A,
+		/* Latin-1 Supplement */
+		0x00E0,0x0317,  0x00F8,0x0307,  0x00FF,0x0001,0x0178,
+		/* Latin Extended-A */
+		0x0100,0x0130,  0x0132,0x0106,  0x0139,0x0110,  0x014A,0x012E,  0x0179,0x0106,
+		/* Latin Extended-B */
+		0x0180,0x004D,0x0243,0x0181,0x0182,0x0182,0x0184,0x0184,0x0186,0x0187,0x0187,0x0189,0x018A,0x018B,0x018B,0x018D,0x018E,0x018F,0x0190,0x0191,0x0191,0x0193,0x0194,0x01F6,0x0196,0x0197,0x0198,0x0198,0x023D,0x019B,0x019C,0x019D,0x0220,0x019F,0x01A0,0x01A0,0x01A2,0x01A2,0x01A4,0x01A4,0x01A6,0x01A7,0x01A7,0x01A9,0x01AA,0x01AB,0x01AC,0x01AC,0x01AE,0x01AF,0x01AF,0x01B1,0x01B2,0x01B3,0x01B3,0x01B5,0x01B5,0x01B7,0x01B8,0x01B8,0x01BA,0x01BB,0x01BC,0x01BC,0x01BE,0x01F7,0x01C0,0x01C1,0x01C2,0x01C3,0x01C4,0x01C5,0x01C4,0x01C7,0x01C8,0x01C7,0x01CA,0x01CB,0x01CA,
+		0x01CD,0x0110,  0x01DD,0x0001,0x018E,  0x01DE,0x0112,  0x01F3,0x0003,0x01F1,0x01F4,0x01F4,  0x01F8,0x0128,
+		0x0222,0x0112,  0x023A,0x0009,0x2C65,0x023B,0x023B,0x023D,0x2C66,0x023F,0x0240,0x0241,0x0241,  0x0246,0x010A,
+		/* IPA Extensions */
+		0x0253,0x0040,0x0181,0x0186,0x0255,0x0189,0x018A,0x0258,0x018F,0x025A,0x0190,0x025C,0x025D,0x025E,0x025F,0x0193,0x0261,0x0262,0x0194,0x0264,0x0265,0x0266,0x0267,0x0197,0x0196,0x026A,0x2C62,0x026C,0x026D,0x026E,0x019C,0x0270,0x0271,0x019D,0x0273,0x0274,0x019F,0x0276,0x0277,0x0278,0x0279,0x027A,0x027B,0x027C,0x2C64,0x027E,0x027F,0x01A6,0x0281,0x0282,0x01A9,0x0284,0x0285,0x0286,0x0287,0x01AE,0x0244,0x01B1,0x01B2,0x0245,0x028D,0x028E,0x028F,0x0290,0x0291,0x01B7,
+		/* Greek, Coptic */
+		0x037B,0x0003,0x03FD,0x03FE,0x03FF,  0x03AC,0x0004,0x0386,0x0388,0x0389,0x038A,  0x03B1,0x0311,
+		0x03C2,0x0002,0x03A3,0x03A3,  0x03C4,0x0308,  0x03CC,0x0003,0x038C,0x038E,0x038F,  0x03D8,0x0118,
+		0x03F2,0x000A,0x03F9,0x03F3,0x03F4,0x03F5,0x03F6,0x03F7,0x03F7,0x03F9,0x03FA,0x03FA,
+		/* Cyrillic */
+		0x0430,0x0320,  0x0450,0x0710,  0x0460,0x0122,  0x048A,0x0136,  0x04C1,0x010E,  0x04CF,0x0001,0x04C0,  0x04D0,0x0144,
+		/* Armenian */
+		0x0561,0x0426,
+
+		0x0000
+	};
+	static const WCHAR cvt2[] = {	/* U+1000 - U+FFFF */
+		/* Phonetic Extensions */
+		0x1D7D,0x0001,0x2C63,
+		/* Latin Extended Additional */
+		0x1E00,0x0196,  0x1EA0,0x015A,
+		/* Greek Extended */
+		0x1F00,0x0608,  0x1F10,0x0606,  0x1F20,0x0608,  0x1F30,0x0608,  0x1F40,0x0606,
+		0x1F51,0x0007,0x1F59,0x1F52,0x1F5B,0x1F54,0x1F5D,0x1F56,0x1F5F,  0x1F60,0x0608,
+		0x1F70,0x000E,0x1FBA,0x1FBB,0x1FC8,0x1FC9,0x1FCA,0x1FCB,0x1FDA,0x1FDB,0x1FF8,0x1FF9,0x1FEA,0x1FEB,0x1FFA,0x1FFB,
+		0x1F80,0x0608,  0x1F90,0x0608,  0x1FA0,0x0608,  0x1FB0,0x0004,0x1FB8,0x1FB9,0x1FB2,0x1FBC,
+		0x1FCC,0x0001,0x1FC3,  0x1FD0,0x0602,  0x1FE0,0x0602,  0x1FE5,0x0001,0x1FEC,  0x1FF2,0x0001,0x1FFC,
+		/* Letterlike Symbols */
+		0x214E,0x0001,0x2132,
+		/* Number forms */
+		0x2170,0x0210,  0x2184,0x0001,0x2183,
+		/* Enclosed Alphanumerics */
+		0x24D0,0x051A,  0x2C30,0x042F,
+		/* Latin Extended-C */
+		0x2C60,0x0102,  0x2C67,0x0106, 0x2C75,0x0102,
+		/* Coptic */
+		0x2C80,0x0164,
+		/* Georgian Supplement */
+		0x2D00,0x0826,
+		/* Full-width */
+		0xFF41,0x031A,
+
+		0x0000
+	};
+	const WCHAR *p;
+	WCHAR bc, nc, cmd;
+
+
+	p = chr < 0x1000 ? cvt1 : cvt2;
+	for (;;) {
+		bc = *p++;								/* Get block base */
+		if (!bc || chr < bc) break;
+		nc = *p++; cmd = nc >> 8; nc &= 0xFF;	/* Get processing command and block size */
+		if (chr < bc + nc) {	/* In the block? */
+			switch (cmd) {
+			case 0:	chr = p[chr - bc]; break;		/* Table conversion */
+			case 1:	chr -= (chr - bc) & 1; break;	/* Case pairs */
+			case 2: chr -= 16; break;				/* Shift -16 */
+			case 3:	chr -= 32; break;				/* Shift -32 */
+			case 4:	chr -= 48; break;				/* Shift -48 */
+			case 5:	chr -= 26; break;				/* Shift -26 */
+			case 6:	chr += 8; break;				/* Shift +8 */
+			case 7: chr -= 80; break;				/* Shift -80 */
+			case 8:	chr -= 0x1C60; break;			/* Shift -0x1C60 */
+			}
+			break;
+		}
+		if (!cmd) p += nc;
+	}
+
+	return chr;
+}
+
diff --git a/crazyflie-firmware-src/src/lib/FatFS/desktop.ini b/crazyflie-firmware-src/src/lib/FatFS/desktop.ini
new file mode 100644
index 0000000000000000000000000000000000000000..50942d7aa0e4047cf7ed944ac9562ad529289759
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/desktop.ini
@@ -0,0 +1,5 @@
+[.ShellClassInfo]
+InfoTip=Ta mapa je v skupni rabi v spletu.
+IconFile=C:\Program Files (x86)\Google\Drive\googledrivesync.exe
+IconIndex=12
+    
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/lib/FatFS/diskio_function_tests.c b/crazyflie-firmware-src/src/lib/FatFS/diskio_function_tests.c
new file mode 100644
index 0000000000000000000000000000000000000000..8853b947f4680a044ba78a63c402496e5c2c089a
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/diskio_function_tests.c
@@ -0,0 +1,301 @@
+/*----------------------------------------------------------------------/
+/ Low level disk I/O module function checker
+/-----------------------------------------------------------------------/
+/ WARNING: The data on the target drive will be lost!
+*/
+
+#define DEBUG_MODULE ""
+
+#include <stdio.h>
+#include <string.h>
+#include "ff.h"
+#include "diskio.h"
+#include "debug.h"
+
+static
+DWORD pn (
+    DWORD pns
+)
+{
+    static DWORD lfsr;
+    UINT n;
+
+
+    if (pns) {
+        lfsr = pns;
+        for (n = 0; n < 32; n++) pn(0);
+    }
+    if (lfsr & 1) {
+        lfsr >>= 1;
+        lfsr ^= 0x80200003;
+    } else {
+        lfsr >>= 1;
+    }
+    return lfsr;
+}
+
+
+int test_diskio (
+    BYTE pdrv,      /* Physical drive number to be checked (all data on the drive will be lost) */
+    UINT ncyc,      /* Number of test cycles */
+    DWORD* buff,    /* Pointer to the working buffer */
+    UINT sz_buff    /* Size of the working buffer in unit of byte */
+)
+{
+    UINT n, cc, ns;
+    DWORD sz_drv, lba, lba2, sz_eblk, pns = 1;
+    WORD sz_sect;
+    BYTE *pbuff = (BYTE*)buff;
+    DSTATUS ds;
+    DRESULT dr;
+
+
+    DEBUG_PRINT("test_diskio(%u, %u, 0x%08X, 0x%08X)\n", pdrv, ncyc, (UINT)buff, sz_buff);
+
+    if (sz_buff < _MAX_SS + 4) {
+        DEBUG_PRINT("Insufficient work area to test.\n");
+        return 1;
+    }
+
+    for (cc = 1; cc <= ncyc; cc++) {
+        DEBUG_PRINT("**** Test cycle %u of %u start ****\n", cc, ncyc);
+
+        /* Initialization */
+        DEBUG_PRINT(" disk_initalize(%u)", pdrv);
+        ds = disk_initialize(pdrv);
+        if (ds & STA_NOINIT) {
+            DEBUG_PRINT("[FAIL].\n");
+            return 2;
+        } else {
+            DEBUG_PRINT("[OK].\n");
+        }
+
+        /* Get drive size */
+        DEBUG_PRINT("**** Get drive size ****\n");
+        DEBUG_PRINT(" disk_ioctl(%u, GET_SECTOR_COUNT, 0x%08X)", pdrv, (UINT)&sz_drv);
+        sz_drv = 0;
+        dr = disk_ioctl(pdrv, GET_SECTOR_COUNT, &sz_drv);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 3;
+        }
+        if (sz_drv < 128) {
+            DEBUG_PRINT("Failed: Insufficient drive size to test.\n");
+            return 4;
+        }
+        DEBUG_PRINT(" Number of sectors on the drive %u is %lu.\n", pdrv, sz_drv);
+
+#if _MAX_SS != _MIN_SS
+        /* Get sector size */
+        DEBUG_PRINT("**** Get sector size ****\n");
+        DEBUG_PRINT(" disk_ioctl(%u, GET_SECTOR_SIZE, 0x%X)", pdrv, (UINT)&sz_sect);
+        sz_sect = 0;
+        dr = disk_ioctl(pdrv, GET_SECTOR_SIZE, &sz_sect);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 5;
+        }
+        DEBUG_PRINT(" Size of sector is %u bytes.\n", sz_sect);
+#else
+        sz_sect = _MAX_SS;
+#endif
+
+        /* Get erase block size */
+        DEBUG_PRINT("**** Get block size ****\n");
+        DEBUG_PRINT(" disk_ioctl(%u, GET_BLOCK_SIZE, 0x%X)", pdrv, (UINT)&sz_eblk);
+        sz_eblk = 0;
+        dr = disk_ioctl(pdrv, GET_BLOCK_SIZE, &sz_eblk);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+        }
+        if (dr == RES_OK || sz_eblk >= 2) {
+            DEBUG_PRINT(" Size of the erase block is %lu sectors.\n", sz_eblk);
+        } else {
+            DEBUG_PRINT(" Size of the erase block is unknown.\n");
+        }
+
+        /* Single sector write test */
+        DEBUG_PRINT("**** Single sector write test 1 ****\n");
+        lba = 0;
+        for (n = 0, pn(pns); n < sz_sect; n++) pbuff[n] = (BYTE)pn(0);
+        DEBUG_PRINT(" disk_write(%u, 0x%X, %lu, 1)", pdrv, (UINT)pbuff, lba);
+        dr = disk_write(pdrv, pbuff, lba, 1);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 6;
+        }
+        DEBUG_PRINT(" disk_ioctl(%u, CTRL_SYNC, NULL)", pdrv);
+        dr = disk_ioctl(pdrv, CTRL_SYNC, 0);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 7;
+        }
+        memset(pbuff, 0, sz_sect);
+        DEBUG_PRINT(" disk_read(%u, 0x%X, %lu, 1)", pdrv, (UINT)pbuff, lba);
+        dr = disk_read(pdrv, pbuff, lba, 1);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 8;
+        }
+        for (n = 0, pn(pns); n < sz_sect && pbuff[n] == (BYTE)pn(0); n++) ;
+        if (n == sz_sect) {
+            DEBUG_PRINT(" Data matched.\n");
+        } else {
+            DEBUG_PRINT("Failed: Read data differs from the data written.\n");
+            return 10;
+        }
+        pns++;
+
+        /* Multiple sector write test */
+        DEBUG_PRINT("**** Multiple sector write test ****\n");
+        lba = 1; ns = sz_buff / sz_sect;
+        if (ns > 4) ns = 4;
+        for (n = 0, pn(pns); n < (UINT)(sz_sect * ns); n++) pbuff[n] = (BYTE)pn(0);
+        DEBUG_PRINT(" disk_write(%u, 0x%X, %lu, %u)", pdrv, (UINT)pbuff, lba, ns);
+        dr = disk_write(pdrv, pbuff, lba, ns);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 11;
+        }
+        DEBUG_PRINT(" disk_ioctl(%u, CTRL_SYNC, NULL)", pdrv);
+        dr = disk_ioctl(pdrv, CTRL_SYNC, 0);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 12;
+        }
+        memset(pbuff, 0, sz_sect * ns);
+        DEBUG_PRINT(" disk_read(%u, 0x%X, %lu, %u)", pdrv, (UINT)pbuff, lba, ns);
+        dr = disk_read(pdrv, pbuff, lba, ns);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 13;
+        }
+        for (n = 0, pn(pns); n < (UINT)(sz_sect * ns) && pbuff[n] == (BYTE)pn(0); n++) ;
+        if (n == (UINT)(sz_sect * ns)) {
+            DEBUG_PRINT(" Data matched.\n");
+        } else {
+            DEBUG_PRINT("Failed: Read data differs from the data written.\n");
+            return 14;
+        }
+        pns++;
+
+        /* Single sector write test (misaligned memory address) */
+        DEBUG_PRINT("**** Single sector write test 2 ****\n");
+        lba = 5;
+        for (n = 0, pn(pns); n < sz_sect; n++) pbuff[n+3] = (BYTE)pn(0);
+        DEBUG_PRINT(" disk_write(%u, 0x%X, %lu, 1)", pdrv, (UINT)(pbuff+3), lba);
+        dr = disk_write(pdrv, pbuff+3, lba, 1);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 15;
+        }
+        DEBUG_PRINT(" disk_ioctl(%u, CTRL_SYNC, NULL)", pdrv);
+        dr = disk_ioctl(pdrv, CTRL_SYNC, 0);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 16;
+        }
+        memset(pbuff+5, 0, sz_sect);
+        DEBUG_PRINT(" disk_read(%u, 0x%X, %lu, 1)", pdrv, (UINT)(pbuff+5), lba);
+        dr = disk_read(pdrv, pbuff+5, lba, 1);
+        if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+        } else {
+            DEBUG_PRINT("[FAIL].\n");
+            return 17;
+        }
+        for (n = 0, pn(pns); n < sz_sect && pbuff[n+5] == (BYTE)pn(0); n++) ;
+        if (n == sz_sect) {
+            DEBUG_PRINT(" Data matched.\n");
+        } else {
+            DEBUG_PRINT("Failed: Read data differs from the data written.\n");
+            return 18;
+        }
+        pns++;
+
+        /* 4GB barrier test */
+        DEBUG_PRINT("**** 4GB barrier test ****\n");
+        if (sz_drv >= 128 + 0x80000000 / (sz_sect / 2)) {
+            lba = 6; lba2 = lba + 0x80000000 / (sz_sect / 2);
+            for (n = 0, pn(pns); n < (UINT)(sz_sect * 2); n++) pbuff[n] = (BYTE)pn(0);
+            DEBUG_PRINT(" disk_write(%u, 0x%X, %lu, 1)", pdrv, (UINT)pbuff, lba);
+            dr = disk_write(pdrv, pbuff, lba, 1);
+            if (dr == RES_OK) {
+                DEBUG_PRINT("[OK].\n");
+            } else {
+                DEBUG_PRINT("[FAIL].\n");
+                return 19;
+            }
+            DEBUG_PRINT(" disk_write(%u, 0x%X, %lu, 1)", pdrv, (UINT)(pbuff+sz_sect), lba2);
+            dr = disk_write(pdrv, pbuff+sz_sect, lba2, 1);
+            if (dr == RES_OK) {
+                DEBUG_PRINT("[OK].\n");
+            } else {
+                DEBUG_PRINT("[FAIL].\n");
+                return 20;
+            }
+            DEBUG_PRINT(" disk_ioctl(%u, CTRL_SYNC, NULL)", pdrv);
+            dr = disk_ioctl(pdrv, CTRL_SYNC, 0);
+            if (dr == RES_OK) {
+            DEBUG_PRINT("[OK].\n");
+            } else {
+                DEBUG_PRINT("[FAIL].\n");
+                return 21;
+            }
+            memset(pbuff, 0, sz_sect * 2);
+            DEBUG_PRINT(" disk_read(%u, 0x%X, %lu, 1)", pdrv, (UINT)pbuff, lba);
+            dr = disk_read(pdrv, pbuff, lba, 1);
+            if (dr == RES_OK) {
+                DEBUG_PRINT("[OK].\n");
+            } else {
+                DEBUG_PRINT("[FAIL].\n");
+                return 22;
+            }
+            DEBUG_PRINT(" disk_read(%u, 0x%X, %lu, 1)", pdrv, (UINT)(pbuff+sz_sect), lba2);
+            dr = disk_read(pdrv, pbuff+sz_sect, lba2, 1);
+            if (dr == RES_OK) {
+                DEBUG_PRINT("[OK].\n");
+            } else {
+                DEBUG_PRINT("[FAIL].\n");
+                return 23;
+            }
+            for (n = 0, pn(pns); pbuff[n] == (BYTE)pn(0) && n < (UINT)(sz_sect * 2); n++) ;
+            if (n == (UINT)(sz_sect * 2)) {
+                DEBUG_PRINT(" Data matched.\n");
+            } else {
+                DEBUG_PRINT("Failed: Read data differs from the data written.\n");
+                return 24;
+            }
+        } else {
+            DEBUG_PRINT(" Test skipped.\n");
+        }
+        pns++;
+
+        DEBUG_PRINT("**** Test cycle %u of %u completed ****\n\n", cc, ncyc);
+    }
+
+    return 0;
+}
+
diff --git a/crazyflie-firmware-src/src/lib/FatFS/ff.c b/crazyflie-firmware-src/src/lib/FatFS/ff.c
new file mode 100644
index 0000000000000000000000000000000000000000..0869614422c1659d1f3d15a1cbeba5b9e4c00b78
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/ff.c
@@ -0,0 +1,6041 @@
+/*----------------------------------------------------------------------------/
+/  FatFs - Generic FAT file system module  R0.12b                             /
+/-----------------------------------------------------------------------------/
+/
+/ Copyright (C) 2016, ChaN, all right reserved.
+/
+/ FatFs module is an open source software. Redistribution and use of FatFs in
+/ source and binary forms, with or without modification, are permitted provided
+/ that the following condition is met:
+
+/ 1. Redistributions of source code must retain the above copyright notice,
+/    this condition and the following disclaimer.
+/
+/ This software is provided by the copyright holder and contributors "AS IS"
+/ and any warranties related to this software are DISCLAIMED.
+/ The copyright owner or contributors be NOT LIABLE for any damages caused
+/ by use of this software.
+/----------------------------------------------------------------------------*/
+
+
+#include "ff.h"			/* Declarations of FatFs API */
+#include "diskio.h"		/* Declarations of device I/O functions */
+
+
+/*--------------------------------------------------------------------------
+
+   Module Private Definitions
+
+---------------------------------------------------------------------------*/
+
+#if _FATFS != 68020	/* Revision ID */
+#error Wrong include file (ff.h).
+#endif
+
+
+#define	ABORT(fs, res)		{ fp->err = (BYTE)(res); LEAVE_FF(fs, res); }
+
+
+/* Reentrancy related */
+#if _FS_REENTRANT
+#if _USE_LFN == 1
+#error Static LFN work area cannot be used at thread-safe configuration
+#endif
+#define	ENTER_FF(fs)		{ if (!lock_fs(fs)) return FR_TIMEOUT; }
+#define	LEAVE_FF(fs, res)	{ unlock_fs(fs, res); return res; }
+#else
+#define	ENTER_FF(fs)
+#define LEAVE_FF(fs, res)	return res
+#endif
+
+
+
+/* Definitions of sector size */
+#if (_MAX_SS < _MIN_SS) || (_MAX_SS != 512 && _MAX_SS != 1024 && _MAX_SS != 2048 && _MAX_SS != 4096) || (_MIN_SS != 512 && _MIN_SS != 1024 && _MIN_SS != 2048 && _MIN_SS != 4096)
+#error Wrong sector size configuration
+#endif
+#if _MAX_SS == _MIN_SS
+#define	SS(fs)	((UINT)_MAX_SS)	/* Fixed sector size */
+#else
+#define	SS(fs)	((fs)->ssize)	/* Variable sector size */
+#endif
+
+
+/* Timestamp */
+#if _FS_NORTC == 1
+#if _NORTC_YEAR < 1980 || _NORTC_YEAR > 2107 || _NORTC_MON < 1 || _NORTC_MON > 12 || _NORTC_MDAY < 1 || _NORTC_MDAY > 31
+#error Invalid _FS_NORTC settings
+#endif
+#define GET_FATTIME()	((DWORD)(_NORTC_YEAR - 1980) << 25 | (DWORD)_NORTC_MON << 21 | (DWORD)_NORTC_MDAY << 16)
+#else
+#define GET_FATTIME()	get_fattime()
+#endif
+
+
+/* File lock controls */
+#if _FS_LOCK != 0
+#if _FS_READONLY
+#error _FS_LOCK must be 0 at read-only configuration
+#endif
+typedef struct {
+	FATFS *fs;		/* Object ID 1, volume (NULL:blank entry) */
+	DWORD clu;		/* Object ID 2, directory (0:root) */
+	DWORD ofs;		/* Object ID 3, directory offset */
+	WORD ctr;		/* Object open counter, 0:none, 0x01..0xFF:read mode open count, 0x100:write mode */
+} FILESEM;
+#endif
+
+
+
+/* DBCS code ranges and SBCS upper conversion tables */
+
+#if _CODE_PAGE == 932	/* Japanese Shift-JIS */
+#define _DF1S	0x81	/* DBC 1st byte range 1 start */
+#define _DF1E	0x9F	/* DBC 1st byte range 1 end */
+#define _DF2S	0xE0	/* DBC 1st byte range 2 start */
+#define _DF2E	0xFC	/* DBC 1st byte range 2 end */
+#define _DS1S	0x40	/* DBC 2nd byte range 1 start */
+#define _DS1E	0x7E	/* DBC 2nd byte range 1 end */
+#define _DS2S	0x80	/* DBC 2nd byte range 2 start */
+#define _DS2E	0xFC	/* DBC 2nd byte range 2 end */
+
+#elif _CODE_PAGE == 936	/* Simplified Chinese GBK */
+#define _DF1S	0x81
+#define _DF1E	0xFE
+#define _DS1S	0x40
+#define _DS1E	0x7E
+#define _DS2S	0x80
+#define _DS2E	0xFE
+
+#elif _CODE_PAGE == 949	/* Korean */
+#define _DF1S	0x81
+#define _DF1E	0xFE
+#define _DS1S	0x41
+#define _DS1E	0x5A
+#define _DS2S	0x61
+#define _DS2E	0x7A
+#define _DS3S	0x81
+#define _DS3E	0xFE
+
+#elif _CODE_PAGE == 950	/* Traditional Chinese Big5 */
+#define _DF1S	0x81
+#define _DF1E	0xFE
+#define _DS1S	0x40
+#define _DS1E	0x7E
+#define _DS2S	0xA1
+#define _DS2E	0xFE
+
+#elif _CODE_PAGE == 437	/* U.S. */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x45,0x41,0x8E,0x41,0x8F,0x80,0x45,0x45,0x45,0x49,0x49,0x49,0x8E,0x8F, \
+				0x90,0x92,0x92,0x4F,0x99,0x4F,0x55,0x55,0x59,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 720	/* Arabic */
+#define _DF1S	0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0xA0,0xA1,0xA2,0xA3,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 737	/* Greek */
+#define _DF1S	0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0x90,0x92,0x92,0x93,0x94,0x95,0x96,0x97,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87, \
+				0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F,0x90,0x91,0xAA,0x92,0x93,0x94,0x95,0x96, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0x97,0xEA,0xEB,0xEC,0xE4,0xED,0xEE,0xEF,0xF5,0xF0,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 771	/* KBL */
+#define _DF1S	0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDC,0xDE,0xDE, \
+				0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0xF0,0xF0,0xF2,0xF2,0xF4,0xF4,0xF6,0xF6,0xF8,0xF8,0xFA,0xFA,0xFC,0xFC,0xFE,0xFF}
+
+#elif _CODE_PAGE == 775	/* Baltic */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x91,0xA0,0x8E,0x95,0x8F,0x80,0xAD,0xED,0x8A,0x8A,0xA1,0x8D,0x8E,0x8F, \
+				0x90,0x92,0x92,0xE2,0x99,0x95,0x96,0x97,0x97,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \
+				0xA0,0xA1,0xE0,0xA3,0xA3,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xB5,0xB6,0xB7,0xB8,0xBD,0xBE,0xC6,0xC7,0xA5,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE3,0xE8,0xE8,0xEA,0xEA,0xEE,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 850	/* Latin 1 */
+#define _DF1S	0
+#define _EXCVT {0x43,0x55,0x45,0x41,0x41,0x41,0x41,0x43,0x45,0x45,0x45,0x49,0x49,0x49,0x41,0x41, \
+				0x45,0x92,0x92,0x4F,0x4F,0x4F,0x55,0x55,0x59,0x4F,0x55,0x4F,0x9C,0x4F,0x9E,0x9F, \
+				0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0x41,0x41,0x41,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0x41,0x41,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD1,0xD1,0x45,0x45,0x45,0x49,0x49,0x49,0x49,0xD9,0xDA,0xDB,0xDC,0xDD,0x49,0xDF, \
+				0x4F,0xE1,0x4F,0x4F,0x4F,0x4F,0xE6,0xE8,0xE8,0x55,0x55,0x55,0x59,0x59,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 852	/* Latin 2 */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xDE,0x8F,0x80,0x9D,0xD3,0x8A,0x8A,0xD7,0x8D,0x8E,0x8F, \
+				0x90,0x91,0x91,0xE2,0x99,0x95,0x95,0x97,0x97,0x99,0x9A,0x9B,0x9B,0x9D,0x9E,0xAC, \
+				0xB5,0xD6,0xE0,0xE9,0xA4,0xA4,0xA6,0xA6,0xA8,0xA8,0xAA,0x8D,0xAC,0xB8,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBD,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC6,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD1,0xD1,0xD2,0xD3,0xD2,0xD5,0xD6,0xD7,0xB7,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE3,0xD5,0xE6,0xE6,0xE8,0xE9,0xE8,0xEB,0xED,0xED,0xDD,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xEB,0xFC,0xFC,0xFE,0xFF}
+
+#elif _CODE_PAGE == 855	/* Cyrillic */
+#define _DF1S	0
+#define _EXCVT {0x81,0x81,0x83,0x83,0x85,0x85,0x87,0x87,0x89,0x89,0x8B,0x8B,0x8D,0x8D,0x8F,0x8F, \
+				0x91,0x91,0x93,0x93,0x95,0x95,0x97,0x97,0x99,0x99,0x9B,0x9B,0x9D,0x9D,0x9F,0x9F, \
+				0xA1,0xA1,0xA3,0xA3,0xA5,0xA5,0xA7,0xA7,0xA9,0xA9,0xAB,0xAB,0xAD,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB6,0xB6,0xB8,0xB8,0xB9,0xBA,0xBB,0xBC,0xBE,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD1,0xD1,0xD3,0xD3,0xD5,0xD5,0xD7,0xD7,0xDD,0xD9,0xDA,0xDB,0xDC,0xDD,0xE0,0xDF, \
+				0xE0,0xE2,0xE2,0xE4,0xE4,0xE6,0xE6,0xE8,0xE8,0xEA,0xEA,0xEC,0xEC,0xEE,0xEE,0xEF, \
+				0xF0,0xF2,0xF2,0xF4,0xF4,0xF6,0xF6,0xF8,0xF8,0xFA,0xFA,0xFC,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 857	/* Turkish */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x90,0xB6,0x8E,0xB7,0x8F,0x80,0xD2,0xD3,0xD4,0xD8,0xD7,0x49,0x8E,0x8F, \
+				0x90,0x92,0x92,0xE2,0x99,0xE3,0xEA,0xEB,0x98,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9E, \
+				0xB5,0xD6,0xE0,0xE9,0xA5,0xA5,0xA6,0xA6,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC7,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0x49,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE5,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xDE,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 860	/* Portuguese */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x90,0x8F,0x8E,0x91,0x86,0x80,0x89,0x89,0x92,0x8B,0x8C,0x98,0x8E,0x8F, \
+				0x90,0x91,0x92,0x8C,0x99,0xA9,0x96,0x9D,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0x86,0x8B,0x9F,0x96,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 861	/* Icelandic */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x90,0x41,0x8E,0x41,0x8F,0x80,0x45,0x45,0x45,0x8B,0x8B,0x8D,0x8E,0x8F, \
+				0x90,0x92,0x92,0x4F,0x99,0x8D,0x55,0x97,0x97,0x99,0x9A,0x9D,0x9C,0x9D,0x9E,0x9F, \
+				0xA4,0xA5,0xA6,0xA7,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 862	/* Hebrew */
+#define _DF1S	0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 863	/* Canadian-French */
+#define _DF1S	0
+#define _EXCVT {0x43,0x55,0x45,0x41,0x41,0x41,0x86,0x43,0x45,0x45,0x45,0x49,0x49,0x8D,0x41,0x8F, \
+				0x45,0x45,0x45,0x4F,0x45,0x49,0x55,0x55,0x98,0x4F,0x55,0x9B,0x9C,0x55,0x55,0x9F, \
+				0xA0,0xA1,0x4F,0x55,0xA4,0xA5,0xA6,0xA7,0x49,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 864	/* Arabic */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x45,0x41,0x8E,0x41,0x8F,0x80,0x45,0x45,0x45,0x49,0x49,0x49,0x8E,0x8F, \
+				0x90,0x92,0x92,0x4F,0x99,0x4F,0x55,0x55,0x59,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 865	/* Nordic */
+#define _DF1S	0
+#define _EXCVT {0x80,0x9A,0x90,0x41,0x8E,0x41,0x8F,0x80,0x45,0x45,0x45,0x49,0x49,0x49,0x8E,0x8F, \
+				0x90,0x92,0x92,0x4F,0x99,0x4F,0x55,0x55,0x59,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0x41,0x49,0x4F,0x55,0xA5,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0xE0,0xE1,0xE2,0xE3,0xE4,0xE5,0xE6,0xE7,0xE8,0xE9,0xEA,0xEB,0xEC,0xED,0xEE,0xEF, \
+				0xF0,0xF1,0xF2,0xF3,0xF4,0xF5,0xF6,0xF7,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 866	/* Russian */
+#define _DF1S	0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xD6,0xD7,0xD8,0xD9,0xDA,0xDB,0xDC,0xDD,0xDE,0xDF, \
+				0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x9B,0x9C,0x9D,0x9E,0x9F, \
+				0xF0,0xF0,0xF2,0xF2,0xF4,0xF4,0xF6,0xF6,0xF8,0xF9,0xFA,0xFB,0xFC,0xFD,0xFE,0xFF}
+
+#elif _CODE_PAGE == 869	/* Greek 2 */
+#define _DF1S	0
+#define _EXCVT {0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x8A,0x8B,0x8C,0x8D,0x8E,0x8F, \
+				0x90,0x91,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9A,0x86,0x9C,0x8D,0x8F,0x90, \
+				0x91,0x90,0x92,0x95,0xA4,0xA5,0xA6,0xA7,0xA8,0xA9,0xAA,0xAB,0xAC,0xAD,0xAE,0xAF, \
+				0xB0,0xB1,0xB2,0xB3,0xB4,0xB5,0xB6,0xB7,0xB8,0xB9,0xBA,0xBB,0xBC,0xBD,0xBE,0xBF, \
+				0xC0,0xC1,0xC2,0xC3,0xC4,0xC5,0xC6,0xC7,0xC8,0xC9,0xCA,0xCB,0xCC,0xCD,0xCE,0xCF, \
+				0xD0,0xD1,0xD2,0xD3,0xD4,0xD5,0xA4,0xA5,0xA6,0xD9,0xDA,0xDB,0xDC,0xA7,0xA8,0xDF, \
+				0xA9,0xAA,0xAC,0xAD,0xB5,0xB6,0xB7,0xB8,0xBD,0xBE,0xC6,0xC7,0xCF,0xCF,0xD0,0xEF, \
+				0xF0,0xF1,0xD1,0xD2,0xD3,0xF5,0xD4,0xF7,0xF8,0xF9,0xD5,0x96,0x95,0x98,0xFE,0xFF}
+
+#elif _CODE_PAGE == 1	/* ASCII (for only non-LFN cfg) */
+#if _USE_LFN != 0
+#error Cannot enable LFN without valid code page.
+#endif
+#define _DF1S	0
+
+#else
+#error Unknown code page
+
+#endif
+
+
+/* Character code support macros */
+#define IsUpper(c)	(((c)>='A')&&((c)<='Z'))
+#define IsLower(c)	(((c)>='a')&&((c)<='z'))
+#define IsDigit(c)	(((c)>='0')&&((c)<='9'))
+
+#if _DF1S != 0	/* Code page is DBCS */
+
+#ifdef _DF2S	/* Two 1st byte areas */
+#define IsDBCS1(c)	(((BYTE)(c) >= _DF1S && (BYTE)(c) <= _DF1E) || ((BYTE)(c) >= _DF2S && (BYTE)(c) <= _DF2E))
+#else			/* One 1st byte area */
+#define IsDBCS1(c)	((BYTE)(c) >= _DF1S && (BYTE)(c) <= _DF1E)
+#endif
+
+#ifdef _DS3S	/* Three 2nd byte areas */
+#define IsDBCS2(c)	(((BYTE)(c) >= _DS1S && (BYTE)(c) <= _DS1E) || ((BYTE)(c) >= _DS2S && (BYTE)(c) <= _DS2E) || ((BYTE)(c) >= _DS3S && (BYTE)(c) <= _DS3E))
+#else			/* Two 2nd byte areas */
+#define IsDBCS2(c)	(((BYTE)(c) >= _DS1S && (BYTE)(c) <= _DS1E) || ((BYTE)(c) >= _DS2S && (BYTE)(c) <= _DS2E))
+#endif
+
+#else			/* Code page is SBCS */
+
+#define IsDBCS1(c)	0
+#define IsDBCS2(c)	0
+
+#endif /* _DF1S */
+
+
+/* File attribute bits (internal use) */
+#define	AM_VOL		0x08	/* Volume label */
+#define AM_LFN		0x0F	/* LFN entry */
+#define AM_MASK		0x3F	/* Mask of defined bits */
+
+
+/* File access control and file status flags (internal use) */
+#define FA_SEEKEND	0x20	/* Seek to end of the file on file open */
+#define FA_MODIFIED	0x40	/* File has been modified */
+#define FA_DIRTY	0x80	/* FIL.buf[] needs to be written-back */
+
+
+/* Name status flags */
+#define NSFLAG		11		/* Index of name status byte in fn[] */
+#define NS_LOSS		0x01	/* Out of 8.3 format */
+#define NS_LFN		0x02	/* Force to create LFN entry */
+#define NS_LAST		0x04	/* Last segment */
+#define NS_BODY		0x08	/* Lower case flag (body) */
+#define NS_EXT		0x10	/* Lower case flag (ext) */
+#define NS_DOT		0x20	/* Dot entry */
+#define NS_NOLFN	0x40	/* Do not find LFN */
+#define NS_NONAME	0x80	/* Not followed */
+
+
+/* Limits and boundaries (differ from specs but correct for real DOS/Windows) */
+#define MAX_FAT12	0xFF5			/* Maximum number of FAT12 clusters */
+#define	MAX_FAT16	0xFFF5			/* Maximum number of FAT16 clusters */
+#define	MAX_FAT32	0xFFFFFF5		/* Maximum number of FAT32 clusters */
+#define	MAX_EXFAT	0x7FFFFFFD		/* Maximum number of exFAT clusters (limited by implementation) */
+#define MAX_DIR		0x200000		/* Maximum size of FAT directory */
+#define MAX_DIR_EX	0x10000000		/* Maximum size of exFAT directory */
+
+
+/* FatFs refers the members in the FAT structures as byte array instead of
+/ structure members because the structure is not binary compatible between
+/ different platforms */
+
+#define BS_JmpBoot			0		/* x86 jump instruction (3-byte) */
+#define BS_OEMName			3		/* OEM name (8-byte) */
+#define BPB_BytsPerSec		11		/* Sector size [byte] (WORD) */
+#define BPB_SecPerClus		13		/* Cluster size [sector] (BYTE) */
+#define BPB_RsvdSecCnt		14		/* Size of reserved area [sector] (WORD) */
+#define BPB_NumFATs			16		/* Number of FATs (BYTE) */
+#define BPB_RootEntCnt		17		/* Size of root directory area for FAT12/16 [entry] (WORD) */
+#define BPB_TotSec16		19		/* Volume size (16-bit) [sector] (WORD) */
+#define BPB_Media			21		/* Media descriptor byte (BYTE) */
+#define BPB_FATSz16			22		/* FAT size (16-bit) [sector] (WORD) */
+#define BPB_SecPerTrk		24		/* Track size for int13h [sector] (WORD) */
+#define BPB_NumHeads		26		/* Number of heads for int13h (WORD) */
+#define BPB_HiddSec			28		/* Volume offset from top of the drive (DWORD) */
+#define BPB_TotSec32		32		/* Volume size (32-bit) [sector] (DWORD) */
+#define BS_DrvNum			36		/* Physical drive number for int13h (BYTE) */
+#define BS_NTres			37		/* Error flag (BYTE) */
+#define BS_BootSig			38		/* Extended boot signature (BYTE) */
+#define BS_VolID			39		/* Volume serial number (DWORD) */
+#define BS_VolLab			43		/* Volume label string (8-byte) */
+#define BS_FilSysType		54		/* File system type string (8-byte) */
+#define BS_BootCode			62		/* Boot code (448-byte) */
+#define BS_55AA				510		/* Signature word (WORD) */
+
+#define BPB_FATSz32			36		/* FAT32: FAT size [sector] (DWORD) */
+#define BPB_ExtFlags32		40		/* FAT32: Extended flags (WORD) */
+#define BPB_FSVer32			42		/* FAT32: File system version (WORD) */
+#define BPB_RootClus32		44		/* FAT32: Root directory cluster (DWORD) */
+#define BPB_FSInfo32		48		/* FAT32: Offset of FSINFO sector (WORD) */
+#define BPB_BkBootSec32		50		/* FAT32: Offset of backup boot sector (WORD) */
+#define BS_DrvNum32			64		/* FAT32: Physical drive number for int13h (BYTE) */
+#define BS_NTres32			65		/* FAT32: Error flag (BYTE) */
+#define BS_BootSig32		66		/* FAT32: Extended boot signature (BYTE) */
+#define BS_VolID32			67		/* FAT32: Volume serial number (DWORD) */
+#define BS_VolLab32			71		/* FAT32: Volume label string (8-byte) */
+#define BS_FilSysType32		82		/* FAT32: File system type string (8-byte) */
+#define BS_BootCode32		90		/* FAT32: Boot code (420-byte) */
+
+#define BPB_ZeroedEx		11		/* exFAT: MBZ field (53-byte) */
+#define BPB_VolOfsEx		64		/* exFAT: Volume offset from top of the drive [sector] (QWORD) */
+#define BPB_TotSecEx		72		/* exFAT: Volume size [sector] (QWORD) */
+#define BPB_FatOfsEx		80		/* exFAT: FAT offset from top of the volume [sector] (DWORD) */
+#define BPB_FatSzEx			84		/* exFAT: FAT size [sector] (DWORD) */
+#define BPB_DataOfsEx		88		/* exFAT: Data offset from top of the volume [sector] (DWORD) */
+#define BPB_NumClusEx		92		/* exFAT: Number of clusters (DWORD) */
+#define BPB_RootClusEx		96		/* exFAT: Root directory cluster (DWORD) */
+#define BPB_VolIDEx			100		/* exFAT: Volume serial number (DWORD) */
+#define BPB_FSVerEx			104		/* exFAT: File system version (WORD) */
+#define BPB_VolFlagEx		106		/* exFAT: Volume flags (BYTE) */
+#define BPB_ActFatEx		107		/* exFAT: Active FAT flags (BYTE) */
+#define BPB_BytsPerSecEx	108		/* exFAT: Log2 of sector size in byte (BYTE) */
+#define BPB_SecPerClusEx	109		/* exFAT: Log2 of cluster size in sector (BYTE) */
+#define BPB_NumFATsEx		110		/* exFAT: Number of FATs (BYTE) */
+#define BPB_DrvNumEx		111		/* exFAT: Physical drive number for int13h (BYTE) */
+#define BPB_PercInUseEx		112		/* exFAT: Percent in use (BYTE) */
+#define	BPB_RsvdEx			113		/* exFAT: Reserved (7-byte) */
+#define BS_BootCodeEx		120		/* exFAT: Boot code (390-byte) */
+
+#define	FSI_LeadSig			0		/* FAT32 FSI: Leading signature (DWORD) */
+#define	FSI_StrucSig		484		/* FAT32 FSI: Structure signature (DWORD) */
+#define	FSI_Free_Count		488		/* FAT32 FSI: Number of free clusters (DWORD) */
+#define	FSI_Nxt_Free		492		/* FAT32 FSI: Last allocated cluster (DWORD) */
+
+#define MBR_Table			446		/* MBR: Offset of partition table in the MBR */
+#define	SZ_PTE				16		/* MBR: Size of a partition table entry */
+#define PTE_Boot			0		/* MBR PTE: Boot indicator */
+#define PTE_StHead			1		/* MBR PTE: Start head */
+#define PTE_StSec			2		/* MBR PTE: Start sector */
+#define PTE_StCyl			3		/* MBR PTE: Start cylinder */
+#define PTE_System			4		/* MBR PTE: System ID */
+#define PTE_EdHead			5		/* MBR PTE: End head */
+#define PTE_EdSec			6		/* MBR PTE: End sector */
+#define PTE_EdCyl			7		/* MBR PTE: End cylinder */
+#define PTE_StLba			8		/* MBR PTE: Start in LBA */
+#define PTE_SizLba			12		/* MBR PTE: Size in LBA */
+
+#define	DIR_Name			0		/* Short file name (11-byte) */
+#define	DIR_Attr			11		/* Attribute (BYTE) */
+#define	DIR_NTres			12		/* Lower case flag (BYTE) */
+#define DIR_CrtTime10		13		/* Created time sub-second (BYTE) */
+#define	DIR_CrtTime			14		/* Created time (DWORD) */
+#define DIR_LstAccDate		18		/* Last accessed date (WORD) */
+#define	DIR_FstClusHI		20		/* Higher 16-bit of first cluster (WORD) */
+#define	DIR_ModTime			22		/* Modified time (DWORD) */
+#define	DIR_FstClusLO		26		/* Lower 16-bit of first cluster (WORD) */
+#define	DIR_FileSize		28		/* File size (DWORD) */
+#define	LDIR_Ord			0		/* LFN entry order and LLE flag (BYTE) */
+#define	LDIR_Attr			11		/* LFN attribute (BYTE) */
+#define	LDIR_Type			12		/* LFN type (BYTE) */
+#define	LDIR_Chksum			13		/* Checksum of the SFN entry (BYTE) */
+#define	LDIR_FstClusLO		26		/* Must be zero (WORD) */
+#define	XDIR_Type			0		/* Type of exFAT directory entry (BYTE) */
+#define	XDIR_NumLabel		1		/* Number of volume label characters (BYTE) */
+#define	XDIR_Label			2		/* Volume label (11-WORD) */
+#define	XDIR_CaseSum		4		/* Sum of case conversion table (DWORD) */
+#define	XDIR_NumSec			1		/* Number of secondary entries (BYTE) */
+#define	XDIR_SetSum			2		/* Sum of the set of directory entries (WORD) */
+#define	XDIR_Attr			4		/* File attribute (WORD) */
+#define	XDIR_CrtTime		8		/* Created time (DWORD) */
+#define	XDIR_ModTime		12		/* Modified time (DWORD) */
+#define	XDIR_AccTime		16		/* Last accessed time (DWORD) */
+#define	XDIR_CrtTime10		20		/* Created time subsecond (BYTE) */
+#define	XDIR_ModTime10		21		/* Modified time subsecond (BYTE) */
+#define	XDIR_CrtTZ			22		/* Created timezone (BYTE) */
+#define	XDIR_ModTZ			23		/* Modified timezone (BYTE) */
+#define	XDIR_AccTZ			24		/* Last accessed timezone (BYTE) */
+#define	XDIR_GenFlags		33		/* Gneral secondary flags (WORD) */
+#define	XDIR_NumName		35		/* Number of file name characters (BYTE) */
+#define	XDIR_NameHash		36		/* Hash of file name (WORD) */
+#define XDIR_ValidFileSize	40		/* Valid file size (QWORD) */
+#define	XDIR_FstClus		52		/* First cluster of the file data (DWORD) */
+#define	XDIR_FileSize		56		/* File/Directory size (QWORD) */
+
+#define	SZDIRE				32		/* Size of a directory entry */
+#define	LLEF				0x40	/* Last long entry flag in LDIR_Ord */
+#define	DDEM				0xE5	/* Deleted directory entry mark set to DIR_Name[0] */
+#define	RDDEM				0x05	/* Replacement of the character collides with DDEM */
+
+
+
+
+
+/*--------------------------------------------------------------------------
+
+   Module Private Work Area
+
+---------------------------------------------------------------------------*/
+
+/* Remark: Variables here without initial value shall be guaranteed zero/null
+/  at start-up. If not, either the linker or start-up routine being used is
+/  not compliance with C standard. */
+
+#if _VOLUMES < 1 || _VOLUMES > 9
+#error Wrong _VOLUMES setting
+#endif
+static FATFS *FatFs[_VOLUMES];	/* Pointer to the file system objects (logical drives) */
+static WORD Fsid;				/* File system mount ID */
+
+#if _FS_RPATH != 0 && _VOLUMES >= 2
+static BYTE CurrVol;			/* Current drive */
+#endif
+
+#if _FS_LOCK != 0
+static FILESEM Files[_FS_LOCK];	/* Open object lock semaphores */
+#endif
+
+#if _USE_LFN == 0			/* Non-LFN configuration */
+#define	DEF_NAMBUF
+#define INIT_NAMBUF(fs)
+#define	FREE_NAMBUF()
+#else
+#if _MAX_LFN < 12 || _MAX_LFN > 255
+#error Wrong _MAX_LFN setting
+#endif
+
+#if _USE_LFN == 1		/* LFN enabled with static working buffer */
+#if _FS_EXFAT
+static BYTE	DirBuf[SZDIRE*19];	/* Directory entry block scratchpad buffer (19 entries in size) */
+#endif
+static WCHAR LfnBuf[_MAX_LFN+1];	/* LFN enabled with static working buffer */
+#define	DEF_NAMBUF
+#define INIT_NAMBUF(fs)
+#define	FREE_NAMBUF()
+
+#elif _USE_LFN == 2 	/* LFN enabled with dynamic working buffer on the stack */
+#if _FS_EXFAT
+#define	DEF_NAMBUF		WCHAR lbuf[_MAX_LFN+1]; BYTE dbuf[SZDIRE*19];
+#define INIT_NAMBUF(fs)	{ (fs)->lfnbuf = lbuf; (fs)->dirbuf = dbuf; }
+#define	FREE_NAMBUF()
+#else
+#define	DEF_NAMBUF		WCHAR lbuf[_MAX_LFN+1];
+#define INIT_NAMBUF(fs)	{ (fs)->lfnbuf = lbuf; }
+#define	FREE_NAMBUF()
+#endif
+
+#elif _USE_LFN == 3 	/* LFN enabled with dynamic working buffer on the heap */
+#if _FS_EXFAT
+#define	DEF_NAMBUF		WCHAR *lfn;
+#define INIT_NAMBUF(fs)	{ lfn = ff_memalloc((_MAX_LFN+1)*2 + SZDIRE*19); if (!lfn) LEAVE_FF(fs, FR_NOT_ENOUGH_CORE); (fs)->lfnbuf = lfn; (fs)->dirbuf = (BYTE*)(lfn+_MAX_LFN+1); }
+#define	FREE_NAMBUF()	ff_memfree(lfn)
+#else
+#define	DEF_NAMBUF		WCHAR *lfn;
+#define INIT_NAMBUF(fs)	{ lfn = ff_memalloc((_MAX_LFN+1)*2); if (!lfn) LEAVE_FF(fs, FR_NOT_ENOUGH_CORE); (fs)->lfnbuf = lfn; }
+#define	FREE_NAMBUF()	ff_memfree(lfn)
+#endif
+
+#else
+#error Wrong _USE_LFN setting
+#endif
+#endif
+
+#ifdef _EXCVT
+static const BYTE ExCvt[] = _EXCVT;	/* Upper conversion table for SBCS extended characters */
+#endif
+
+
+
+
+
+
+/*--------------------------------------------------------------------------
+
+   Module Private Functions
+
+---------------------------------------------------------------------------*/
+
+
+/*-----------------------------------------------------------------------*/
+/* Load/Store multi-byte word in the FAT structure                       */
+/*-----------------------------------------------------------------------*/
+
+static
+WORD ld_word (const BYTE* ptr)	/*	 Load a 2-byte little-endian word */
+{
+	WORD rv;
+
+	rv = ptr[1];
+	rv = rv << 8 | ptr[0];
+	return rv;
+}
+
+static
+DWORD ld_dword (const BYTE* ptr)	/* Load a 4-byte little-endian word */
+{
+	DWORD rv;
+
+	rv = ptr[3];
+	rv = rv << 8 | ptr[2];
+	rv = rv << 8 | ptr[1];
+	rv = rv << 8 | ptr[0];
+	return rv;
+}
+
+#if _FS_EXFAT
+static
+QWORD ld_qword (const BYTE* ptr)	/* Load an 8-byte little-endian word */
+{
+	QWORD rv;
+
+	rv = ptr[7];
+	rv = rv << 8 | ptr[6];
+	rv = rv << 8 | ptr[5];
+	rv = rv << 8 | ptr[4];
+	rv = rv << 8 | ptr[3];
+	rv = rv << 8 | ptr[2];
+	rv = rv << 8 | ptr[1];
+	rv = rv << 8 | ptr[0];
+	return rv;
+}
+#endif
+
+#if !_FS_READONLY
+static
+void st_word (BYTE* ptr, WORD val)	/* Store a 2-byte word in little-endian */
+{
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val;
+}
+
+static
+void st_dword (BYTE* ptr, DWORD val)	/* Store a 4-byte word in little-endian */
+{
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val;
+}
+
+#if _FS_EXFAT
+static
+void st_qword (BYTE* ptr, QWORD val)	/* Store an 8-byte word in little-endian */
+{
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val; val >>= 8;
+	*ptr++ = (BYTE)val;
+}
+#endif
+#endif	/* !_FS_READONLY */
+
+
+
+/*-----------------------------------------------------------------------*/
+/* String functions                                                      */
+/*-----------------------------------------------------------------------*/
+
+/* Copy memory to memory */
+static
+void mem_cpy (void* dst, const void* src, UINT cnt) {
+	BYTE *d = (BYTE*)dst;
+	const BYTE *s = (const BYTE*)src;
+
+	if (cnt) {
+		do *d++ = *s++; while (--cnt);
+	}
+}
+
+/* Fill memory block */
+static
+void mem_set (void* dst, int val, UINT cnt) {
+	BYTE *d = (BYTE*)dst;
+
+	do *d++ = (BYTE)val; while (--cnt);
+}
+
+/* Compare memory block */
+static
+int mem_cmp (const void* dst, const void* src, UINT cnt) {	/* ZR:same, NZ:different */
+	const BYTE *d = (const BYTE *)dst, *s = (const BYTE *)src;
+	int r = 0;
+
+	do {
+		r = *d++ - *s++;
+	} while (--cnt && r == 0);
+
+	return r;
+}
+
+/* Check if chr is contained in the string */
+static
+int chk_chr (const char* str, int chr) {	/* NZ:contained, ZR:not contained */
+	while (*str && *str != chr) str++;
+	return *str;
+}
+
+
+
+
+#if _FS_REENTRANT
+/*-----------------------------------------------------------------------*/
+/* Request/Release grant to access the volume                            */
+/*-----------------------------------------------------------------------*/
+static
+int lock_fs (
+	FATFS* fs		/* File system object */
+)
+{
+	return ff_req_grant(fs->sobj);
+}
+
+
+static
+void unlock_fs (
+	FATFS* fs,		/* File system object */
+	FRESULT res		/* Result code to be returned */
+)
+{
+	if (fs && res != FR_NOT_ENABLED && res != FR_INVALID_DRIVE && res != FR_TIMEOUT) {
+		ff_rel_grant(fs->sobj);
+	}
+}
+
+#endif
+
+
+
+#if _FS_LOCK != 0
+/*-----------------------------------------------------------------------*/
+/* File lock control functions                                           */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT chk_lock (	/* Check if the file can be accessed */
+	DIR* dp,		/* Directory object pointing the file to be checked */
+	int acc			/* Desired access type (0:Read, 1:Write, 2:Delete/Rename) */
+)
+{
+	UINT i, be;
+
+	/* Search file semaphore table */
+	for (i = be = 0; i < _FS_LOCK; i++) {
+		if (Files[i].fs) {	/* Existing entry */
+			if (Files[i].fs == dp->obj.fs &&	 	/* Check if the object matched with an open object */
+				Files[i].clu == dp->obj.sclust &&
+				Files[i].ofs == dp->dptr) break;
+		} else {			/* Blank entry */
+			be = 1;
+		}
+	}
+	if (i == _FS_LOCK) {	/* The object is not opened */
+		return (be || acc == 2) ? FR_OK : FR_TOO_MANY_OPEN_FILES;	/* Is there a blank entry for new object? */
+	}
+
+	/* The object has been opened. Reject any open against writing file and all write mode open */
+	return (acc || Files[i].ctr == 0x100) ? FR_LOCKED : FR_OK;
+}
+
+
+static
+int enq_lock (void)	/* Check if an entry is available for a new object */
+{
+	UINT i;
+
+	for (i = 0; i < _FS_LOCK && Files[i].fs; i++) ;
+	return (i == _FS_LOCK) ? 0 : 1;
+}
+
+
+static
+UINT inc_lock (	/* Increment object open counter and returns its index (0:Internal error) */
+	DIR* dp,	/* Directory object pointing the file to register or increment */
+	int acc		/* Desired access (0:Read, 1:Write, 2:Delete/Rename) */
+)
+{
+	UINT i;
+
+
+	for (i = 0; i < _FS_LOCK; i++) {	/* Find the object */
+		if (Files[i].fs == dp->obj.fs &&
+			Files[i].clu == dp->obj.sclust &&
+			Files[i].ofs == dp->dptr) break;
+	}
+
+	if (i == _FS_LOCK) {				/* Not opened. Register it as new. */
+		for (i = 0; i < _FS_LOCK && Files[i].fs; i++) ;
+		if (i == _FS_LOCK) return 0;	/* No free entry to register (int err) */
+		Files[i].fs = dp->obj.fs;
+		Files[i].clu = dp->obj.sclust;
+		Files[i].ofs = dp->dptr;
+		Files[i].ctr = 0;
+	}
+
+	if (acc && Files[i].ctr) return 0;	/* Access violation (int err) */
+
+	Files[i].ctr = acc ? 0x100 : Files[i].ctr + 1;	/* Set semaphore value */
+
+	return i + 1;
+}
+
+
+static
+FRESULT dec_lock (	/* Decrement object open counter */
+	UINT i			/* Semaphore index (1..) */
+)
+{
+	WORD n;
+	FRESULT res;
+
+
+	if (--i < _FS_LOCK) {	/* Shift index number origin from 0 */
+		n = Files[i].ctr;
+		if (n == 0x100) n = 0;		/* If write mode open, delete the entry */
+		if (n > 0) n--;				/* Decrement read mode open count */
+		Files[i].ctr = n;
+		if (n == 0) Files[i].fs = 0;	/* Delete the entry if open count gets zero */
+		res = FR_OK;
+	} else {
+		res = FR_INT_ERR;			/* Invalid index nunber */
+	}
+	return res;
+}
+
+
+static
+void clear_lock (	/* Clear lock entries of the volume */
+	FATFS *fs
+)
+{
+	UINT i;
+
+	for (i = 0; i < _FS_LOCK; i++) {
+		if (Files[i].fs == fs) Files[i].fs = 0;
+	}
+}
+
+#endif	/* _FS_LOCK != 0 */
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Move/Flush disk access window in the file system object               */
+/*-----------------------------------------------------------------------*/
+#if !_FS_READONLY
+static
+FRESULT sync_window (	/* Returns FR_OK or FR_DISK_ERROR */
+	FATFS* fs			/* File system object */
+)
+{
+	DWORD wsect;
+	UINT nf;
+	FRESULT res = FR_OK;
+
+
+	if (fs->wflag) {	/* Write back the sector if it is dirty */
+		wsect = fs->winsect;	/* Current sector number */
+		if (disk_write(fs->drv, fs->win, wsect, 1) != RES_OK) {
+			res = FR_DISK_ERR;
+		} else {
+			fs->wflag = 0;
+			if (wsect - fs->fatbase < fs->fsize) {		/* Is it in the FAT area? */
+				for (nf = fs->n_fats; nf >= 2; nf--) {	/* Reflect the change to all FAT copies */
+					wsect += fs->fsize;
+					disk_write(fs->drv, fs->win, wsect, 1);
+				}
+			}
+		}
+	}
+	return res;
+}
+#endif
+
+
+static
+FRESULT move_window (	/* Returns FR_OK or FR_DISK_ERROR */
+	FATFS* fs,			/* File system object */
+	DWORD sector		/* Sector number to make appearance in the fs->win[] */
+)
+{
+	FRESULT res = FR_OK;
+
+
+	if (sector != fs->winsect) {	/* Window offset changed? */
+#if !_FS_READONLY
+		res = sync_window(fs);		/* Write-back changes */
+#endif
+		if (res == FR_OK) {			/* Fill sector window with new data */
+			if (disk_read(fs->drv, fs->win, sector, 1) != RES_OK) {
+				sector = 0xFFFFFFFF;	/* Invalidate window if data is not reliable */
+				res = FR_DISK_ERR;
+			}
+			fs->winsect = sector;
+		}
+	}
+	return res;
+}
+
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Synchronize file system and strage device                             */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT sync_fs (	/* FR_OK:succeeded, !=0:error */
+	FATFS* fs		/* File system object */
+)
+{
+	FRESULT res;
+
+
+	res = sync_window(fs);
+	if (res == FR_OK) {
+		/* Update FSInfo sector if needed */
+		if (fs->fs_type == FS_FAT32 && fs->fsi_flag == 1) {
+			/* Create FSInfo structure */
+			mem_set(fs->win, 0, SS(fs));
+			st_word(fs->win + BS_55AA, 0xAA55);
+			st_dword(fs->win + FSI_LeadSig, 0x41615252);
+			st_dword(fs->win + FSI_StrucSig, 0x61417272);
+			st_dword(fs->win + FSI_Free_Count, fs->free_clst);
+			st_dword(fs->win + FSI_Nxt_Free, fs->last_clst);
+			/* Write it into the FSInfo sector */
+			fs->winsect = fs->volbase + 1;
+			disk_write(fs->drv, fs->win, fs->winsect, 1);
+			fs->fsi_flag = 0;
+		}
+		/* Make sure that no pending write process in the physical drive */
+		if (disk_ioctl(fs->drv, CTRL_SYNC, 0) != RES_OK) res = FR_DISK_ERR;
+	}
+
+	return res;
+}
+
+#endif
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Get sector# from cluster#                                             */
+/*-----------------------------------------------------------------------*/
+
+static
+DWORD clust2sect (	/* !=0:Sector number, 0:Failed (invalid cluster#) */
+	FATFS* fs,		/* File system object */
+	DWORD clst		/* Cluster# to be converted */
+)
+{
+	clst -= 2;
+	if (clst >= fs->n_fatent - 2) return 0;		/* Invalid cluster# */
+	return clst * fs->csize + fs->database;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* FAT access - Read value of a FAT entry                                */
+/*-----------------------------------------------------------------------*/
+
+static
+DWORD get_fat (	/* 0xFFFFFFFF:Disk error, 1:Internal error, 2..0x7FFFFFFF:Cluster status */
+	_FDID* obj,	/* Corresponding object */
+	DWORD clst	/* Cluster number to get the value */
+)
+{
+	UINT wc, bc;
+	DWORD val;
+	FATFS *fs = obj->fs;
+
+
+	if (clst < 2 || clst >= fs->n_fatent) {	/* Check if in valid range */
+		val = 1;	/* Internal error */
+
+	} else {
+		val = 0xFFFFFFFF;	/* Default value falls on disk error */
+
+		switch (fs->fs_type) {
+		case FS_FAT12 :
+			bc = (UINT)clst; bc += bc / 2;
+			if (move_window(fs, fs->fatbase + (bc / SS(fs))) != FR_OK) break;
+			wc = fs->win[bc++ % SS(fs)];
+			if (move_window(fs, fs->fatbase + (bc / SS(fs))) != FR_OK) break;
+			wc |= fs->win[bc % SS(fs)] << 8;
+			val = (clst & 1) ? (wc >> 4) : (wc & 0xFFF);
+			break;
+
+		case FS_FAT16 :
+			if (move_window(fs, fs->fatbase + (clst / (SS(fs) / 2))) != FR_OK) break;
+			val = ld_word(fs->win + clst * 2 % SS(fs));
+			break;
+
+		case FS_FAT32 :
+			if (move_window(fs, fs->fatbase + (clst / (SS(fs) / 4))) != FR_OK) break;
+			val = ld_dword(fs->win + clst * 4 % SS(fs)) & 0x0FFFFFFF;
+			break;
+#if _FS_EXFAT
+		case FS_EXFAT :
+			if (obj->objsize) {
+				DWORD cofs = clst - obj->sclust;	/* Offset from start cluster */
+				DWORD clen = (DWORD)((obj->objsize - 1) / SS(fs)) / fs->csize;	/* Number of clusters - 1 */
+
+				if (obj->stat == 2) {	/* Is there no valid chain on the FAT? */
+					if (cofs <= clen) {
+						val = (cofs == clen) ? 0x7FFFFFFF : clst + 1;	/* Generate the value */
+						break;
+					}
+				}
+				if (obj->stat == 3 && cofs < obj->n_cont) {	/* Is it in the contiguous part? */
+					val = clst + 1; 	/* Generate the value */
+					break;
+				}
+				if (obj->stat != 2) {	/* Get value from FAT if FAT chain is valid */
+					if (move_window(fs, fs->fatbase + (clst / (SS(fs) / 4))) != FR_OK) break;
+					val = ld_dword(fs->win + clst * 4 % SS(fs)) & 0x7FFFFFFF;
+					break;
+				}
+			}
+			/* go next */
+#endif
+		default:
+			val = 1;	/* Internal error */
+		}
+	}
+
+	return val;
+}
+
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* FAT access - Change value of a FAT entry                              */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT put_fat (	/* FR_OK(0):succeeded, !=0:error */
+	FATFS* fs,		/* Corresponding file system object */
+	DWORD clst,		/* FAT index number (cluster number) to be changed */
+	DWORD val		/* New value to be set to the entry */
+)
+{
+	UINT bc;
+	BYTE *p;
+	FRESULT res = FR_INT_ERR;
+
+
+	if (clst >= 2 && clst < fs->n_fatent) {	/* Check if in valid range */
+		switch (fs->fs_type) {
+		case FS_FAT12 :	/* Bitfield items */
+			bc = (UINT)clst; bc += bc / 2;
+			res = move_window(fs, fs->fatbase + (bc / SS(fs)));
+			if (res != FR_OK) break;
+			p = fs->win + bc++ % SS(fs);
+			*p = (clst & 1) ? ((*p & 0x0F) | ((BYTE)val << 4)) : (BYTE)val;
+			fs->wflag = 1;
+			res = move_window(fs, fs->fatbase + (bc / SS(fs)));
+			if (res != FR_OK) break;
+			p = fs->win + bc % SS(fs);
+			*p = (clst & 1) ? (BYTE)(val >> 4) : ((*p & 0xF0) | ((BYTE)(val >> 8) & 0x0F));
+			fs->wflag = 1;
+			break;
+
+		case FS_FAT16 :	/* WORD aligned items */
+			res = move_window(fs, fs->fatbase + (clst / (SS(fs) / 2)));
+			if (res != FR_OK) break;
+			st_word(fs->win + clst * 2 % SS(fs), (WORD)val);
+			fs->wflag = 1;
+			break;
+
+		case FS_FAT32 :	/* DWORD aligned items */
+#if _FS_EXFAT
+		case FS_EXFAT :
+#endif
+			res = move_window(fs, fs->fatbase + (clst / (SS(fs) / 4)));
+			if (res != FR_OK) break;
+			if (!_FS_EXFAT || fs->fs_type != FS_EXFAT) {
+				val = (val & 0x0FFFFFFF) | (ld_dword(fs->win + clst * 4 % SS(fs)) & 0xF0000000);
+			}
+			st_dword(fs->win + clst * 4 % SS(fs), val);
+			fs->wflag = 1;
+			break;
+		}
+	}
+	return res;
+}
+
+#endif /* !_FS_READONLY */
+
+
+
+
+#if _FS_EXFAT && !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* exFAT: Accessing FAT and Allocation Bitmap                            */
+/*-----------------------------------------------------------------------*/
+
+/*---------------------------------------------*/
+/* exFAT: Find a contiguous free cluster block */
+/*---------------------------------------------*/
+
+static
+DWORD find_bitmap (	/* 0:No free cluster, 2..:Free cluster found, 0xFFFFFFFF:Disk error */
+	FATFS* fs,	/* File system object */
+	DWORD clst,	/* Cluster number to scan from */
+	DWORD ncl	/* Number of contiguous clusters to find (1..) */
+)
+{
+	BYTE bm, bv;
+	UINT i;
+	DWORD val, scl, ctr;
+
+
+	clst -= 2;	/* The first bit in the bitmap corresponds to cluster #2 */
+	if (clst >= fs->n_fatent - 2) clst = 0;
+	scl = val = clst; ctr = 0;
+	for (;;) {
+		if (move_window(fs, fs->database + val / 8 / SS(fs)) != FR_OK) return 0xFFFFFFFF;	/* (assuming bitmap is located top of the cluster heap) */
+		i = val / 8 % SS(fs); bm = 1 << (val % 8);
+		do {
+			do {
+				bv = fs->win[i] & bm; bm <<= 1;		/* Get bit value */
+				if (++val >= fs->n_fatent - 2) {	/* Next cluster (with wrap-around) */
+					val = 0; bm = 0; i = 4096;
+				}
+				if (!bv) {	/* Is it a free cluster? */
+					if (++ctr == ncl) return scl + 2;	/* Check run length */
+				} else {
+					scl = val; ctr = 0;		/* Encountered a live cluster, restart to scan */
+				}
+				if (val == clst) return 0;	/* All cluster scanned? */
+			} while (bm);
+			bm = 1;
+		} while (++i < SS(fs));
+	}
+}
+
+
+/*------------------------------------*/
+/* exFAT: Set/Clear a block of bitmap */
+/*------------------------------------*/
+
+static
+FRESULT change_bitmap (
+	FATFS* fs,	/* File system object */
+	DWORD clst,	/* Cluster number to change from */
+	DWORD ncl,	/* Number of clusters to be changed */
+	int bv		/* bit value to be set (0 or 1) */
+)
+{
+	BYTE bm;
+	UINT i;
+	DWORD sect;
+
+
+	clst -= 2;	/* The first bit corresponds to cluster #2 */
+	sect = fs->database + clst / 8 / SS(fs);	/* Sector address (assuming bitmap is located top of the cluster heap) */
+	i = clst / 8 % SS(fs);						/* Byte offset in the sector */
+	bm = 1 << (clst % 8);						/* Bit mask in the byte */
+	for (;;) {
+		if (move_window(fs, sect++) != FR_OK) return FR_DISK_ERR;
+		do {
+			do {
+				if (bv == (int)((fs->win[i] & bm) != 0)) return FR_INT_ERR;	/* Is the bit expected value? */
+				fs->win[i] ^= bm;	/* Flip the bit */
+				fs->wflag = 1;
+				if (--ncl == 0) return FR_OK;	/* All bits processed? */
+			} while (bm <<= 1);		/* Next bit */
+			bm = 1;
+		} while (++i < SS(fs));		/* Next byte */
+		i = 0;
+	}
+}
+
+
+/*---------------------------------------------*/
+/* Complement contiguous part of the FAT chain */
+/*---------------------------------------------*/
+
+static
+FRESULT fill_fat_chain (
+	_FDID* obj	/* Pointer to the corresponding object */
+)
+{
+	FRESULT res;
+	DWORD cl, n;
+
+	if (obj->stat == 3) {	/* Has the object been changed 'fragmented'? */
+		for (cl = obj->sclust, n = obj->n_cont; n; cl++, n--) {	/* Create cluster chain on the FAT */
+			res = put_fat(obj->fs, cl, cl + 1);
+			if (res != FR_OK) return res;
+		}
+		obj->stat = 0;	/* Change status 'FAT chain is valid' */
+	}
+	return FR_OK;
+}
+
+#endif	/* _FS_EXFAT && !_FS_READONLY */
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* FAT handling - Remove a cluster chain                                 */
+/*-----------------------------------------------------------------------*/
+static
+FRESULT remove_chain (	/* FR_OK(0):succeeded, !=0:error */
+	_FDID* obj,			/* Corresponding object */
+	DWORD clst,			/* Cluster to remove a chain from */
+	DWORD pclst			/* Previous cluster of clst (0:an entire chain) */
+)
+{
+	FRESULT res = FR_OK;
+	DWORD nxt;
+	FATFS *fs = obj->fs;
+#if _FS_EXFAT || _USE_TRIM
+	DWORD scl = clst, ecl = clst;
+#endif
+#if _USE_TRIM
+	DWORD rt[2];
+#endif
+
+	if (clst < 2 || clst >= fs->n_fatent) return FR_INT_ERR;	/* Check if in valid range */
+
+	/* Mark the previous cluster 'EOC' on the FAT if it exists */
+	if (pclst && (!_FS_EXFAT || fs->fs_type != FS_EXFAT || obj->stat != 2)) {
+		res = put_fat(fs, pclst, 0xFFFFFFFF);
+		if (res != FR_OK) return res;
+	}
+
+	/* Remove the chain */
+	do {
+		nxt = get_fat(obj, clst);			/* Get cluster status */
+		if (nxt == 0) break;				/* Empty cluster? */
+		if (nxt == 1) return FR_INT_ERR;	/* Internal error? */
+		if (nxt == 0xFFFFFFFF) return FR_DISK_ERR;	/* Disk error? */
+		if (!_FS_EXFAT || fs->fs_type != FS_EXFAT) {
+			res = put_fat(fs, clst, 0);		/* Mark the cluster 'free' on the FAT */
+			if (res != FR_OK) return res;
+		}
+		if (fs->free_clst < fs->n_fatent - 2) {	/* Update FSINFO */
+			fs->free_clst++;
+			fs->fsi_flag |= 1;
+		}
+#if _FS_EXFAT || _USE_TRIM
+		if (ecl + 1 == nxt) {	/* Is next cluster contiguous? */
+			ecl = nxt;
+		} else {				/* End of contiguous cluster block */ 
+#if _FS_EXFAT
+			if (fs->fs_type == FS_EXFAT) {
+				res = change_bitmap(fs, scl, ecl - scl + 1, 0);	/* Mark the cluster block 'free' on the bitmap */
+				if (res != FR_OK) return res;
+			}
+#endif
+#if _USE_TRIM
+			rt[0] = clust2sect(fs, scl);					/* Start sector */
+			rt[1] = clust2sect(fs, ecl) + fs->csize - 1;	/* End sector */
+			disk_ioctl(fs->drv, CTRL_TRIM, rt);				/* Inform device the block can be erased */
+#endif
+			scl = ecl = nxt;
+		}
+#endif
+		clst = nxt;					/* Next cluster */
+	} while (clst < fs->n_fatent);	/* Repeat while not the last link */
+
+#if _FS_EXFAT
+	if (fs->fs_type == FS_EXFAT) {
+		if (pclst == 0) {	/* Does object have no chain? */
+			obj->stat = 0;		/* Change the object status 'initial' */
+		} else {
+			if (obj->stat == 3 && pclst >= obj->sclust && pclst <= obj->sclust + obj->n_cont) {	/* Did the chain got contiguous? */
+				obj->stat = 2;	/* Change the object status 'contiguous' */
+			}
+		}
+	}
+#endif
+	return FR_OK;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* FAT handling - Stretch a chain or Create a new chain                  */
+/*-----------------------------------------------------------------------*/
+static
+DWORD create_chain (	/* 0:No free cluster, 1:Internal error, 0xFFFFFFFF:Disk error, >=2:New cluster# */
+	_FDID* obj,			/* Corresponding object */
+	DWORD clst			/* Cluster# to stretch, 0:Create a new chain */
+)
+{
+	DWORD cs, ncl, scl;
+	FRESULT res;
+	FATFS *fs = obj->fs;
+
+
+	if (clst == 0) {	/* Create a new chain */
+		scl = fs->last_clst;				/* Get suggested cluster to start from */
+		if (scl == 0 || scl >= fs->n_fatent) scl = 1;
+	}
+	else {				/* Stretch current chain */
+		cs = get_fat(obj, clst);			/* Check the cluster status */
+		if (cs < 2) return 1;				/* Invalid value */
+		if (cs == 0xFFFFFFFF) return cs;	/* A disk error occurred */
+		if (cs < fs->n_fatent) return cs;	/* It is already followed by next cluster */
+		scl = clst;
+	}
+
+#if _FS_EXFAT
+	if (fs->fs_type == FS_EXFAT) {	/* On the exFAT volume */
+		ncl = find_bitmap(fs, scl, 1);				/* Find a free cluster */
+		if (ncl == 0 || ncl == 0xFFFFFFFF) return ncl;	/* No free cluster or hard error? */
+		res = change_bitmap(fs, ncl, 1, 1);			/* Mark the cluster 'in use' */
+		if (res == FR_INT_ERR) return 1;
+		if (res == FR_DISK_ERR) return 0xFFFFFFFF;
+		if (clst == 0) {							/* Is it a new chain? */
+			obj->stat = 2;							/* Set status 'contiguous chain' */
+		} else {									/* This is a stretched chain */
+			if (obj->stat == 2 && ncl != scl + 1) {	/* Is the chain got fragmented? */
+				obj->n_cont = scl - obj->sclust;	/* Set size of the contiguous part */
+				obj->stat = 3;						/* Change status 'just fragmented' */
+			}
+		}
+	} else
+#endif
+	{	/* On the FAT12/16/32 volume */
+		ncl = scl;	/* Start cluster */
+		for (;;) {
+			ncl++;							/* Next cluster */
+			if (ncl >= fs->n_fatent) {		/* Check wrap-around */
+				ncl = 2;
+				if (ncl > scl) return 0;	/* No free cluster */
+			}
+			cs = get_fat(obj, ncl);			/* Get the cluster status */
+			if (cs == 0) break;				/* Found a free cluster */
+			if (cs == 1 || cs == 0xFFFFFFFF) return cs;	/* An error occurred */
+			if (ncl == scl) return 0;		/* No free cluster */
+		}
+	}
+
+	if (_FS_EXFAT && fs->fs_type == FS_EXFAT && obj->stat == 2) {	/* Is it a contiguous chain? */
+		res = FR_OK;						/* FAT does not need to be written */
+	} else {
+		res = put_fat(fs, ncl, 0xFFFFFFFF);	/* Mark the new cluster 'EOC' */
+		if (res == FR_OK && clst) {
+			res = put_fat(fs, clst, ncl);	/* Link it from the previous one if needed */
+		}
+	}
+
+	if (res == FR_OK) {			/* Update FSINFO if function succeeded. */
+		fs->last_clst = ncl;
+		if (fs->free_clst < fs->n_fatent - 2) fs->free_clst--;
+		fs->fsi_flag |= 1;
+	} else {
+		ncl = (res == FR_DISK_ERR) ? 0xFFFFFFFF : 1;	/* Failed. Create error status */
+	}
+
+	return ncl;		/* Return new cluster number or error status */
+}
+
+#endif /* !_FS_READONLY */
+
+
+
+
+#if _USE_FASTSEEK
+/*-----------------------------------------------------------------------*/
+/* FAT handling - Convert offset into cluster with link map table        */
+/*-----------------------------------------------------------------------*/
+
+static
+DWORD clmt_clust (	/* <2:Error, >=2:Cluster number */
+	FIL* fp,		/* Pointer to the file object */
+	FSIZE_t ofs		/* File offset to be converted to cluster# */
+)
+{
+	DWORD cl, ncl, *tbl;
+	FATFS *fs = fp->obj.fs;
+
+
+	tbl = fp->cltbl + 1;	/* Top of CLMT */
+	cl = (DWORD)(ofs / SS(fs) / fs->csize);	/* Cluster order from top of the file */
+	for (;;) {
+		ncl = *tbl++;			/* Number of cluters in the fragment */
+		if (ncl == 0) return 0;	/* End of table? (error) */
+		if (cl < ncl) break;	/* In this fragment? */
+		cl -= ncl; tbl++;		/* Next fragment */
+	}
+	return cl + *tbl;	/* Return the cluster number */
+}
+
+#endif	/* _USE_FASTSEEK */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Directory handling - Set directory index                              */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_sdi (	/* FR_OK(0):succeeded, !=0:error */
+	DIR* dp,		/* Pointer to directory object */
+	DWORD ofs		/* Offset of directory table */
+)
+{
+	DWORD csz, clst;
+	FATFS *fs = dp->obj.fs;
+
+
+	if (ofs >= (DWORD)((_FS_EXFAT && fs->fs_type == FS_EXFAT) ? MAX_DIR_EX : MAX_DIR) || ofs % SZDIRE) {	/* Check range of offset and alignment */
+		return FR_INT_ERR;
+	}
+	dp->dptr = ofs;				/* Set current offset */
+	clst = dp->obj.sclust;		/* Table start cluster (0:root) */
+	if (clst == 0 && fs->fs_type >= FS_FAT32) {	/* Replace cluster# 0 with root cluster# */
+		clst = fs->dirbase;
+		if (_FS_EXFAT) dp->obj.stat = 0;	/* exFAT: Root dir has an FAT chain */
+	}
+
+	if (clst == 0) {	/* Static table (root-directory in FAT12/16) */
+		if (ofs / SZDIRE >= fs->n_rootdir)	return FR_INT_ERR;	/* Is index out of range? */
+		dp->sect = fs->dirbase;
+
+	} else {			/* Dynamic table (sub-directory or root-directory in FAT32+) */
+		csz = (DWORD)fs->csize * SS(fs);	/* Bytes per cluster */
+		while (ofs >= csz) {				/* Follow cluster chain */
+			clst = get_fat(&dp->obj, clst);				/* Get next cluster */
+			if (clst == 0xFFFFFFFF) return FR_DISK_ERR;	/* Disk error */
+			if (clst < 2 || clst >= fs->n_fatent) return FR_INT_ERR;	/* Reached to end of table or internal error */
+			ofs -= csz;
+		}
+		dp->sect = clust2sect(fs, clst);
+	}
+	dp->clust = clst;					/* Current cluster# */
+	if (!dp->sect) return FR_INT_ERR;
+	dp->sect += ofs / SS(fs);			/* Sector# of the directory entry */
+	dp->dir = fs->win + (ofs % SS(fs));	/* Pointer to the entry in the win[] */
+
+	return FR_OK;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Directory handling - Move directory table index next                  */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_next (	/* FR_OK(0):succeeded, FR_NO_FILE:End of table, FR_DENIED:Could not stretch */
+	DIR* dp,		/* Pointer to the directory object */
+	int stretch		/* 0: Do not stretch table, 1: Stretch table if needed */
+)
+{
+	DWORD ofs, clst;
+	FATFS *fs = dp->obj.fs;
+#if !_FS_READONLY
+	UINT n;
+#endif
+
+	ofs = dp->dptr + SZDIRE;	/* Next entry */
+	if (!dp->sect || ofs >= (DWORD)((_FS_EXFAT && fs->fs_type == FS_EXFAT) ? MAX_DIR_EX : MAX_DIR)) return FR_NO_FILE;	/* Report EOT when offset has reached max value */
+
+	if (ofs % SS(fs) == 0) {	/* Sector changed? */
+		dp->sect++;				/* Next sector */
+
+		if (!dp->clust) {		/* Static table */
+			if (ofs / SZDIRE >= fs->n_rootdir) {	/* Report EOT if it reached end of static table */
+				dp->sect = 0; return FR_NO_FILE;
+			}
+		}
+		else {					/* Dynamic table */
+			if ((ofs / SS(fs) & (fs->csize - 1)) == 0) {		/* Cluster changed? */
+				clst = get_fat(&dp->obj, dp->clust);			/* Get next cluster */
+				if (clst <= 1) return FR_INT_ERR;				/* Internal error */
+				if (clst == 0xFFFFFFFF) return FR_DISK_ERR;		/* Disk error */
+				if (clst >= fs->n_fatent) {						/* Reached end of dynamic table */
+#if !_FS_READONLY
+					if (!stretch) {								/* If no stretch, report EOT */
+						dp->sect = 0; return FR_NO_FILE;
+					}
+					clst = create_chain(&dp->obj, dp->clust);	/* Allocate a cluster */
+					if (clst == 0) return FR_DENIED;			/* No free cluster */
+					if (clst == 1) return FR_INT_ERR;			/* Internal error */
+					if (clst == 0xFFFFFFFF) return FR_DISK_ERR;	/* Disk error */
+					/* Clean-up the stretched table */
+					if (_FS_EXFAT) dp->obj.stat |= 4;			/* The directory needs to be updated */
+					if (sync_window(fs) != FR_OK) return FR_DISK_ERR;	/* Flush disk access window */
+					mem_set(fs->win, 0, SS(fs));				/* Clear window buffer */
+					for (n = 0, fs->winsect = clust2sect(fs, clst); n < fs->csize; n++, fs->winsect++) {	/* Fill the new cluster with 0 */
+						fs->wflag = 1;
+						if (sync_window(fs) != FR_OK) return FR_DISK_ERR;
+					}
+					fs->winsect -= n;							/* Restore window offset */
+#else
+					if (!stretch) dp->sect = 0;					/* If no stretch, report EOT (this is to suppress warning) */
+					dp->sect = 0; return FR_NO_FILE;			/* Report EOT */
+#endif
+				}
+				dp->clust = clst;		/* Initialize data for new cluster */
+				dp->sect = clust2sect(fs, clst);
+			}
+		}
+	}
+	dp->dptr = ofs;						/* Current entry */
+	dp->dir = fs->win + ofs % SS(fs);	/* Pointer to the entry in the win[] */
+
+	return FR_OK;
+}
+
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Directory handling - Reserve a block of directory entries             */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_alloc (	/* FR_OK(0):succeeded, !=0:error */
+	DIR* dp,		/* Pointer to the directory object */
+	UINT nent		/* Number of contiguous entries to allocate */
+)
+{
+	FRESULT res;
+	UINT n;
+	FATFS *fs = dp->obj.fs;
+
+
+	res = dir_sdi(dp, 0);
+	if (res == FR_OK) {
+		n = 0;
+		do {
+			res = move_window(fs, dp->sect);
+			if (res != FR_OK) break;
+#if _FS_EXFAT
+			if ((fs->fs_type == FS_EXFAT) ? (int)((dp->dir[XDIR_Type] & 0x80) == 0) : (int)(dp->dir[DIR_Name] == DDEM || dp->dir[DIR_Name] == 0)) {
+#else
+			if (dp->dir[DIR_Name] == DDEM || dp->dir[DIR_Name] == 0) {
+#endif
+				if (++n == nent) break;	/* A block of contiguous free entries is found */
+			} else {
+				n = 0;					/* Not a blank entry. Restart to search */
+			}
+			res = dir_next(dp, 1);
+		} while (res == FR_OK);	/* Next entry with table stretch enabled */
+	}
+
+	if (res == FR_NO_FILE) res = FR_DENIED;	/* No directory entry to allocate */
+	return res;
+}
+
+#endif	/* !_FS_READONLY */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* FAT: Directory handling - Load/Store start cluster number             */
+/*-----------------------------------------------------------------------*/
+
+static
+DWORD ld_clust (	/* Returns the top cluster value of the SFN entry */
+	FATFS* fs,		/* Pointer to the fs object */
+	const BYTE* dir	/* Pointer to the key entry */
+)
+{
+	DWORD cl;
+
+	cl = ld_word(dir + DIR_FstClusLO);
+	if (fs->fs_type == FS_FAT32) {
+		cl |= (DWORD)ld_word(dir + DIR_FstClusHI) << 16;
+	}
+
+	return cl;
+}
+
+
+#if !_FS_READONLY
+static
+void st_clust (
+	FATFS* fs,	/* Pointer to the fs object */
+	BYTE* dir,	/* Pointer to the key entry */
+	DWORD cl	/* Value to be set */
+)
+{
+	st_word(dir + DIR_FstClusLO, (WORD)cl);
+	if (fs->fs_type == FS_FAT32) {
+		st_word(dir + DIR_FstClusHI, (WORD)(cl >> 16));
+	}
+}
+#endif
+
+
+
+#if _USE_LFN != 0
+/*------------------------------------------------------------------------*/
+/* FAT-LFN: LFN handling                                                  */
+/*------------------------------------------------------------------------*/
+static
+const BYTE LfnOfs[] = {1,3,5,7,9,14,16,18,20,22,24,28,30};	/* Offset of LFN characters in the directory entry */
+
+
+/*--------------------------------------------------------*/
+/* FAT-LFN: Compare a part of file name with an LFN entry */
+/*--------------------------------------------------------*/
+static
+int cmp_lfn (				/* 1:matched, 0:not matched */
+	const WCHAR* lfnbuf,	/* Pointer to the LFN working buffer to be compared */
+	BYTE* dir				/* Pointer to the directory entry containing the part of LFN */
+)
+{
+	UINT i, s;
+	WCHAR wc, uc;
+
+
+	if (ld_word(dir + LDIR_FstClusLO) != 0) return 0;	/* Check LDIR_FstClusLO */
+
+	i = ((dir[LDIR_Ord] & 0x3F) - 1) * 13;	/* Offset in the LFN buffer */
+
+	for (wc = 1, s = 0; s < 13; s++) {		/* Process all characters in the entry */
+		uc = ld_word(dir + LfnOfs[s]);		/* Pick an LFN character */
+		if (wc) {
+			if (i >= _MAX_LFN || ff_wtoupper(uc) != ff_wtoupper(lfnbuf[i++])) {	/* Compare it */
+				return 0;					/* Not matched */
+			}
+			wc = uc;
+		} else {
+			if (uc != 0xFFFF) return 0;		/* Check filler */
+		}
+	}
+
+	if ((dir[LDIR_Ord] & LLEF) && wc && lfnbuf[i]) return 0;	/* Last segment matched but different length */
+
+	return 1;		/* The part of LFN matched */
+}
+
+
+#if _FS_MINIMIZE <= 1 || _FS_RPATH >= 2 || _USE_LABEL || _FS_EXFAT
+/*-----------------------------------------------------*/
+/* FAT-LFN: Pick a part of file name from an LFN entry */
+/*-----------------------------------------------------*/
+static
+int pick_lfn (			/* 1:succeeded, 0:buffer overflow or invalid LFN entry */
+	WCHAR* lfnbuf,		/* Pointer to the LFN working buffer */
+	BYTE* dir			/* Pointer to the LFN entry */
+)
+{
+	UINT i, s;
+	WCHAR wc, uc;
+
+
+	if (ld_word(dir + LDIR_FstClusLO) != 0) return 0;	/* Check LDIR_FstClusLO */
+
+	i = ((dir[LDIR_Ord] & 0x3F) - 1) * 13;	/* Offset in the LFN buffer */
+
+	for (wc = 1, s = 0; s < 13; s++) {		/* Process all characters in the entry */
+		uc = ld_word(dir + LfnOfs[s]);		/* Pick an LFN character */
+		if (wc) {
+			if (i >= _MAX_LFN) return 0;	/* Buffer overflow? */
+			lfnbuf[i++] = wc = uc;			/* Store it */
+		} else {
+			if (uc != 0xFFFF) return 0;		/* Check filler */
+		}
+	}
+
+	if (dir[LDIR_Ord] & LLEF) {				/* Put terminator if it is the last LFN part */
+		if (i >= _MAX_LFN) return 0;		/* Buffer overflow? */
+		lfnbuf[i] = 0;
+	}
+
+	return 1;		/* The part of LFN is valid */
+}
+#endif
+
+
+#if !_FS_READONLY
+/*-----------------------------------------*/
+/* FAT-LFN: Create an entry of LFN entries */
+/*-----------------------------------------*/
+static
+void put_lfn (
+	const WCHAR* lfn,	/* Pointer to the LFN */
+	BYTE* dir,			/* Pointer to the LFN entry to be created */
+	BYTE ord,			/* LFN order (1-20) */
+	BYTE sum			/* Checksum of the corresponding SFN */
+)
+{
+	UINT i, s;
+	WCHAR wc;
+
+
+	dir[LDIR_Chksum] = sum;			/* Set checksum */
+	dir[LDIR_Attr] = AM_LFN;		/* Set attribute. LFN entry */
+	dir[LDIR_Type] = 0;
+	st_word(dir + LDIR_FstClusLO, 0);
+
+	i = (ord - 1) * 13;				/* Get offset in the LFN working buffer */
+	s = wc = 0;
+	do {
+		if (wc != 0xFFFF) wc = lfn[i++];	/* Get an effective character */
+		st_word(dir + LfnOfs[s], wc);		/* Put it */
+		if (wc == 0) wc = 0xFFFF;		/* Padding characters for left locations */
+	} while (++s < 13);
+	if (wc == 0xFFFF || !lfn[i]) ord |= LLEF;	/* Last LFN part is the start of LFN sequence */
+	dir[LDIR_Ord] = ord;			/* Set the LFN order */
+}
+
+#endif	/* !_FS_READONLY */
+#endif	/* _USE_LFN != 0 */
+
+
+
+#if _USE_LFN != 0 && !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* FAT-LFN: Create a Numbered SFN                                        */
+/*-----------------------------------------------------------------------*/
+
+static
+void gen_numname (
+	BYTE* dst,			/* Pointer to the buffer to store numbered SFN */
+	const BYTE* src,	/* Pointer to SFN */
+	const WCHAR* lfn,	/* Pointer to LFN */
+	UINT seq			/* Sequence number */
+)
+{
+	BYTE ns[8], c;
+	UINT i, j;
+	WCHAR wc;
+	DWORD sr;
+
+
+	mem_cpy(dst, src, 11);
+
+	if (seq > 5) {	/* In case of many collisions, generate a hash number instead of sequential number */
+		sr = seq;
+		while (*lfn) {	/* Create a CRC */
+			wc = *lfn++;
+			for (i = 0; i < 16; i++) {
+				sr = (sr << 1) + (wc & 1);
+				wc >>= 1;
+				if (sr & 0x10000) sr ^= 0x11021;
+			}
+		}
+		seq = (UINT)sr;
+	}
+
+	/* itoa (hexdecimal) */
+	i = 7;
+	do {
+		c = (BYTE)((seq % 16) + '0');
+		if (c > '9') c += 7;
+		ns[i--] = c;
+		seq /= 16;
+	} while (seq);
+	ns[i] = '~';
+
+	/* Append the number */
+	for (j = 0; j < i && dst[j] != ' '; j++) {
+		if (IsDBCS1(dst[j])) {
+			if (j == i - 1) break;
+			j++;
+		}
+	}
+	do {
+		dst[j++] = (i < 8) ? ns[i++] : ' ';
+	} while (j < 8);
+}
+#endif	/* _USE_LFN != 0 && !_FS_READONLY */
+
+
+
+#if _USE_LFN != 0
+/*-----------------------------------------------------------------------*/
+/* FAT-LFN: Calculate checksum of an SFN entry                           */
+/*-----------------------------------------------------------------------*/
+
+static
+BYTE sum_sfn (
+	const BYTE* dir		/* Pointer to the SFN entry */
+)
+{
+	BYTE sum = 0;
+	UINT n = 11;
+
+	do sum = (sum >> 1) + (sum << 7) + *dir++; while (--n);
+	return sum;
+}
+
+#endif	/* _USE_LFN != 0 */
+
+
+
+#if _FS_EXFAT
+/*-----------------------------------------------------------------------*/
+/* exFAT: Checksum                                                       */
+/*-----------------------------------------------------------------------*/
+
+static
+WORD xdir_sum (			/* Get checksum of the directoly block */
+	const BYTE* dir		/* Directory entry block to be calculated */
+)
+{
+	UINT i, szblk;
+	WORD sum;
+
+
+	szblk = (dir[XDIR_NumSec] + 1) * SZDIRE;
+	for (i = sum = 0; i < szblk; i++) {
+		if (i == XDIR_SetSum) {	/* Skip sum field */
+			i++;
+		} else {
+			sum = ((sum & 1) ? 0x8000 : 0) + (sum >> 1) + dir[i];
+		}
+	}
+	return sum;
+}
+
+
+
+static
+WORD xname_sum (		/* Get check sum (to be used as hash) of the name */
+	const WCHAR* name	/* File name to be calculated */
+)
+{
+	WCHAR chr;
+	WORD sum = 0;
+
+
+	while ((chr = *name++) != 0) {
+		chr = ff_wtoupper(chr);		/* File name needs to be ignored case */
+		sum = ((sum & 1) ? 0x8000 : 0) + (sum >> 1) + (chr & 0xFF);
+		sum = ((sum & 1) ? 0x8000 : 0) + (sum >> 1) + (chr >> 8);
+	}
+	return sum;
+}
+
+
+#if !_FS_READONLY && _USE_MKFS
+static
+DWORD xsum32 (
+	BYTE  dat,	/* Data to be sumed */
+	DWORD sum	/* Previous value */
+)
+{
+	sum = ((sum & 1) ? 0x80000000 : 0) + (sum >> 1) + dat;
+	return sum;
+}
+#endif
+
+
+#if _FS_MINIMIZE <= 1 || _FS_RPATH >= 2
+/*------------------------------------------------------*/
+/* exFAT: Get object information from a directory block */
+/*------------------------------------------------------*/
+
+static
+void get_xdir_info (
+	BYTE* dirb,			/* Pointer to the direcotry entry block 85+C0+C1s */
+	FILINFO* fno		/* Buffer to store the extracted file information */
+)
+{
+	UINT di, si;
+	WCHAR w;
+#if !_LFN_UNICODE
+	UINT nc;
+#endif
+
+	/* Get file name */
+#if _LFN_UNICODE
+	if (dirb[XDIR_NumName] <= _MAX_LFN) {
+		for (si = SZDIRE * 2, di = 0; di < dirb[XDIR_NumName]; si += 2, di++) {
+			if ((si % SZDIRE) == 0) si += 2;	/* Skip entry type field */
+			w = ld_word(dirb + si);				/* Get a character */
+			fno->fname[di] = w;					/* Store it */
+		}
+	} else {
+		di = 0;	/* Buffer overflow and inaccessible object */
+	}
+#else
+	for (si = SZDIRE * 2, di = nc = 0; nc < dirb[XDIR_NumName]; si += 2, nc++) {
+		if ((si % SZDIRE) == 0) si += 2;	/* Skip entry type field */
+		w = ld_word(dirb + si);				/* Get a character */
+		w = ff_convert(w, 0);				/* Unicode -> OEM */
+		if (w == 0) { di = 0; break; }		/* Could not be converted and inaccessible object */
+		if (_DF1S && w >= 0x100) {			/* Put 1st byte if it is a DBC (always false at SBCS cfg) */
+			fno->fname[di++] = (char)(w >> 8);
+		}
+		if (di >= _MAX_LFN) { di = 0; break; }	/* Buffer overflow and inaccessible object */
+		fno->fname[di++] = (char)w;
+	}
+#endif
+	if (di == 0) fno->fname[di++] = '?';	/* Inaccessible object? */
+	fno->fname[di] = 0;						/* Terminate file name */
+
+	fno->altname[0] = 0;							/* No SFN */
+	fno->fattrib = dirb[XDIR_Attr];					/* Attribute */
+	fno->fsize = (fno->fattrib & AM_DIR) ? 0 : ld_qword(dirb + XDIR_FileSize);	/* Size */
+	fno->ftime = ld_word(dirb + XDIR_ModTime + 0);	/* Time */
+	fno->fdate = ld_word(dirb + XDIR_ModTime + 2);	/* Date */
+}
+
+#endif	/* _FS_MINIMIZE <= 1 || _FS_RPATH >= 2 */
+
+
+/*-----------------------------------*/
+/* exFAT: Get a directry entry block */
+/*-----------------------------------*/
+
+static
+FRESULT load_xdir (	/* FR_INT_ERR: invalid entry block */
+	DIR* dp			/* Pointer to the reading direcotry object pointing the 85 entry */
+)
+{
+	FRESULT res;
+	UINT i, nent;
+	BYTE* dirb = dp->obj.fs->dirbuf;	/* Pointer to the on-memory direcotry entry block 85+C0+C1s */
+
+
+	/* Load 85 entry */
+	res = move_window(dp->obj.fs, dp->sect);
+	if (res != FR_OK) return res;
+	if (dp->dir[XDIR_Type] != 0x85) return FR_INT_ERR;
+	mem_cpy(dirb, dp->dir, SZDIRE);
+	nent = dirb[XDIR_NumSec] + 1;
+
+	/* Load C0 entry */
+	res = dir_next(dp, 0);
+	if (res != FR_OK) return res;
+	res = move_window(dp->obj.fs, dp->sect);
+	if (res != FR_OK) return res;
+	if (dp->dir[XDIR_Type] != 0xC0) return FR_INT_ERR;
+	mem_cpy(dirb + SZDIRE, dp->dir, SZDIRE);
+
+	/* Load C1 entries */
+	if (nent < 3 || nent > 19) return FR_NO_FILE;
+	i = SZDIRE * 2; nent *= SZDIRE;
+	do {
+		res = dir_next(dp, 0);
+		if (res != FR_OK) return res;
+		res = move_window(dp->obj.fs, dp->sect);
+		if (res != FR_OK) return res;
+		if (dp->dir[XDIR_Type] != 0xC1) return FR_INT_ERR;
+		mem_cpy(dirb + i, dp->dir, SZDIRE);
+		i += SZDIRE;
+	} while (i < nent);
+
+	/* Sanity check */
+	if (xdir_sum(dirb) != ld_word(dirb + XDIR_SetSum)) return FR_INT_ERR;
+
+	return FR_OK;
+}
+
+
+#if !_FS_READONLY || _FS_RPATH != 0 
+/*------------------------------------------------*/
+/* exFAT: Load the object's directory entry block */
+/*------------------------------------------------*/
+static
+FRESULT load_obj_dir (	
+	DIR* dp,			/* Blank directory object to be used to access containing direcotry */
+	const _FDID* obj	/* Object with containing directory information */
+)
+{
+	FRESULT res;
+
+
+	/* Open object containing directory */
+	dp->obj.fs = obj->fs;
+	dp->obj.sclust = obj->c_scl;
+	dp->obj.stat = (BYTE)obj->c_size;
+	dp->obj.objsize = obj->c_size & 0xFFFFFF00;
+	dp->blk_ofs = obj->c_ofs;
+
+	res = dir_sdi(dp, dp->blk_ofs);	/* Goto the block location */
+	if (res == FR_OK) {
+		res = load_xdir(dp);		/* Load the object's entry block */
+	}
+	return res;
+}
+#endif
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------*/
+/* exFAT: Store the directory block to the media */
+/*-----------------------------------------------*/
+static
+FRESULT store_xdir (
+	DIR* dp				/* Pointer to the direcotry object */
+)
+{
+	FRESULT res;
+	UINT nent;
+	BYTE* dirb = dp->obj.fs->dirbuf;	/* Pointer to the direcotry entry block 85+C0+C1s */
+
+	/* Create set sum */
+	st_word(dirb + XDIR_SetSum, xdir_sum(dirb));
+	nent = dirb[XDIR_NumSec] + 1;
+
+	/* Store the set of directory to the volume */
+	res = dir_sdi(dp, dp->blk_ofs);
+	while (res == FR_OK) {
+		res = move_window(dp->obj.fs, dp->sect);
+		if (res != FR_OK) break;
+		mem_cpy(dp->dir, dirb, SZDIRE);
+		dp->obj.fs->wflag = 1;
+		if (--nent == 0) break;
+		dirb += SZDIRE;
+		res = dir_next(dp, 0);
+	}
+	return (res == FR_OK || res == FR_DISK_ERR) ? res : FR_INT_ERR;
+}
+
+
+
+/*-------------------------------------------*/
+/* exFAT: Create a new directory enrty block */
+/*-------------------------------------------*/
+
+static
+void create_xdir (
+	BYTE* dirb,			/* Pointer to the direcotry entry block buffer */
+	const WCHAR* lfn	/* Pointer to the nul terminated file name */
+)
+{
+	UINT i;
+	BYTE nb, nc;
+	WCHAR chr;
+
+
+	mem_set(dirb, 0, 2 * SZDIRE);			/* Initialize 85+C0 entry */
+	dirb[XDIR_Type] = 0x85;
+	dirb[XDIR_Type + SZDIRE] = 0xC0;
+	st_word(dirb + XDIR_NameHash, xname_sum(lfn));	/* Set name hash */
+
+	i = SZDIRE * 2;	/* C1 offset */
+	nc = 0; nb = 1; chr = 1;
+	do {
+		dirb[i++] = 0xC1; dirb[i++] = 0;	/* Entry type C1 */
+		do {	/* Fill name field */
+			if (chr && (chr = lfn[nc]) != 0) nc++;	/* Get a character if exist */
+			st_word(dirb + i, chr); i += 2;	/* Store it */
+		} while (i % SZDIRE);
+		nb++;
+	} while (lfn[nc]);	/* Fill next entry if any char follows */
+
+	dirb[XDIR_NumName] = nc;	/* Set name length */
+	dirb[XDIR_NumSec] = nb;		/* Set number of C0+C1s */
+}
+
+#endif	/* !_FS_READONLY */
+#endif	/* _FS_EXFAT */
+
+
+
+#if _FS_MINIMIZE <= 1 || _FS_RPATH >= 2 || _USE_LABEL || _FS_EXFAT
+/*-----------------------------------------------------------------------*/
+/* Read an object from the directory                                     */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_read (
+	DIR* dp,		/* Pointer to the directory object */
+	int vol			/* Filtered by 0:file/directory or 1:volume label */
+)
+{
+	FRESULT res = FR_NO_FILE;
+	FATFS *fs = dp->obj.fs;
+	BYTE a, c;
+#if _USE_LFN != 0
+	BYTE ord = 0xFF, sum = 0xFF;
+#endif
+
+	while (dp->sect) {
+		res = move_window(fs, dp->sect);
+		if (res != FR_OK) break;
+		c = dp->dir[DIR_Name];	/* Test for the entry type */
+		if (c == 0) { res = FR_NO_FILE; break; }	/* Reached to end of the directory */
+#if _FS_EXFAT
+		if (fs->fs_type == FS_EXFAT) {	/* On the exFAT volume */
+			if (_USE_LABEL && vol) {
+				if (c == 0x83) break;	/* Volume label entry? */
+			} else {
+				if (c == 0x85) {		/* Start of the file entry block? */
+					dp->blk_ofs = dp->dptr;	/* Get location of the block */
+					res = load_xdir(dp);	/* Load the entry block */
+					if (res == FR_OK) {
+						dp->obj.attr = fs->dirbuf[XDIR_Attr] & AM_MASK;	/* Get attribute */
+					}
+					break;
+				}
+			}
+		} else
+#endif
+		{	/* On the FAT12/16/32 volume */
+			dp->obj.attr = a = dp->dir[DIR_Attr] & AM_MASK;	/* Get attribute */
+#if _USE_LFN != 0	/* LFN configuration */
+			if (c == DDEM || c == '.' || (int)((a & ~AM_ARC) == AM_VOL) != vol) {	/* An entry without valid data */
+				ord = 0xFF;
+			} else {
+				if (a == AM_LFN) {			/* An LFN entry is found */
+					if (c & LLEF) {			/* Is it start of an LFN sequence? */
+						sum = dp->dir[LDIR_Chksum];
+						c &= (BYTE)~LLEF; ord = c;
+						dp->blk_ofs = dp->dptr;
+					}
+					/* Check LFN validity and capture it */
+					ord = (c == ord && sum == dp->dir[LDIR_Chksum] && pick_lfn(fs->lfnbuf, dp->dir)) ? ord - 1 : 0xFF;
+				} else {					/* An SFN entry is found */
+					if (ord || sum != sum_sfn(dp->dir)) {	/* Is there a valid LFN? */
+						dp->blk_ofs = 0xFFFFFFFF;			/* It has no LFN. */
+					}
+					break;
+				}
+			}
+#else		/* Non LFN configuration */
+			if (c != DDEM && c != '.' && a != AM_LFN && (int)((a & ~AM_ARC) == AM_VOL) == vol) {	/* Is it a valid entry? */
+				break;
+			}
+#endif
+		}
+		res = dir_next(dp, 0);		/* Next entry */
+		if (res != FR_OK) break;
+	}
+
+	if (res != FR_OK) dp->sect = 0;		/* Terminate the read operation on error or EOT */
+	return res;
+}
+
+#endif	/* _FS_MINIMIZE <= 1 || _USE_LABEL || _FS_RPATH >= 2 */
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Directory handling - Find an object in the directory                  */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_find (	/* FR_OK(0):succeeded, !=0:error */
+	DIR* dp			/* Pointer to the directory object with the file name */
+)
+{
+	FRESULT res;
+	FATFS *fs = dp->obj.fs;
+	BYTE c;
+#if _USE_LFN != 0
+	BYTE a, ord, sum;
+#endif
+
+	res = dir_sdi(dp, 0);			/* Rewind directory object */
+	if (res != FR_OK) return res;
+#if _FS_EXFAT
+	if (fs->fs_type == FS_EXFAT) {	/* On the exFAT volume */
+		BYTE nc;
+		UINT di, ni;
+		WORD hash = xname_sum(fs->lfnbuf);		/* Hash value of the name to find */
+
+		while ((res = dir_read(dp, 0)) == FR_OK) {	/* Read an item */
+			if (ld_word(fs->dirbuf + XDIR_NameHash) != hash) continue;	/* Skip the comparison if hash value mismatched */
+			for (nc = fs->dirbuf[XDIR_NumName], di = SZDIRE * 2, ni = 0; nc; nc--, di += 2, ni++) {	/* Compare the name */
+				if ((di % SZDIRE) == 0) di += 2;
+				if (ff_wtoupper(ld_word(fs->dirbuf + di)) != ff_wtoupper(fs->lfnbuf[ni])) break;
+			}
+			if (nc == 0 && !fs->lfnbuf[ni]) break;	/* Name matched? */
+		}
+		return res;
+	}
+#endif
+	/* On the FAT12/16/32 volume */
+#if _USE_LFN != 0
+	ord = sum = 0xFF; dp->blk_ofs = 0xFFFFFFFF;	/* Reset LFN sequence */
+#endif
+	do {
+		res = move_window(fs, dp->sect);
+		if (res != FR_OK) break;
+		c = dp->dir[DIR_Name];
+		if (c == 0) { res = FR_NO_FILE; break; }	/* Reached to end of table */
+#if _USE_LFN != 0	/* LFN configuration */
+		dp->obj.attr = a = dp->dir[DIR_Attr] & AM_MASK;
+		if (c == DDEM || ((a & AM_VOL) && a != AM_LFN)) {	/* An entry without valid data */
+			ord = 0xFF; dp->blk_ofs = 0xFFFFFFFF;	/* Reset LFN sequence */
+		} else {
+			if (a == AM_LFN) {			/* An LFN entry is found */
+				if (!(dp->fn[NSFLAG] & NS_NOLFN)) {
+					if (c & LLEF) {		/* Is it start of LFN sequence? */
+						sum = dp->dir[LDIR_Chksum];
+						c &= (BYTE)~LLEF; ord = c;	/* LFN start order */
+						dp->blk_ofs = dp->dptr;	/* Start offset of LFN */
+					}
+					/* Check validity of the LFN entry and compare it with given name */
+					ord = (c == ord && sum == dp->dir[LDIR_Chksum] && cmp_lfn(fs->lfnbuf, dp->dir)) ? ord - 1 : 0xFF;
+				}
+			} else {					/* An SFN entry is found */
+				if (!ord && sum == sum_sfn(dp->dir)) break;	/* LFN matched? */
+				if (!(dp->fn[NSFLAG] & NS_LOSS) && !mem_cmp(dp->dir, dp->fn, 11)) break;	/* SFN matched? */
+				ord = 0xFF; dp->blk_ofs = 0xFFFFFFFF;	/* Reset LFN sequence */
+			}
+		}
+#else		/* Non LFN configuration */
+		dp->obj.attr = dp->dir[DIR_Attr] & AM_MASK;
+		if (!(dp->dir[DIR_Attr] & AM_VOL) && !mem_cmp(dp->dir, dp->fn, 11)) break;	/* Is it a valid entry? */
+#endif
+		res = dir_next(dp, 0);	/* Next entry */
+	} while (res == FR_OK);
+
+	return res;
+}
+
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Register an object to the directory                                   */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_register (	/* FR_OK:succeeded, FR_DENIED:no free entry or too many SFN collision, FR_DISK_ERR:disk error */
+	DIR* dp				/* Target directory with object name to be created */
+)
+{
+	FRESULT res;
+	FATFS *fs = dp->obj.fs;
+#if _USE_LFN != 0	/* LFN configuration */
+	UINT n, nlen, nent;
+	BYTE sn[12], sum;
+
+
+	if (dp->fn[NSFLAG] & (NS_DOT | NS_NONAME)) return FR_INVALID_NAME;	/* Check name validity */
+	for (nlen = 0; fs->lfnbuf[nlen]; nlen++) ;	/* Get lfn length */
+
+#if _FS_EXFAT
+	if (fs->fs_type == FS_EXFAT) {	/* On the exFAT volume */
+		DIR dj;
+
+		nent = (nlen + 14) / 15 + 2;	/* Number of entries to allocate (85+C0+C1s) */
+		res = dir_alloc(dp, nent);		/* Allocate entries */
+		if (res != FR_OK) return res;
+		dp->blk_ofs = dp->dptr - SZDIRE * (nent - 1);			/* Set block position */
+
+		if (dp->obj.sclust != 0 && (dp->obj.stat & 4)) {	/* Has the sub-directory been stretched? */
+			dp->obj.stat &= 3;
+			dp->obj.objsize += (DWORD)fs->csize * SS(fs);	/* Increase object size by cluster size */
+			res = fill_fat_chain(&dp->obj);	/* Complement FAT chain if needed */
+			if (res != FR_OK) return res;
+			res = load_obj_dir(&dj, &dp->obj);
+			if (res != FR_OK) return res;	/* Load the object status */
+			st_qword(fs->dirbuf + XDIR_FileSize, dp->obj.objsize);		/* Update the allocation status */
+			st_qword(fs->dirbuf + XDIR_ValidFileSize, dp->obj.objsize);
+			fs->dirbuf[XDIR_GenFlags] = dp->obj.stat | 1;
+			res = store_xdir(&dj);			/* Store the object status */
+			if (res != FR_OK) return res;
+		}
+
+		create_xdir(fs->dirbuf, fs->lfnbuf);	/* Create on-memory directory block to be written later */
+		return FR_OK;
+	}
+#endif
+	/* On the FAT12/16/32 volume */
+	mem_cpy(sn, dp->fn, 12);
+	if (sn[NSFLAG] & NS_LOSS) {			/* When LFN is out of 8.3 format, generate a numbered name */
+		dp->fn[NSFLAG] = NS_NOLFN;		/* Find only SFN */
+		for (n = 1; n < 100; n++) {
+			gen_numname(dp->fn, sn, fs->lfnbuf, n);	/* Generate a numbered name */
+			res = dir_find(dp);				/* Check if the name collides with existing SFN */
+			if (res != FR_OK) break;
+		}
+		if (n == 100) return FR_DENIED;		/* Abort if too many collisions */
+		if (res != FR_NO_FILE) return res;	/* Abort if the result is other than 'not collided' */
+		dp->fn[NSFLAG] = sn[NSFLAG];
+	}
+
+	/* Create an SFN with/without LFNs. */
+	nent = (sn[NSFLAG] & NS_LFN) ? (nlen + 12) / 13 + 1 : 1;	/* Number of entries to allocate */
+	res = dir_alloc(dp, nent);		/* Allocate entries */
+	if (res == FR_OK && --nent) {	/* Set LFN entry if needed */
+		res = dir_sdi(dp, dp->dptr - nent * SZDIRE);
+		if (res == FR_OK) {
+			sum = sum_sfn(dp->fn);	/* Checksum value of the SFN tied to the LFN */
+			do {					/* Store LFN entries in bottom first */
+				res = move_window(fs, dp->sect);
+				if (res != FR_OK) break;
+				put_lfn(fs->lfnbuf, dp->dir, (BYTE)nent, sum);
+				fs->wflag = 1;
+				res = dir_next(dp, 0);	/* Next entry */
+			} while (res == FR_OK && --nent);
+		}
+	}
+
+#else	/* Non LFN configuration */
+	res = dir_alloc(dp, 1);		/* Allocate an entry for SFN */
+
+#endif
+
+	/* Set SFN entry */
+	if (res == FR_OK) {
+		res = move_window(fs, dp->sect);
+		if (res == FR_OK) {
+			mem_set(dp->dir, 0, SZDIRE);	/* Clean the entry */
+			mem_cpy(dp->dir + DIR_Name, dp->fn, 11);	/* Put SFN */
+#if _USE_LFN != 0
+			dp->dir[DIR_NTres] = dp->fn[NSFLAG] & (NS_BODY | NS_EXT);	/* Put NT flag */
+#endif
+			fs->wflag = 1;
+		}
+	}
+
+	return res;
+}
+
+#endif /* !_FS_READONLY */
+
+
+
+#if !_FS_READONLY && _FS_MINIMIZE == 0
+/*-----------------------------------------------------------------------*/
+/* Remove an object from the directory                                   */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT dir_remove (	/* FR_OK:Succeeded, FR_DISK_ERR:A disk error */
+	DIR* dp				/* Directory object pointing the entry to be removed */
+)
+{
+	FRESULT res;
+	FATFS *fs = dp->obj.fs;
+#if _USE_LFN != 0	/* LFN configuration */
+	DWORD last = dp->dptr;
+
+	res = (dp->blk_ofs == 0xFFFFFFFF) ? FR_OK : dir_sdi(dp, dp->blk_ofs);	/* Goto top of the entry block if LFN is exist */
+	if (res == FR_OK) {
+		do {
+			res = move_window(fs, dp->sect);
+			if (res != FR_OK) break;
+			/* Mark an entry 'deleted' */
+			if (_FS_EXFAT && fs->fs_type == FS_EXFAT) {	/* On the exFAT volume */
+				dp->dir[XDIR_Type] &= 0x7F;
+			} else {									/* On the FAT12/16/32 volume */
+				dp->dir[DIR_Name] = DDEM;
+			}
+			fs->wflag = 1;
+			if (dp->dptr >= last) break;	/* If reached last entry then all entries of the object has been deleted. */
+			res = dir_next(dp, 0);	/* Next entry */
+		} while (res == FR_OK);
+		if (res == FR_NO_FILE) res = FR_INT_ERR;
+	}
+#else			/* Non LFN configuration */
+
+	res = move_window(fs, dp->sect);
+	if (res == FR_OK) {
+		dp->dir[DIR_Name] = DDEM;
+		fs->wflag = 1;
+	}
+#endif
+
+	return res;
+}
+
+#endif /* !_FS_READONLY && _FS_MINIMIZE == 0 */
+
+
+
+#if _FS_MINIMIZE <= 1 || _FS_RPATH >= 2
+/*-----------------------------------------------------------------------*/
+/* Get file information from directory entry                             */
+/*-----------------------------------------------------------------------*/
+
+static
+void get_fileinfo (		/* No return code */
+	DIR* dp,			/* Pointer to the directory object */
+	FILINFO* fno	 	/* Pointer to the file information to be filled */
+)
+{
+	UINT i, j;
+	TCHAR c;
+	DWORD tm;
+#if _USE_LFN != 0
+	WCHAR w, lfv;
+	FATFS *fs = dp->obj.fs;
+#endif
+
+
+	fno->fname[0] = 0;		/* Invaidate file info */
+	if (!dp->sect) return;	/* Exit if read pointer has reached end of directory */
+
+#if _USE_LFN != 0	/* LFN configuration */
+#if _FS_EXFAT
+	if (fs->fs_type == FS_EXFAT) {	/* On the exFAT volume */
+		get_xdir_info(fs->dirbuf, fno);
+		return;
+	} else
+#endif
+	{	/* On the FAT12/16/32 volume */
+		if (dp->blk_ofs != 0xFFFFFFFF) {	/* Get LFN if available */
+			i = j = 0;
+			while ((w = fs->lfnbuf[j++]) != 0) {	/* Get an LFN character */
+#if !_LFN_UNICODE
+				w = ff_convert(w, 0);		/* Unicode -> OEM */
+				if (w == 0) { i = 0; break; }	/* No LFN if it could not be converted */
+				if (_DF1S && w >= 0x100) {	/* Put 1st byte if it is a DBC (always false at SBCS cfg) */
+					fno->fname[i++] = (char)(w >> 8);
+				}
+#endif
+				if (i >= _MAX_LFN) { i = 0; break; }	/* No LFN if buffer overflow */
+				fno->fname[i++] = (TCHAR)w;
+			}
+			fno->fname[i] = 0;	/* Terminate the LFN */
+		}
+	}
+
+	i = j = 0;
+	lfv = fno->fname[i];	/* LFN is exist if non-zero */
+	while (i < 11) {		/* Copy name body and extension */
+		c = (TCHAR)dp->dir[i++];
+		if (c == ' ') continue;				/* Skip padding spaces */
+		if (c == RDDEM) c = (TCHAR)DDEM;	/* Restore replaced DDEM character */
+		if (i == 9) {						/* Insert a . if extension is exist */
+			if (!lfv) fno->fname[j] = '.';
+			fno->altname[j++] = '.';
+		}
+#if _LFN_UNICODE
+		if (IsDBCS1(c) && i != 8 && i != 11 && IsDBCS2(dp->dir[i])) {
+			c = c << 8 | dp->dir[i++];
+		}
+		c = ff_convert(c, 1);	/* OEM -> Unicode */
+		if (!c) c = '?';
+#endif
+		fno->altname[j] = c;
+		if (!lfv) {
+			if (IsUpper(c) && (dp->dir[DIR_NTres] & (i >= 9 ? NS_EXT : NS_BODY))) {
+				c += 0x20;			/* To lower */
+			}
+			fno->fname[j] = c;
+		}
+		j++;
+	}
+	if (!lfv) {
+		fno->fname[j] = 0;
+		if (!dp->dir[DIR_NTres]) j = 0;	/* Altname is no longer needed if neither LFN nor case info is exist. */
+	}
+	fno->altname[j] = 0;	/* Terminate the SFN */
+
+#else	/* Non-LFN configuration */
+	i = j = 0;
+	while (i < 11) {		/* Copy name body and extension */
+		c = (TCHAR)dp->dir[i++];
+		if (c == ' ') continue;				/* Skip padding spaces */
+		if (c == RDDEM) c = (TCHAR)DDEM;	/* Restore replaced DDEM character */
+		if (i == 9) fno->fname[j++] = '.';	/* Insert a . if extension is exist */
+		fno->fname[j++] = c;
+	}
+	fno->fname[j] = 0;
+#endif
+
+	fno->fattrib = dp->dir[DIR_Attr];				/* Attribute */
+	fno->fsize = ld_dword(dp->dir + DIR_FileSize);	/* Size */
+	tm = ld_dword(dp->dir + DIR_ModTime);			/* Timestamp */
+	fno->ftime = (WORD)tm; fno->fdate = (WORD)(tm >> 16);
+}
+
+#endif /* _FS_MINIMIZE <= 1 || _FS_RPATH >= 2 */
+
+
+
+#if _USE_FIND && _FS_MINIMIZE <= 1
+/*-----------------------------------------------------------------------*/
+/* Pattern matching                                                      */
+/*-----------------------------------------------------------------------*/
+
+static
+WCHAR get_achar (		/* Get a character and advances ptr 1 or 2 */
+	const TCHAR** ptr	/* Pointer to pointer to the SBCS/DBCS/Unicode string */
+)
+{
+#if !_LFN_UNICODE
+	WCHAR chr;
+
+	chr = (BYTE)*(*ptr)++;					/* Get a byte */
+	if (IsLower(chr)) chr -= 0x20;			/* To upper ASCII char */
+#ifdef _EXCVT
+	if (chr >= 0x80) chr = ExCvt[chr - 0x80];	/* To upper SBCS extended char */
+#else
+	if (IsDBCS1(chr) && IsDBCS2(**ptr)) {		/* Get DBC 2nd byte if needed */
+		chr = chr << 8 | (BYTE)*(*ptr)++;
+	}
+#endif
+	return chr;
+#else
+	return ff_wtoupper(*(*ptr)++);			/* Get a word and to upper */
+#endif
+}
+
+
+static
+int pattern_matching (	/* 0:not matched, 1:matched */
+	const TCHAR* pat,	/* Matching pattern */
+	const TCHAR* nam,	/* String to be tested */
+	int skip,			/* Number of pre-skip chars (number of ?s) */
+	int inf				/* Infinite search (* specified) */
+)
+{
+	const TCHAR *pp, *np;
+	WCHAR pc, nc;
+	int nm, nx;
+
+
+	while (skip--) {				/* Pre-skip name chars */
+		if (!get_achar(&nam)) return 0;	/* Branch mismatched if less name chars */
+	}
+	if (!*pat && inf) return 1;		/* (short circuit) */
+
+	do {
+		pp = pat; np = nam;			/* Top of pattern and name to match */
+		for (;;) {
+			if (*pp == '?' || *pp == '*') {	/* Wildcard? */
+				nm = nx = 0;
+				do {				/* Analyze the wildcard chars */
+					if (*pp++ == '?') nm++; else nx = 1;
+				} while (*pp == '?' || *pp == '*');
+				if (pattern_matching(pp, np, nm, nx)) return 1;	/* Test new branch (recurs upto number of wildcard blocks in the pattern) */
+				nc = *np; break;	/* Branch mismatched */
+			}
+			pc = get_achar(&pp);	/* Get a pattern char */
+			nc = get_achar(&np);	/* Get a name char */
+			if (pc != nc) break;	/* Branch mismatched? */
+			if (pc == 0) return 1;	/* Branch matched? (matched at end of both strings) */
+		}
+		get_achar(&nam);			/* nam++ */
+	} while (inf && nc);			/* Retry until end of name if infinite search is specified */
+
+	return 0;
+}
+
+#endif /* _USE_FIND && _FS_MINIMIZE <= 1 */
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Pick a top segment and create the object name in directory form       */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT create_name (	/* FR_OK: successful, FR_INVALID_NAME: could not create */
+	DIR* dp,			/* Pointer to the directory object */
+	const TCHAR** path	/* Pointer to pointer to the segment in the path string */
+)
+{
+#if _USE_LFN != 0	/* LFN configuration */
+	BYTE b, cf;
+	WCHAR w, *lfn;
+	UINT i, ni, si, di;
+	const TCHAR *p;
+
+	/* Create LFN in Unicode */
+	p = *path; lfn = dp->obj.fs->lfnbuf; si = di = 0;
+	for (;;) {
+		w = p[si++];					/* Get a character */
+		if (w < ' ') break;				/* Break if end of the path name */
+		if (w == '/' || w == '\\') {	/* Break if a separator is found */
+			while (p[si] == '/' || p[si] == '\\') si++;	/* Skip duplicated separator if exist */
+			break;
+		}
+		if (di >= _MAX_LFN) return FR_INVALID_NAME;	/* Reject too long name */
+#if !_LFN_UNICODE
+		w &= 0xFF;
+		if (IsDBCS1(w)) {				/* Check if it is a DBC 1st byte (always false on SBCS cfg) */
+			b = (BYTE)p[si++];			/* Get 2nd byte */
+			w = (w << 8) + b;			/* Create a DBC */
+			if (!IsDBCS2(b)) return FR_INVALID_NAME;	/* Reject invalid sequence */
+		}
+		w = ff_convert(w, 1);			/* Convert ANSI/OEM to Unicode */
+		if (!w) return FR_INVALID_NAME;	/* Reject invalid code */
+#endif
+		if (w < 0x80 && chk_chr("\"*:<>\?|\x7F", w)) return FR_INVALID_NAME;	/* Reject illegal characters for LFN */
+		lfn[di++] = w;					/* Store the Unicode character */
+	}
+	*path = &p[si];						/* Return pointer to the next segment */
+	cf = (w < ' ') ? NS_LAST : 0;		/* Set last segment flag if end of the path */
+#if _FS_RPATH != 0
+	if ((di == 1 && lfn[di - 1] == '.') ||
+		(di == 2 && lfn[di - 1] == '.' && lfn[di - 2] == '.')) {	/* Is this segment a dot name? */
+		lfn[di] = 0;
+		for (i = 0; i < 11; i++)		/* Create dot name for SFN entry */
+			dp->fn[i] = (i < di) ? '.' : ' ';
+		dp->fn[i] = cf | NS_DOT;		/* This is a dot entry */
+		return FR_OK;
+	}
+#endif
+	while (di) {						/* Snip off trailing spaces and dots if exist */
+		w = lfn[di - 1];
+		if (w != ' ' && w != '.') break;
+		di--;
+	}
+	lfn[di] = 0;						/* LFN is created */
+	if (di == 0) return FR_INVALID_NAME;	/* Reject nul name */
+
+	/* Create SFN in directory form */
+	mem_set(dp->fn, ' ', 11);
+	for (si = 0; lfn[si] == ' ' || lfn[si] == '.'; si++) ;	/* Strip leading spaces and dots */
+	if (si) cf |= NS_LOSS | NS_LFN;
+	while (di && lfn[di - 1] != '.') di--;	/* Find extension (di<=si: no extension) */
+
+	i = b = 0; ni = 8;
+	for (;;) {
+		w = lfn[si++];					/* Get an LFN character */
+		if (!w) break;					/* Break on end of the LFN */
+		if (w == ' ' || (w == '.' && si != di)) {	/* Remove spaces and dots */
+			cf |= NS_LOSS | NS_LFN; continue;
+		}
+
+		if (i >= ni || si == di) {		/* Extension or end of SFN */
+			if (ni == 11) {				/* Long extension */
+				cf |= NS_LOSS | NS_LFN; break;
+			}
+			if (si != di) cf |= NS_LOSS | NS_LFN;	/* Out of 8.3 format */
+			if (si > di) break;			/* No extension */
+			si = di; i = 8; ni = 11;	/* Enter extension section */
+			b <<= 2; continue;
+		}
+
+		if (w >= 0x80) {				/* Non ASCII character */
+#ifdef _EXCVT
+			w = ff_convert(w, 0);		/* Unicode -> OEM code */
+			if (w) w = ExCvt[w - 0x80];	/* Convert extended character to upper (SBCS) */
+#else
+			w = ff_convert(ff_wtoupper(w), 0);	/* Upper converted Unicode -> OEM code */
+#endif
+			cf |= NS_LFN;				/* Force create LFN entry */
+		}
+
+		if (_DF1S && w >= 0x100) {		/* Is this DBC? (always false at SBCS cfg) */
+			if (i >= ni - 1) {
+				cf |= NS_LOSS | NS_LFN; i = ni; continue;
+			}
+			dp->fn[i++] = (BYTE)(w >> 8);
+		} else {						/* SBC */
+			if (!w || chk_chr("+,;=[]", w)) {	/* Replace illegal characters for SFN */
+				w = '_'; cf |= NS_LOSS | NS_LFN;/* Lossy conversion */
+			} else {
+				if (IsUpper(w)) {		/* ASCII large capital */
+					b |= 2;
+				} else {
+					if (IsLower(w)) {	/* ASCII small capital */
+						b |= 1; w -= 0x20;
+					}
+				}
+			}
+		}
+		dp->fn[i++] = (BYTE)w;
+	}
+
+	if (dp->fn[0] == DDEM) dp->fn[0] = RDDEM;	/* If the first character collides with DDEM, replace it with RDDEM */
+
+	if (ni == 8) b <<= 2;
+	if ((b & 0x0C) == 0x0C || (b & 0x03) == 0x03) cf |= NS_LFN;	/* Create LFN entry when there are composite capitals */
+	if (!(cf & NS_LFN)) {						/* When LFN is in 8.3 format without extended character, NT flags are created */
+		if ((b & 0x03) == 0x01) cf |= NS_EXT;	/* NT flag (Extension has only small capital) */
+		if ((b & 0x0C) == 0x04) cf |= NS_BODY;	/* NT flag (Filename has only small capital) */
+	}
+
+	dp->fn[NSFLAG] = cf;	/* SFN is created */
+
+	return FR_OK;
+
+
+#else	/* _USE_LFN != 0 : Non-LFN configuration */
+	BYTE c, d, *sfn;
+	UINT ni, si, i;
+	const char *p;
+
+	/* Create file name in directory form */
+	p = *path; sfn = dp->fn;
+	mem_set(sfn, ' ', 11);
+	si = i = 0; ni = 8;
+#if _FS_RPATH != 0
+	if (p[si] == '.') { /* Is this a dot entry? */
+		for (;;) {
+			c = (BYTE)p[si++];
+			if (c != '.' || si >= 3) break;
+			sfn[i++] = c;
+		}
+		if (c != '/' && c != '\\' && c > ' ') return FR_INVALID_NAME;
+		*path = p + si;								/* Return pointer to the next segment */
+		sfn[NSFLAG] = (c <= ' ') ? NS_LAST | NS_DOT : NS_DOT;	/* Set last segment flag if end of the path */
+		return FR_OK;
+	}
+#endif
+	for (;;) {
+		c = (BYTE)p[si++];
+		if (c <= ' ') break; 			/* Break if end of the path name */
+		if (c == '/' || c == '\\') {	/* Break if a separator is found */
+			while (p[si] == '/' || p[si] == '\\') si++;	/* Skip duplicated separator if exist */
+			break;
+		}
+		if (c == '.' || i >= ni) {		/* End of body or over size? */
+			if (ni == 11 || c != '.') return FR_INVALID_NAME;	/* Over size or invalid dot */
+			i = 8; ni = 11;				/* Goto extension */
+			continue;
+		}
+		if (c >= 0x80) {				/* Extended character? */
+#ifdef _EXCVT
+			c = ExCvt[c - 0x80];		/* To upper extended characters (SBCS cfg) */
+#else
+#if !_DF1S
+			return FR_INVALID_NAME;		/* Reject extended characters (ASCII only cfg) */
+#endif
+#endif
+		}
+		if (IsDBCS1(c)) {				/* Check if it is a DBC 1st byte (always false at SBCS cfg.) */
+			d = (BYTE)p[si++];			/* Get 2nd byte */
+			if (!IsDBCS2(d) || i >= ni - 1) return FR_INVALID_NAME;	/* Reject invalid DBC */
+			sfn[i++] = c;
+			sfn[i++] = d;
+		} else {						/* SBC */
+			if (chk_chr("\"*+,:;<=>\?[]|\x7F", c)) return FR_INVALID_NAME;	/* Reject illegal chrs for SFN */
+			if (IsLower(c)) c -= 0x20;	/* To upper */
+			sfn[i++] = c;
+		}
+	}
+	*path = p + si;						/* Return pointer to the next segment */
+	if (i == 0) return FR_INVALID_NAME;	/* Reject nul string */
+
+	if (sfn[0] == DDEM) sfn[0] = RDDEM;	/* If the first character collides with DDEM, replace it with RDDEM */
+	sfn[NSFLAG] = (c <= ' ') ? NS_LAST : 0;		/* Set last segment flag if end of the path */
+
+	return FR_OK;
+#endif /* _USE_LFN != 0 */
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Follow a file path                                                    */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT follow_path (	/* FR_OK(0): successful, !=0: error code */
+	DIR* dp,			/* Directory object to return last directory and found object */
+	const TCHAR* path	/* Full-path string to find a file or directory */
+)
+{
+	FRESULT res;
+	BYTE ns;
+	_FDID *obj = &dp->obj;
+	FATFS *fs = obj->fs;
+
+
+#if _FS_RPATH != 0
+	if (*path != '/' && *path != '\\') {	/* Without heading separator */
+		obj->sclust = fs->cdir;				/* Start from the current directory */
+	} else
+#endif
+	{										/* With heading separator */
+		while (*path == '/' || *path == '\\') path++;	/* Strip heading separator */
+		obj->sclust = 0;					/* Start from the root directory */
+	}
+#if _FS_EXFAT && _FS_RPATH != 0
+	if (fs->fs_type == FS_EXFAT && obj->sclust) {	/* Retrieve the sub-directory status if needed */
+		DIR dj;
+
+		obj->c_scl = fs->cdc_scl;
+		obj->c_size = fs->cdc_size;
+		obj->c_ofs = fs->cdc_ofs;
+		res = load_obj_dir(&dj, obj);
+		if (res != FR_OK) return res;
+		obj->objsize = ld_dword(fs->dirbuf + XDIR_FileSize);
+		obj->stat = fs->dirbuf[XDIR_GenFlags] & 2;
+	}
+#endif
+
+	if ((UINT)*path < ' ') {				/* Null path name is the origin directory itself */
+		dp->fn[NSFLAG] = NS_NONAME;
+		res = dir_sdi(dp, 0);
+
+	} else {								/* Follow path */
+		for (;;) {
+			res = create_name(dp, &path);	/* Get a segment name of the path */
+			if (res != FR_OK) break;
+			res = dir_find(dp);				/* Find an object with the segment name */
+			ns = dp->fn[NSFLAG];
+			if (res != FR_OK) {				/* Failed to find the object */
+				if (res == FR_NO_FILE) {	/* Object is not found */
+					if (_FS_RPATH && (ns & NS_DOT)) {	/* If dot entry is not exist, stay there */
+						if (!(ns & NS_LAST)) continue;	/* Continue to follow if not last segment */
+						dp->fn[NSFLAG] = NS_NONAME;
+						res = FR_OK;
+					} else {							/* Could not find the object */
+						if (!(ns & NS_LAST)) res = FR_NO_PATH;	/* Adjust error code if not last segment */
+					}
+				}
+				break;
+			}
+			if (ns & NS_LAST) break;			/* Last segment matched. Function completed. */
+			/* Get into the sub-directory */
+			if (!(obj->attr & AM_DIR)) {		/* It is not a sub-directory and cannot follow */
+				res = FR_NO_PATH; break;
+			}
+#if _FS_EXFAT
+			if (fs->fs_type == FS_EXFAT) {
+				obj->c_scl = obj->sclust;		/* Save containing directory information for next dir */
+				obj->c_size = ((DWORD)obj->objsize & 0xFFFFFF00) | obj->stat;
+				obj->c_ofs = dp->blk_ofs;
+				obj->sclust = ld_dword(fs->dirbuf + XDIR_FstClus);	/* Open next directory */
+				obj->stat = fs->dirbuf[XDIR_GenFlags] & 2;
+				obj->objsize = ld_qword(fs->dirbuf + XDIR_FileSize);
+			} else
+#endif
+			{
+				obj->sclust = ld_clust(fs, fs->win + dp->dptr % SS(fs));	/* Open next directory */
+			}
+		}
+	}
+
+	return res;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Get logical drive number from path name                               */
+/*-----------------------------------------------------------------------*/
+
+static
+int get_ldnumber (		/* Returns logical drive number (-1:invalid drive) */
+	const TCHAR** path	/* Pointer to pointer to the path name */
+)
+{
+	const TCHAR *tp, *tt;
+	UINT i;
+	int vol = -1;
+#if _STR_VOLUME_ID		/* Find string drive id */
+	static const char* const str[] = {_VOLUME_STRS};
+	const char *sp;
+	char c;
+	TCHAR tc;
+#endif
+
+
+	if (*path) {	/* If the pointer is not a null */
+		for (tt = *path; (UINT)*tt >= (_USE_LFN ? ' ' : '!') && *tt != ':'; tt++) ;	/* Find ':' in the path */
+		if (*tt == ':') {	/* If a ':' is exist in the path name */
+			tp = *path;
+			i = *tp++ - '0'; 
+			if (i < 10 && tp == tt) {	/* Is there a numeric drive id? */
+				if (i < _VOLUMES) {	/* If a drive id is found, get the value and strip it */
+					vol = (int)i;
+					*path = ++tt;
+				}
+			}
+#if _STR_VOLUME_ID
+			 else {	/* No numeric drive number, find string drive id */
+				i = 0; tt++;
+				do {
+					sp = str[i]; tp = *path;
+					do {	/* Compare a string drive id with path name */
+						c = *sp++; tc = *tp++;
+						if (IsLower(tc)) tc -= 0x20;
+					} while (c && (TCHAR)c == tc);
+				} while ((c || tp != tt) && ++i < _VOLUMES);	/* Repeat for each id until pattern match */
+				if (i < _VOLUMES) {	/* If a drive id is found, get the value and strip it */
+					vol = (int)i;
+					*path = tt;
+				}
+			}
+#endif
+			return vol;
+		}
+#if _FS_RPATH != 0 && _VOLUMES >= 2
+		vol = CurrVol;	/* Current drive */
+#else
+		vol = 0;		/* Drive 0 */
+#endif
+	}
+	return vol;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Load a sector and check if it is an FAT boot sector                   */
+/*-----------------------------------------------------------------------*/
+
+static
+BYTE check_fs (	/* 0:FAT, 1:exFAT, 2:Valid BS but not FAT, 3:Not a BS, 4:Disk error */
+	FATFS* fs,	/* File system object */
+	DWORD sect	/* Sector# (lba) to check if it is an FAT-VBR or not */
+)
+{
+	fs->wflag = 0; fs->winsect = 0xFFFFFFFF;		/* Invaidate window */
+	if (move_window(fs, sect) != FR_OK) return 4;	/* Load boot record */
+
+	if (ld_word(fs->win + BS_55AA) != 0xAA55) return 3;	/* Check boot record signature (always placed at offset 510 even if the sector size is >512) */
+
+	if (fs->win[BS_JmpBoot] == 0xE9 || (fs->win[BS_JmpBoot] == 0xEB && fs->win[BS_JmpBoot + 2] == 0x90)) {
+		if ((ld_dword(fs->win + BS_FilSysType) & 0xFFFFFF) == 0x544146) return 0;	/* Check "FAT" string */
+		if (ld_dword(fs->win + BS_FilSysType32) == 0x33544146) return 0;			/* Check "FAT3" string */
+	}
+#if _FS_EXFAT
+	if (!mem_cmp(fs->win + BS_JmpBoot, "\xEB\x76\x90" "EXFAT   ", 11)) return 1;
+#endif
+	return 2;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Find logical drive and check if the volume is mounted                 */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT find_volume (	/* FR_OK(0): successful, !=0: any error occurred */
+	const TCHAR** path,	/* Pointer to pointer to the path name (drive number) */
+	FATFS** rfs,		/* Pointer to pointer to the found file system object */
+	BYTE mode			/* !=0: Check write protection for write access */
+)
+{
+	BYTE fmt, *pt;
+	int vol;
+	DSTATUS stat;
+	DWORD bsect, fasize, tsect, sysect, nclst, szbfat, br[4];
+	WORD nrsv;
+	FATFS *fs;
+	UINT i;
+
+
+	/* Get logical drive number */
+	*rfs = 0;
+	vol = get_ldnumber(path);
+	if (vol < 0) return FR_INVALID_DRIVE;
+
+	/* Check if the file system object is valid or not */
+	fs = FatFs[vol];					/* Get pointer to the file system object */
+	if (!fs) return FR_NOT_ENABLED;		/* Is the file system object available? */
+
+	ENTER_FF(fs);						/* Lock the volume */
+	*rfs = fs;							/* Return pointer to the file system object */
+
+	mode &= (BYTE)~FA_READ;				/* Desired access mode, write access or not */
+	if (fs->fs_type) {					/* If the volume has been mounted */
+		stat = disk_status(fs->drv);
+		if (!(stat & STA_NOINIT)) {		/* and the physical drive is kept initialized */
+			if (!_FS_READONLY && mode && (stat & STA_PROTECT)) {	/* Check write protection if needed */
+				return FR_WRITE_PROTECTED;
+			}
+			return FR_OK;				/* The file system object is valid */
+		}
+	}
+
+	/* The file system object is not valid. */
+	/* Following code attempts to mount the volume. (analyze BPB and initialize the fs object) */
+
+	fs->fs_type = 0;					/* Clear the file system object */
+	fs->drv = LD2PD(vol);				/* Bind the logical drive and a physical drive */
+	stat = disk_initialize(fs->drv);	/* Initialize the physical drive */
+	if (stat & STA_NOINIT) { 			/* Check if the initialization succeeded */
+		return FR_NOT_READY;			/* Failed to initialize due to no medium or hard error */
+	}
+	if (!_FS_READONLY && mode && (stat & STA_PROTECT)) { /* Check disk write protection if needed */
+		return FR_WRITE_PROTECTED;
+	}
+#if _MAX_SS != _MIN_SS						/* Get sector size (multiple sector size cfg only) */
+	if (disk_ioctl(fs->drv, GET_SECTOR_SIZE, &SS(fs)) != RES_OK) return FR_DISK_ERR;
+	if (SS(fs) > _MAX_SS || SS(fs) < _MIN_SS || (SS(fs) & (SS(fs) - 1))) return FR_DISK_ERR;
+#endif
+	/* Find an FAT partition on the drive. Supports only generic partitioning, FDISK and SFD. */
+	bsect = 0;
+	fmt = check_fs(fs, bsect);			/* Load sector 0 and check if it is an FAT-VBR as SFD */
+	if (fmt == 2 || (fmt < 2 && LD2PT(vol) != 0)) {	/* Not an FAT-VBR or forced partition number */
+		for (i = 0; i < 4; i++) {			/* Get partition offset */
+			pt = fs->win + (MBR_Table + i * SZ_PTE);
+			br[i] = pt[PTE_System] ? ld_dword(pt + PTE_StLba) : 0;
+		}
+		i = LD2PT(vol);						/* Partition number: 0:auto, 1-4:forced */
+		if (i) i--;
+		do {								/* Find an FAT volume */
+			bsect = br[i];
+			fmt = bsect ? check_fs(fs, bsect) : 3;	/* Check the partition */
+		} while (!LD2PT(vol) && fmt >= 2 && ++i < 4);
+	}
+	if (fmt == 4) return FR_DISK_ERR;		/* An error occured in the disk I/O layer */
+	if (fmt >= 2) return FR_NO_FILESYSTEM;	/* No FAT volume is found */
+
+	/* An FAT volume is found. Following code initializes the file system object */
+
+#if _FS_EXFAT
+	if (fmt == 1) {
+		QWORD maxlba;
+
+		for (i = BPB_ZeroedEx; i < BPB_ZeroedEx + 53 && fs->win[i] == 0; i++) ;	/* Check zero filler */
+		if (i < BPB_ZeroedEx + 53) return FR_NO_FILESYSTEM;
+
+		if (ld_word(fs->win + BPB_FSVerEx) != 0x100) return FR_NO_FILESYSTEM;	/* Check exFAT revision (Must be 1.0) */
+
+		if (1 << fs->win[BPB_BytsPerSecEx] != SS(fs))	/* (BPB_BytsPerSecEx must be equal to the physical sector size) */
+			return FR_NO_FILESYSTEM;
+
+		maxlba = ld_qword(fs->win + BPB_TotSecEx) + bsect;	/* Last LBA + 1 of the volume */
+		if (maxlba >= 0x100000000) return FR_NO_FILESYSTEM;	/* (It cannot be handled in 32-bit LBA) */
+
+		fs->fsize = ld_dword(fs->win + BPB_FatSzEx);	/* Number of sectors per FAT */
+
+		fs->n_fats = fs->win[BPB_NumFATsEx];			/* Number of FATs */
+		if (fs->n_fats != 1) return FR_NO_FILESYSTEM;	/* (Supports only 1 FAT) */
+
+		fs->csize = 1 << fs->win[BPB_SecPerClusEx];		/* Cluster size */
+		if (fs->csize == 0)	return FR_NO_FILESYSTEM;	/* (Must be 1..32768) */
+
+		nclst = ld_dword(fs->win + BPB_NumClusEx);		/* Number of clusters */
+		if (nclst > MAX_EXFAT) return FR_NO_FILESYSTEM;	/* (Too many clusters) */
+		fs->n_fatent = nclst + 2;
+
+		/* Boundaries and Limits */
+		fs->volbase = bsect;
+		fs->database = bsect + ld_dword(fs->win + BPB_DataOfsEx);
+		fs->fatbase = bsect + ld_dword(fs->win + BPB_FatOfsEx);
+		if (maxlba < (QWORD)fs->database + nclst * fs->csize) return FR_NO_FILESYSTEM;	/* (Volume size must not be smaller than the size requiered) */
+		fs->dirbase = ld_dword(fs->win + BPB_RootClusEx);
+
+		/* Check if bitmap location is in assumption (at the first cluster) */
+		if (move_window(fs, clust2sect(fs, fs->dirbase)) != FR_OK) return FR_DISK_ERR;
+		for (i = 0; i < SS(fs); i += SZDIRE) {
+			if (fs->win[i] == 0x81 && ld_dword(fs->win + i + 20) == 2) break;	/* 81 entry with cluster #2? */
+		}
+		if (i == SS(fs)) return FR_NO_FILESYSTEM;
+#if !_FS_READONLY
+		fs->last_clst = fs->free_clst = 0xFFFFFFFF;		/* Initialize cluster allocation information */
+#endif
+		fmt = FS_EXFAT;			/* FAT sub-type */
+	} else
+#endif	/* _FS_EXFAT */
+	{
+		if (ld_word(fs->win + BPB_BytsPerSec) != SS(fs)) return FR_NO_FILESYSTEM;	/* (BPB_BytsPerSec must be equal to the physical sector size) */
+
+		fasize = ld_word(fs->win + BPB_FATSz16);			/* Number of sectors per FAT */
+		if (fasize == 0) fasize = ld_dword(fs->win + BPB_FATSz32);
+		fs->fsize = fasize;
+
+		fs->n_fats = fs->win[BPB_NumFATs];					/* Number of FATs */
+		if (fs->n_fats != 1 && fs->n_fats != 2) return FR_NO_FILESYSTEM;	/* (Must be 1 or 2) */
+		fasize *= fs->n_fats;								/* Number of sectors for FAT area */
+
+		fs->csize = fs->win[BPB_SecPerClus];				/* Cluster size */
+		if (fs->csize == 0 || (fs->csize & (fs->csize - 1))) return FR_NO_FILESYSTEM;	/* (Must be power of 2) */
+
+		fs->n_rootdir = ld_word(fs->win + BPB_RootEntCnt);	/* Number of root directory entries */
+		if (fs->n_rootdir % (SS(fs) / SZDIRE)) return FR_NO_FILESYSTEM;	/* (Must be sector aligned) */
+
+		tsect = ld_word(fs->win + BPB_TotSec16);			/* Number of sectors on the volume */
+		if (tsect == 0) tsect = ld_dword(fs->win + BPB_TotSec32);
+
+		nrsv = ld_word(fs->win + BPB_RsvdSecCnt);			/* Number of reserved sectors */
+		if (nrsv == 0) return FR_NO_FILESYSTEM;				/* (Must not be 0) */
+
+		/* Determine the FAT sub type */
+		sysect = nrsv + fasize + fs->n_rootdir / (SS(fs) / SZDIRE);	/* RSV + FAT + DIR */
+		if (tsect < sysect) return FR_NO_FILESYSTEM;		/* (Invalid volume size) */
+		nclst = (tsect - sysect) / fs->csize;				/* Number of clusters */
+		if (nclst == 0) return FR_NO_FILESYSTEM;			/* (Invalid volume size) */
+		fmt = FS_FAT32;
+		if (nclst <= MAX_FAT16) fmt = FS_FAT16;
+		if (nclst <= MAX_FAT12) fmt = FS_FAT12;
+
+		/* Boundaries and Limits */
+		fs->n_fatent = nclst + 2;							/* Number of FAT entries */
+		fs->volbase = bsect;								/* Volume start sector */
+		fs->fatbase = bsect + nrsv; 						/* FAT start sector */
+		fs->database = bsect + sysect;						/* Data start sector */
+		if (fmt == FS_FAT32) {
+			if (ld_word(fs->win + BPB_FSVer32) != 0) return FR_NO_FILESYSTEM;	/* (Must be FAT32 revision 0.0) */
+			if (fs->n_rootdir) return FR_NO_FILESYSTEM;		/* (BPB_RootEntCnt must be 0) */
+			fs->dirbase = ld_dword(fs->win + BPB_RootClus32);	/* Root directory start cluster */
+			szbfat = fs->n_fatent * 4;						/* (Needed FAT size) */
+		} else {
+			if (fs->n_rootdir == 0)	return FR_NO_FILESYSTEM;/* (BPB_RootEntCnt must not be 0) */
+			fs->dirbase = fs->fatbase + fasize;				/* Root directory start sector */
+			szbfat = (fmt == FS_FAT16) ?					/* (Needed FAT size) */
+				fs->n_fatent * 2 : fs->n_fatent * 3 / 2 + (fs->n_fatent & 1);
+		}
+		if (fs->fsize < (szbfat + (SS(fs) - 1)) / SS(fs)) return FR_NO_FILESYSTEM;	/* (BPB_FATSz must not be less than the size needed) */
+
+#if !_FS_READONLY
+		/* Get FSINFO if available */
+		fs->last_clst = fs->free_clst = 0xFFFFFFFF;		/* Initialize cluster allocation information */
+		fs->fsi_flag = 0x80;
+#if (_FS_NOFSINFO & 3) != 3
+		if (fmt == FS_FAT32				/* Enable FSINFO only if FAT32 and BPB_FSInfo32 == 1 */
+			&& ld_word(fs->win + BPB_FSInfo32) == 1
+			&& move_window(fs, bsect + 1) == FR_OK)
+		{
+			fs->fsi_flag = 0;
+			if (ld_word(fs->win + BS_55AA) == 0xAA55	/* Load FSINFO data if available */
+				&& ld_dword(fs->win + FSI_LeadSig) == 0x41615252
+				&& ld_dword(fs->win + FSI_StrucSig) == 0x61417272)
+			{
+#if (_FS_NOFSINFO & 1) == 0
+				fs->free_clst = ld_dword(fs->win + FSI_Free_Count);
+#endif
+#if (_FS_NOFSINFO & 2) == 0
+				fs->last_clst = ld_dword(fs->win + FSI_Nxt_Free);
+#endif
+			}
+		}
+#endif	/* (_FS_NOFSINFO & 3) != 3 */
+#endif	/* !_FS_READONLY */
+	}
+
+	fs->fs_type = fmt;	/* FAT sub-type */
+	fs->id = ++Fsid;	/* File system mount ID */
+#if _USE_LFN == 1
+	fs->lfnbuf = LfnBuf;	/* Static LFN working buffer */
+#if _FS_EXFAT
+	fs->dirbuf = DirBuf;	/* Static directory block working buuffer */
+#endif
+#endif
+#if _FS_RPATH != 0
+	fs->cdir = 0;		/* Initialize current directory */
+#endif
+#if _FS_LOCK != 0		/* Clear file lock semaphores */
+	clear_lock(fs);
+#endif
+	return FR_OK;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Check if the file/directory object is valid or not                    */
+/*-----------------------------------------------------------------------*/
+
+static
+FRESULT validate (	/* Returns FR_OK or FR_INVALID_OBJECT */
+	_FDID* obj,		/* Pointer to the _OBJ, the 1st member in the FIL/DIR object, to check validity */
+	FATFS** fs		/* Pointer to pointer to the owner file system object to return */
+)
+{
+	FRESULT res;
+
+
+	if (!obj || !obj->fs || !obj->fs->fs_type || obj->fs->id != obj->id || (disk_status(obj->fs->drv) & STA_NOINIT)) {
+		*fs = 0;				/* The object is invalid */
+		res = FR_INVALID_OBJECT;
+	} else {
+		*fs = obj->fs;			/* Owner file sytem object */
+		ENTER_FF(obj->fs);		/* Lock file system */
+		res = FR_OK;
+	}
+	return res;
+}
+
+
+
+
+/*---------------------------------------------------------------------------
+
+   Public Functions (FatFs API)
+
+----------------------------------------------------------------------------*/
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Mount/Unmount a Logical Drive                                         */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_mount (
+	FATFS* fs,			/* Pointer to the file system object (NULL:unmount)*/
+	const TCHAR* path,	/* Logical drive number to be mounted/unmounted */
+	BYTE opt			/* Mode option 0:Do not mount (delayed mount), 1:Mount immediately */
+)
+{
+	FATFS *cfs;
+	int vol;
+	FRESULT res;
+	const TCHAR *rp = path;
+
+
+	/* Get logical drive number */
+	vol = get_ldnumber(&rp);
+	if (vol < 0) return FR_INVALID_DRIVE;
+	cfs = FatFs[vol];					/* Pointer to fs object */
+
+	if (cfs) {
+#if _FS_LOCK != 0
+		clear_lock(cfs);
+#endif
+#if _FS_REENTRANT						/* Discard sync object of the current volume */
+		if (!ff_del_syncobj(cfs->sobj)) return FR_INT_ERR;
+#endif
+		cfs->fs_type = 0;				/* Clear old fs object */
+	}
+
+	if (fs) {
+		fs->fs_type = 0;				/* Clear new fs object */
+#if _FS_REENTRANT						/* Create sync object for the new volume */
+		if (!ff_cre_syncobj((BYTE)vol, &fs->sobj)) return FR_INT_ERR;
+#endif
+	}
+	FatFs[vol] = fs;					/* Register new fs object */
+
+	if (!fs || opt != 1) return FR_OK;	/* Do not mount now, it will be mounted later */
+
+	res = find_volume(&path, &fs, 0);	/* Force mounted the volume */
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Open or Create a File                                                 */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_open (
+	FIL* fp,			/* Pointer to the blank file object */
+	const TCHAR* path,	/* Pointer to the file name */
+	BYTE mode			/* Access mode and file open mode flags */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+#if !_FS_READONLY
+	DWORD dw, cl, bcs, clst, sc;
+	FSIZE_t ofs;
+#endif
+	DEF_NAMBUF
+
+
+	if (!fp) return FR_INVALID_OBJECT;
+
+	/* Get logical drive */
+	mode &= _FS_READONLY ? FA_READ : FA_READ | FA_WRITE | FA_CREATE_ALWAYS | FA_CREATE_NEW | FA_OPEN_ALWAYS | FA_OPEN_APPEND | FA_SEEKEND;
+	res = find_volume(&path, &fs, mode);
+	if (res == FR_OK) {
+		dj.obj.fs = fs;
+		INIT_NAMBUF(fs);
+		res = follow_path(&dj, path);	/* Follow the file path */
+#if !_FS_READONLY	/* R/W configuration */
+		if (res == FR_OK) {
+			if (dj.fn[NSFLAG] & NS_NONAME) {	/* Origin directory itself? */
+				res = FR_INVALID_NAME;
+			}
+#if _FS_LOCK != 0
+			else {
+				res = chk_lock(&dj, (mode & ~FA_READ) ? 1 : 0);
+			}
+#endif
+		}
+		/* Create or Open a file */
+		if (mode & (FA_CREATE_ALWAYS | FA_OPEN_ALWAYS | FA_CREATE_NEW)) {
+			if (res != FR_OK) {					/* No file, create new */
+				if (res == FR_NO_FILE)			/* There is no file to open, create a new entry */
+#if _FS_LOCK != 0
+					res = enq_lock() ? dir_register(&dj) : FR_TOO_MANY_OPEN_FILES;
+#else
+					res = dir_register(&dj);
+#endif
+				mode |= FA_CREATE_ALWAYS;		/* File is created */
+			}
+			else {								/* Any object is already existing */
+				if (dj.obj.attr & (AM_RDO | AM_DIR)) {	/* Cannot overwrite it (R/O or DIR) */
+					res = FR_DENIED;
+				} else {
+					if (mode & FA_CREATE_NEW) res = FR_EXIST;	/* Cannot create as new file */
+				}
+			}
+			if (res == FR_OK && (mode & FA_CREATE_ALWAYS)) {	/* Truncate it if overwrite mode */
+				dw = GET_FATTIME();
+#if _FS_EXFAT
+				if (fs->fs_type == FS_EXFAT) {
+					/* Get current allocation info */
+					fp->obj.fs = fs;
+					fp->obj.sclust = ld_dword(fs->dirbuf + XDIR_FstClus);
+					fp->obj.objsize = ld_qword(fs->dirbuf + XDIR_FileSize);
+					fp->obj.stat = fs->dirbuf[XDIR_GenFlags] & 2;
+					/* Initialize directory entry block */
+					st_dword(fs->dirbuf + XDIR_CrtTime, dw);	/* Set created time */
+					fs->dirbuf[XDIR_CrtTime10] = 0;
+					st_dword(fs->dirbuf + XDIR_ModTime, dw);	/* Set modified time */
+					fs->dirbuf[XDIR_ModTime10] = 0;
+					fs->dirbuf[XDIR_Attr] = AM_ARC;				/* Reset attribute */
+					st_dword(fs->dirbuf + XDIR_FstClus, 0);		/* Reset file allocation info */
+					st_qword(fs->dirbuf + XDIR_FileSize, 0);
+					st_qword(fs->dirbuf + XDIR_ValidFileSize, 0);
+					fs->dirbuf[XDIR_GenFlags] = 1;
+					res = store_xdir(&dj);
+					if (res == FR_OK && fp->obj.sclust) {		/* Remove the cluster chain if exist */
+						res = remove_chain(&fp->obj, fp->obj.sclust, 0);
+						fs->last_clst = fp->obj.sclust - 1;		/* Reuse the cluster hole */
+					}
+				} else
+#endif
+				{
+					/* Clean directory info */
+					st_dword(dj.dir + DIR_CrtTime, dw);	/* Set created time */
+					st_dword(dj.dir + DIR_ModTime, dw);	/* Set modified time */
+					dj.dir[DIR_Attr] = AM_ARC;			/* Reset attribute */
+					cl = ld_clust(fs, dj.dir);			/* Get cluster chain */
+					st_clust(fs, dj.dir, 0);			/* Reset file allocation info */
+					st_dword(dj.dir + DIR_FileSize, 0);
+					fs->wflag = 1;
+
+					if (cl) {							/* Remove the cluster chain if exist */
+						dw = fs->winsect;
+						res = remove_chain(&dj.obj, cl, 0);
+						if (res == FR_OK) {
+							res = move_window(fs, dw);
+							fs->last_clst = cl - 1;		/* Reuse the cluster hole */
+						}
+					}
+				}
+			}
+		}
+		else {	/* Open an existing file */
+			if (res == FR_OK) {					/* Following succeeded */
+				if (dj.obj.attr & AM_DIR) {		/* It is a directory */
+					res = FR_NO_FILE;
+				} else {
+					if ((mode & FA_WRITE) && (dj.obj.attr & AM_RDO)) { /* R/O violation */
+						res = FR_DENIED;
+					}
+				}
+			}
+		}
+		if (res == FR_OK) {
+			if (mode & FA_CREATE_ALWAYS)		/* Set file change flag if created or overwritten */
+				mode |= FA_MODIFIED;
+			fp->dir_sect = fs->winsect;			/* Pointer to the directory entry */
+			fp->dir_ptr = dj.dir;
+#if _FS_LOCK != 0
+			fp->obj.lockid = inc_lock(&dj, (mode & ~FA_READ) ? 1 : 0);
+			if (!fp->obj.lockid) res = FR_INT_ERR;
+#endif
+		}
+#else		/* R/O configuration */
+		if (res == FR_OK) {
+			if (dj.fn[NSFLAG] & NS_NONAME) {	/* Origin directory itself? */
+				res = FR_INVALID_NAME;
+			} else {
+				if (dj.obj.attr & AM_DIR) {		/* It is a directory */
+					res = FR_NO_FILE;
+				}
+			}
+		}
+#endif
+
+		if (res == FR_OK) {
+#if _FS_EXFAT
+			if (fs->fs_type == FS_EXFAT) {
+				fp->obj.sclust = ld_dword(fs->dirbuf + XDIR_FstClus);		/* Get allocation info */
+				fp->obj.objsize = ld_qword(fs->dirbuf + XDIR_FileSize);
+				fp->obj.stat = fs->dirbuf[XDIR_GenFlags] & 2;
+				fp->obj.c_scl = dj.obj.sclust;
+				fp->obj.c_size = ((DWORD)dj.obj.objsize & 0xFFFFFF00) | dj.obj.stat;
+				fp->obj.c_ofs = dj.blk_ofs;
+			} else
+#endif
+			{
+				fp->obj.sclust = ld_clust(fs, dj.dir);				/* Get allocation info */
+				fp->obj.objsize = ld_dword(dj.dir + DIR_FileSize);
+			}
+#if _USE_FASTSEEK
+			fp->cltbl = 0;			/* Disable fast seek mode */
+#endif
+			fp->obj.fs = fs;	 	/* Validate the file object */
+			fp->obj.id = fs->id;
+			fp->flag = mode;		/* Set file access mode */
+			fp->err = 0;			/* Clear error flag */
+			fp->sect = 0;			/* Invalidate current data sector */
+			fp->fptr = 0;			/* Set file pointer top of the file */
+#if !_FS_READONLY
+#if !_FS_TINY
+			mem_set(fp->buf, 0, _MAX_SS);	/* Clear sector buffer */
+#endif
+			if ((mode & FA_SEEKEND) && fp->obj.objsize > 0) {	/* Seek to end of file if FA_OPEN_APPEND is specified */
+				fp->fptr = fp->obj.objsize;			/* Offset to seek */
+				bcs = (DWORD)fs->csize * SS(fs);	/* Cluster size in byte */
+				clst = fp->obj.sclust;				/* Follow the cluster chain */
+				for (ofs = fp->obj.objsize; res == FR_OK && ofs > bcs; ofs -= bcs) {
+					clst = get_fat(&fp->obj, clst);
+					if (clst <= 1) res = FR_INT_ERR;
+					if (clst == 0xFFFFFFFF) res = FR_DISK_ERR;
+				}
+				fp->clust = clst;
+				if (res == FR_OK && ofs % SS(fs)) {	/* Fill sector buffer if not on the sector boundary */
+					if ((sc = clust2sect(fs, clst)) == 0) {
+						res = FR_INT_ERR;
+					} else {
+						fp->sect = sc + (DWORD)(ofs / SS(fs));
+#if !_FS_TINY
+						if (disk_read(fs->drv, fp->buf, fp->sect, 1) != RES_OK) res = FR_DISK_ERR;
+#endif
+					}
+				}
+			}
+#endif
+		}
+
+		FREE_NAMBUF();
+	}
+
+	if (res != FR_OK) fp->obj.fs = 0;	/* Invalidate file object on error */
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Read File                                                             */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_read (
+	FIL* fp, 	/* Pointer to the file object */
+	void* buff,	/* Pointer to data buffer */
+	UINT btr,	/* Number of bytes to read */
+	UINT* br	/* Pointer to number of bytes read */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD clst, sect;
+	FSIZE_t remain;
+	UINT rcnt, cc, csect;
+	BYTE *rbuff = (BYTE*)buff;
+
+
+	*br = 0;	/* Clear read byte counter */
+	res = validate(&fp->obj, &fs);				/* Check validity of the file object */
+	if (res != FR_OK || (res = (FRESULT)fp->err) != FR_OK) LEAVE_FF(fs, res);	/* Check validity */
+	if (!(fp->flag & FA_READ)) LEAVE_FF(fs, FR_DENIED); /* Check access mode */
+	remain = fp->obj.objsize - fp->fptr;
+	if (btr > remain) btr = (UINT)remain;		/* Truncate btr by remaining bytes */
+
+	for ( ;  btr;								/* Repeat until all data read */
+		rbuff += rcnt, fp->fptr += rcnt, *br += rcnt, btr -= rcnt) {
+		if (fp->fptr % SS(fs) == 0) {			/* On the sector boundary? */
+			csect = (UINT)(fp->fptr / SS(fs) & (fs->csize - 1));	/* Sector offset in the cluster */
+			if (csect == 0) {					/* On the cluster boundary? */
+				if (fp->fptr == 0) {			/* On the top of the file? */
+					clst = fp->obj.sclust;		/* Follow cluster chain from the origin */
+				} else {						/* Middle or end of the file */
+#if _USE_FASTSEEK
+					if (fp->cltbl) {
+						clst = clmt_clust(fp, fp->fptr);	/* Get cluster# from the CLMT */
+					} else
+#endif
+					{
+						clst = get_fat(&fp->obj, fp->clust);	/* Follow cluster chain on the FAT */
+					}
+				}
+				if (clst < 2) ABORT(fs, FR_INT_ERR);
+				if (clst == 0xFFFFFFFF) ABORT(fs, FR_DISK_ERR);
+				fp->clust = clst;				/* Update current cluster */
+			}
+			sect = clust2sect(fs, fp->clust);	/* Get current sector */
+			if (!sect) ABORT(fs, FR_INT_ERR);
+			sect += csect;
+			cc = btr / SS(fs);					/* When remaining bytes >= sector size, */
+			if (cc) {							/* Read maximum contiguous sectors directly */
+				if (csect + cc > fs->csize) {	/* Clip at cluster boundary */
+					cc = fs->csize - csect;
+				}
+				if (disk_read(fs->drv, rbuff, sect, cc) != RES_OK) ABORT(fs, FR_DISK_ERR);
+#if !_FS_READONLY && _FS_MINIMIZE <= 2			/* Replace one of the read sectors with cached data if it contains a dirty sector */
+#if _FS_TINY
+				if (fs->wflag && fs->winsect - sect < cc) {
+					mem_cpy(rbuff + ((fs->winsect - sect) * SS(fs)), fs->win, SS(fs));
+				}
+#else
+				if ((fp->flag & FA_DIRTY) && fp->sect - sect < cc) {
+					mem_cpy(rbuff + ((fp->sect - sect) * SS(fs)), fp->buf, SS(fs));
+				}
+#endif
+#endif
+				rcnt = SS(fs) * cc;				/* Number of bytes transferred */
+				continue;
+			}
+#if !_FS_TINY
+			if (fp->sect != sect) {			/* Load data sector if not in cache */
+#if !_FS_READONLY
+				if (fp->flag & FA_DIRTY) {		/* Write-back dirty sector cache */
+					if (disk_write(fs->drv, fp->buf, fp->sect, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);
+					fp->flag &= (BYTE)~FA_DIRTY;
+				}
+#endif
+				if (disk_read(fs->drv, fp->buf, sect, 1) != RES_OK)	ABORT(fs, FR_DISK_ERR);	/* Fill sector cache */
+			}
+#endif
+			fp->sect = sect;
+		}
+		rcnt = SS(fs) - (UINT)fp->fptr % SS(fs);	/* Number of bytes left in the sector */
+		if (rcnt > btr) rcnt = btr;					/* Clip it by btr if needed */
+#if _FS_TINY
+		if (move_window(fs, fp->sect) != FR_OK) ABORT(fs, FR_DISK_ERR);	/* Move sector window */
+		mem_cpy(rbuff, fs->win + fp->fptr % SS(fs), rcnt);	/* Extract partial sector */
+#else
+		mem_cpy(rbuff, fp->buf + fp->fptr % SS(fs), rcnt);	/* Extract partial sector */
+#endif
+	}
+
+	LEAVE_FF(fs, FR_OK);
+}
+
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Write File                                                            */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_write (
+	FIL* fp,			/* Pointer to the file object */
+	const void* buff,	/* Pointer to the data to be written */
+	UINT btw,			/* Number of bytes to write */
+	UINT* bw			/* Pointer to number of bytes written */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD clst, sect;
+	UINT wcnt, cc, csect;
+	const BYTE *wbuff = (const BYTE*)buff;
+
+
+	*bw = 0;	/* Clear write byte counter */
+	res = validate(&fp->obj, &fs);			/* Check validity of the file object */
+	if (res != FR_OK || (res = (FRESULT)fp->err) != FR_OK) LEAVE_FF(fs, res);	/* Check validity */
+	if (!(fp->flag & FA_WRITE)) LEAVE_FF(fs, FR_DENIED);	/* Check access mode */
+
+	/* Check fptr wrap-around (file size cannot reach 4GiB on FATxx) */
+	if ((!_FS_EXFAT || fs->fs_type != FS_EXFAT) && (DWORD)(fp->fptr + btw) < (DWORD)fp->fptr) {
+		btw = (UINT)(0xFFFFFFFF - (DWORD)fp->fptr);
+	}
+
+	for ( ;  btw;							/* Repeat until all data written */
+		wbuff += wcnt, fp->fptr += wcnt, fp->obj.objsize = (fp->fptr > fp->obj.objsize) ? fp->fptr : fp->obj.objsize, *bw += wcnt, btw -= wcnt) {
+		if (fp->fptr % SS(fs) == 0) {		/* On the sector boundary? */
+			csect = (UINT)(fp->fptr / SS(fs)) & (fs->csize - 1);	/* Sector offset in the cluster */
+			if (csect == 0) {				/* On the cluster boundary? */
+				if (fp->fptr == 0) {		/* On the top of the file? */
+					clst = fp->obj.sclust;	/* Follow from the origin */
+					if (clst == 0) {		/* If no cluster is allocated, */
+						clst = create_chain(&fp->obj, 0);	/* create a new cluster chain */
+					}
+				} else {					/* On the middle or end of the file */
+#if _USE_FASTSEEK
+					if (fp->cltbl) {
+						clst = clmt_clust(fp, fp->fptr);	/* Get cluster# from the CLMT */
+					} else
+#endif
+					{
+						clst = create_chain(&fp->obj, fp->clust);	/* Follow or stretch cluster chain on the FAT */
+					}
+				}
+				if (clst == 0) break;		/* Could not allocate a new cluster (disk full) */
+				if (clst == 1) ABORT(fs, FR_INT_ERR);
+				if (clst == 0xFFFFFFFF) ABORT(fs, FR_DISK_ERR);
+				fp->clust = clst;			/* Update current cluster */
+				if (fp->obj.sclust == 0) fp->obj.sclust = clst;	/* Set start cluster if the first write */
+			}
+#if _FS_TINY
+			if (fs->winsect == fp->sect && sync_window(fs) != FR_OK) ABORT(fs, FR_DISK_ERR);	/* Write-back sector cache */
+#else
+			if (fp->flag & FA_DIRTY) {		/* Write-back sector cache */
+				if (disk_write(fs->drv, fp->buf, fp->sect, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);
+				fp->flag &= (BYTE)~FA_DIRTY;
+			}
+#endif
+			sect = clust2sect(fs, fp->clust);	/* Get current sector */
+			if (!sect) ABORT(fs, FR_INT_ERR);
+			sect += csect;
+			cc = btw / SS(fs);				/* When remaining bytes >= sector size, */
+			if (cc) {						/* Write maximum contiguous sectors directly */
+				if (csect + cc > fs->csize) {	/* Clip at cluster boundary */
+					cc = fs->csize - csect;
+				}
+				if (disk_write(fs->drv, wbuff, sect, cc) != RES_OK) ABORT(fs, FR_DISK_ERR);
+#if _FS_MINIMIZE <= 2
+#if _FS_TINY
+				if (fs->winsect - sect < cc) {	/* Refill sector cache if it gets invalidated by the direct write */
+					mem_cpy(fs->win, wbuff + ((fs->winsect - sect) * SS(fs)), SS(fs));
+					fs->wflag = 0;
+				}
+#else
+				if (fp->sect - sect < cc) { /* Refill sector cache if it gets invalidated by the direct write */
+					mem_cpy(fp->buf, wbuff + ((fp->sect - sect) * SS(fs)), SS(fs));
+					fp->flag &= (BYTE)~FA_DIRTY;
+				}
+#endif
+#endif
+				wcnt = SS(fs) * cc;		/* Number of bytes transferred */
+				continue;
+			}
+#if _FS_TINY
+			if (fp->fptr >= fp->obj.objsize) {	/* Avoid silly cache filling on the growing edge */
+				if (sync_window(fs) != FR_OK) ABORT(fs, FR_DISK_ERR);
+				fs->winsect = sect;
+			}
+#else
+			if (fp->sect != sect && 		/* Fill sector cache with file data */
+				fp->fptr < fp->obj.objsize &&
+				disk_read(fs->drv, fp->buf, sect, 1) != RES_OK) {
+					ABORT(fs, FR_DISK_ERR);
+			}
+#endif
+			fp->sect = sect;
+		}
+		wcnt = SS(fs) - (UINT)fp->fptr % SS(fs);	/* Number of bytes left in the sector */
+		if (wcnt > btw) wcnt = btw;					/* Clip it by btw if needed */
+#if _FS_TINY
+		if (move_window(fs, fp->sect) != FR_OK) ABORT(fs, FR_DISK_ERR);	/* Move sector window */
+		mem_cpy(fs->win + fp->fptr % SS(fs), wbuff, wcnt);	/* Fit data to the sector */
+		fs->wflag = 1;
+#else
+		mem_cpy(fp->buf + fp->fptr % SS(fs), wbuff, wcnt);	/* Fit data to the sector */
+		fp->flag |= FA_DIRTY;
+#endif
+	}
+
+	fp->flag |= FA_MODIFIED;				/* Set file change flag */
+
+	LEAVE_FF(fs, FR_OK);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Synchronize the File                                                  */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_sync (
+	FIL* fp		/* Pointer to the file object */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD tm;
+	BYTE *dir;
+	//DEF_NAMBUF // TA: Removed FIXME?
+
+
+	res = validate(&fp->obj, &fs);	/* Check validity of the file object */
+	if (res == FR_OK) {
+		if (fp->flag & FA_MODIFIED) {	/* Is there any change to the file? */
+#if !_FS_TINY
+			if (fp->flag & FA_DIRTY) {	/* Write-back cached data if needed */
+				if (disk_write(fs->drv, fp->buf, fp->sect, 1) != RES_OK) LEAVE_FF(fs, FR_DISK_ERR);
+				fp->flag &= (BYTE)~FA_DIRTY;
+			}
+#endif
+			/* Update the directory entry */
+			tm = GET_FATTIME();				/* Modified time */
+#if _FS_EXFAT
+			if (fs->fs_type == FS_EXFAT) {
+				res = fill_fat_chain(&fp->obj);	/* Create FAT chain if needed */
+				if (res == FR_OK) {
+					DIR dj;
+
+					INIT_NAMBUF(fs);
+					res = load_obj_dir(&dj, &fp->obj);	/* Load directory entry block */
+					if (res == FR_OK) {
+						fs->dirbuf[XDIR_Attr] |= AM_ARC;				/* Set archive bit */
+						fs->dirbuf[XDIR_GenFlags] = fp->obj.stat | 1;	/* Update file allocation info */
+						st_dword(fs->dirbuf + XDIR_FstClus, fp->obj.sclust);
+						st_qword(fs->dirbuf + XDIR_FileSize, fp->obj.objsize);
+						st_qword(fs->dirbuf + XDIR_ValidFileSize, fp->obj.objsize);
+						st_dword(fs->dirbuf + XDIR_ModTime, tm);		/* Update modified time */
+						fs->dirbuf[XDIR_ModTime10] = 0;
+						st_dword(fs->dirbuf + XDIR_AccTime, 0);
+						res = store_xdir(&dj);	/* Restore it to the directory */
+						if (res == FR_OK) {
+							res = sync_fs(fs);
+							fp->flag &= (BYTE)~FA_MODIFIED;
+						}
+					}
+					FREE_NAMBUF();
+				}
+			} else
+#endif
+			{
+				res = move_window(fs, fp->dir_sect);
+				if (res == FR_OK) {
+					dir = fp->dir_ptr;
+					dir[DIR_Attr] |= AM_ARC;						/* Set archive bit */
+					st_clust(fp->obj.fs, dir, fp->obj.sclust);		/* Update file allocation info  */
+					st_dword(dir + DIR_FileSize, (DWORD)fp->obj.objsize);	/* Update file size */
+					st_dword(dir + DIR_ModTime, tm);				/* Update modified time */
+					st_word(dir + DIR_LstAccDate, 0);
+					fs->wflag = 1;
+					res = sync_fs(fs);					/* Restore it to the directory */
+					fp->flag &= (BYTE)~FA_MODIFIED;
+				}
+			}
+		}
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+#endif /* !_FS_READONLY */
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Close File                                                            */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_close (
+	FIL* fp		/* Pointer to the file object to be closed */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+
+#if !_FS_READONLY
+	res = f_sync(fp);					/* Flush cached data */
+	if (res == FR_OK)
+#endif
+	{
+		res = validate(&fp->obj, &fs);	/* Lock volume */
+		if (res == FR_OK) {
+#if _FS_LOCK != 0
+			res = dec_lock(fp->obj.lockid);	/* Decrement file open counter */
+			if (res == FR_OK)
+#endif
+			{
+				fp->obj.fs = 0;			/* Invalidate file object */
+			}
+#if _FS_REENTRANT
+			unlock_fs(fs, FR_OK);		/* Unlock volume */
+#endif
+		}
+	}
+	return res;
+}
+
+
+
+
+#if _FS_RPATH >= 1
+/*-----------------------------------------------------------------------*/
+/* Change Current Directory or Current Drive, Get Current Directory      */
+/*-----------------------------------------------------------------------*/
+
+#if _VOLUMES >= 2
+FRESULT f_chdrive (
+	const TCHAR* path		/* Drive number */
+)
+{
+	int vol;
+
+
+	/* Get logical drive number */
+	vol = get_ldnumber(&path);
+	if (vol < 0) return FR_INVALID_DRIVE;
+
+	CurrVol = (BYTE)vol;	/* Set it as current volume */
+
+	return FR_OK;
+}
+#endif
+
+
+FRESULT f_chdir (
+	const TCHAR* path	/* Pointer to the directory path */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+	DEF_NAMBUF
+
+	/* Get logical drive */
+	res = find_volume(&path, &fs, 0);
+	if (res == FR_OK) {
+		dj.obj.fs = fs;
+		INIT_NAMBUF(fs);
+		res = follow_path(&dj, path);		/* Follow the path */
+		if (res == FR_OK) {					/* Follow completed */
+			if (dj.fn[NSFLAG] & NS_NONAME) {
+				fs->cdir = dj.obj.sclust;	/* It is the start directory itself */
+#if _FS_EXFAT
+				if (fs->fs_type == FS_EXFAT) {
+					fs->cdc_scl = dj.obj.c_scl;
+					fs->cdc_size = dj.obj.c_size;
+					fs->cdc_ofs = dj.obj.c_ofs;
+				}
+#endif
+			} else {
+				if (dj.obj.attr & AM_DIR) {	/* It is a sub-directory */
+#if _FS_EXFAT
+					if (fs->fs_type == FS_EXFAT) {
+						fs->cdir = ld_dword(fs->dirbuf + XDIR_FstClus);		/* Sub-directory cluster */
+						fs->cdc_scl = dj.obj.sclust;						/* Save containing directory information */
+						fs->cdc_size = ((DWORD)dj.obj.objsize & 0xFFFFFF00) | dj.obj.stat;
+						fs->cdc_ofs = dj.blk_ofs;
+					} else
+#endif
+					{
+						fs->cdir = ld_clust(fs, dj.dir);					/* Sub-directory cluster */
+					}
+				} else {
+					res = FR_NO_PATH;		/* Reached but a file */
+				}
+			}
+		}
+		FREE_NAMBUF();
+		if (res == FR_NO_FILE) res = FR_NO_PATH;
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+#if _FS_RPATH >= 2
+FRESULT f_getcwd (
+	TCHAR* buff,	/* Pointer to the directory path */
+	UINT len		/* Size of path */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+	UINT i, n;
+	DWORD ccl;
+	TCHAR *tp;
+	FILINFO fno;
+	DEF_NAMBUF
+
+
+	*buff = 0;
+	/* Get logical drive */
+	res = find_volume((const TCHAR**)&buff, &fs, 0);	/* Get current volume */
+	if (res == FR_OK) {
+		dj.obj.fs = fs;
+		INIT_NAMBUF(fs);
+		i = len;			/* Bottom of buffer (directory stack base) */
+		if (!_FS_EXFAT || fs->fs_type != FS_EXFAT) {	/* (Cannot do getcwd on exFAT and returns root path) */
+			dj.obj.sclust = fs->cdir;				/* Start to follow upper directory from current directory */
+			while ((ccl = dj.obj.sclust) != 0) {	/* Repeat while current directory is a sub-directory */
+				res = dir_sdi(&dj, 1 * SZDIRE);	/* Get parent directory */
+				if (res != FR_OK) break;
+				res = move_window(fs, dj.sect);
+				if (res != FR_OK) break;
+				dj.obj.sclust = ld_clust(fs, dj.dir);	/* Goto parent directory */
+				res = dir_sdi(&dj, 0);
+				if (res != FR_OK) break;
+				do {							/* Find the entry links to the child directory */
+					res = dir_read(&dj, 0);
+					if (res != FR_OK) break;
+					if (ccl == ld_clust(fs, dj.dir)) break;	/* Found the entry */
+					res = dir_next(&dj, 0);
+				} while (res == FR_OK);
+				if (res == FR_NO_FILE) res = FR_INT_ERR;/* It cannot be 'not found'. */
+				if (res != FR_OK) break;
+				get_fileinfo(&dj, &fno);		/* Get the directory name and push it to the buffer */
+				for (n = 0; fno.fname[n]; n++) ;
+				if (i < n + 3) {
+					res = FR_NOT_ENOUGH_CORE; break;
+				}
+				while (n) buff[--i] = fno.fname[--n];
+				buff[--i] = '/';
+			}
+		}
+		tp = buff;
+		if (res == FR_OK) {
+#if _VOLUMES >= 2
+			*tp++ = '0' + CurrVol;			/* Put drive number */
+			*tp++ = ':';
+#endif
+			if (i == len) {					/* Root-directory */
+				*tp++ = '/';
+			} else {						/* Sub-directroy */
+				do		/* Add stacked path str */
+					*tp++ = buff[i++];
+				while (i < len);
+			}
+		}
+		*tp = 0;
+		FREE_NAMBUF();
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+#endif /* _FS_RPATH >= 2 */
+#endif /* _FS_RPATH >= 1 */
+
+
+
+#if _FS_MINIMIZE <= 2
+/*-----------------------------------------------------------------------*/
+/* Seek File R/W Pointer                                                 */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_lseek (
+	FIL* fp,		/* Pointer to the file object */
+	FSIZE_t ofs		/* File pointer from top of file */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD clst, bcs, nsect;
+	FSIZE_t ifptr;
+#if _USE_FASTSEEK
+	DWORD cl, pcl, ncl, tcl, dsc, tlen, ulen, *tbl;
+#endif
+
+	res = validate(&fp->obj, &fs);		/* Check validity of the file object */
+	if (res != FR_OK || (res = (FRESULT)fp->err) != FR_OK) LEAVE_FF(fs, res);	/* Check validity */
+#if _USE_FASTSEEK
+	if (fp->cltbl) {	/* Fast seek */
+		if (ofs == CREATE_LINKMAP) {	/* Create CLMT */
+			tbl = fp->cltbl;
+			tlen = *tbl++; ulen = 2;	/* Given table size and required table size */
+			cl = fp->obj.sclust;		/* Origin of the chain */
+			if (cl) {
+				do {
+					/* Get a fragment */
+					tcl = cl; ncl = 0; ulen += 2;	/* Top, length and used items */
+					do {
+						pcl = cl; ncl++;
+						cl = get_fat(&fp->obj, cl);
+						if (cl <= 1) ABORT(fs, FR_INT_ERR);
+						if (cl == 0xFFFFFFFF) ABORT(fs, FR_DISK_ERR);
+					} while (cl == pcl + 1);
+					if (ulen <= tlen) {		/* Store the length and top of the fragment */
+						*tbl++ = ncl; *tbl++ = tcl;
+					}
+				} while (cl < fs->n_fatent);	/* Repeat until end of chain */
+			}
+			*fp->cltbl = ulen;	/* Number of items used */
+			if (ulen <= tlen) {
+				*tbl = 0;		/* Terminate table */
+			} else {
+				res = FR_NOT_ENOUGH_CORE;	/* Given table size is smaller than required */
+			}
+		} else {						/* Fast seek */
+			if (ofs > fp->obj.objsize) ofs = fp->obj.objsize;	/* Clip offset at the file size */
+			fp->fptr = ofs;				/* Set file pointer */
+			if (ofs) {
+				fp->clust = clmt_clust(fp, ofs - 1);
+				dsc = clust2sect(fs, fp->clust);
+				if (!dsc) ABORT(fs, FR_INT_ERR);
+				dsc += (DWORD)((ofs - 1) / SS(fs)) & (fs->csize - 1);
+				if (fp->fptr % SS(fs) && dsc != fp->sect) {	/* Refill sector cache if needed */
+#if !_FS_TINY
+#if !_FS_READONLY
+					if (fp->flag & FA_DIRTY) {		/* Write-back dirty sector cache */
+						if (disk_write(fs->drv, fp->buf, fp->sect, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);
+						fp->flag &= (BYTE)~FA_DIRTY;
+					}
+#endif
+					if (disk_read(fs->drv, fp->buf, dsc, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);	/* Load current sector */
+#endif
+					fp->sect = dsc;
+				}
+			}
+		}
+	} else
+#endif
+
+	/* Normal Seek */
+	{
+#if _FS_EXFAT
+		if (fs->fs_type != FS_EXFAT && ofs >= 0x100000000) ofs = 0xFFFFFFFF;	/* Clip at 4GiB-1 if at FATxx */
+#endif
+		if (ofs > fp->obj.objsize && (_FS_READONLY || !(fp->flag & FA_WRITE))) {	/* In read-only mode, clip offset with the file size */
+			ofs = fp->obj.objsize;
+		}
+		ifptr = fp->fptr;
+		fp->fptr = nsect = 0;
+		if (ofs) {
+			bcs = (DWORD)fs->csize * SS(fs);	/* Cluster size (byte) */
+			if (ifptr > 0 &&
+				(ofs - 1) / bcs >= (ifptr - 1) / bcs) {	/* When seek to same or following cluster, */
+				fp->fptr = (ifptr - 1) & ~(FSIZE_t)(bcs - 1);	/* start from the current cluster */
+				ofs -= fp->fptr;
+				clst = fp->clust;
+			} else {									/* When seek to back cluster, */
+				clst = fp->obj.sclust;					/* start from the first cluster */
+#if !_FS_READONLY
+				if (clst == 0) {						/* If no cluster chain, create a new chain */
+					clst = create_chain(&fp->obj, 0);
+					if (clst == 1) ABORT(fs, FR_INT_ERR);
+					if (clst == 0xFFFFFFFF) ABORT(fs, FR_DISK_ERR);
+					fp->obj.sclust = clst;
+				}
+#endif
+				fp->clust = clst;
+			}
+			if (clst != 0) {
+				while (ofs > bcs) {						/* Cluster following loop */
+					ofs -= bcs; fp->fptr += bcs;
+#if !_FS_READONLY
+					if (fp->flag & FA_WRITE) {			/* Check if in write mode or not */
+						if (_FS_EXFAT && fp->fptr > fp->obj.objsize) {	/* No FAT chain object needs correct objsize to generate FAT value */
+							fp->obj.objsize = fp->fptr;
+							fp->flag |= FA_MODIFIED;
+						}
+						clst = create_chain(&fp->obj, clst);	/* Follow chain with forceed stretch */
+						if (clst == 0) {				/* Clip file size in case of disk full */
+							ofs = 0; break;
+						}
+					} else
+#endif
+					{
+						clst = get_fat(&fp->obj, clst);	/* Follow cluster chain if not in write mode */
+					}
+					if (clst == 0xFFFFFFFF) ABORT(fs, FR_DISK_ERR);
+					if (clst <= 1 || clst >= fs->n_fatent) ABORT(fs, FR_INT_ERR);
+					fp->clust = clst;
+				}
+				fp->fptr += ofs;
+				if (ofs % SS(fs)) {
+					nsect = clust2sect(fs, clst);	/* Current sector */
+					if (!nsect) ABORT(fs, FR_INT_ERR);
+					nsect += (DWORD)(ofs / SS(fs));
+				}
+			}
+		}
+		if (!_FS_READONLY && fp->fptr > fp->obj.objsize) {		/* Set file change flag if the file size is extended */
+			fp->obj.objsize = fp->fptr;
+			fp->flag |= FA_MODIFIED;
+		}
+		if (fp->fptr % SS(fs) && nsect != fp->sect) {	/* Fill sector cache if needed */
+#if !_FS_TINY
+#if !_FS_READONLY
+			if (fp->flag & FA_DIRTY) {			/* Write-back dirty sector cache */
+				if (disk_write(fs->drv, fp->buf, fp->sect, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);
+				fp->flag &= (BYTE)~FA_DIRTY;
+			}
+#endif
+			if (disk_read(fs->drv, fp->buf, nsect, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);	/* Fill sector cache */
+#endif
+			fp->sect = nsect;
+		}
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+#if _FS_MINIMIZE <= 1
+/*-----------------------------------------------------------------------*/
+/* Create a Directory Object                                             */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_opendir (
+	DIR* dp,			/* Pointer to directory object to create */
+	const TCHAR* path	/* Pointer to the directory path */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	_FDID *obj;
+	DEF_NAMBUF
+
+
+	if (!dp) return FR_INVALID_OBJECT;
+
+	/* Get logical drive */
+	obj = &dp->obj;
+	res = find_volume(&path, &fs, 0);
+	if (res == FR_OK) {
+		obj->fs = fs;
+		INIT_NAMBUF(fs);
+		res = follow_path(dp, path);			/* Follow the path to the directory */
+		if (res == FR_OK) {						/* Follow completed */
+			if (!(dp->fn[NSFLAG] & NS_NONAME)) {	/* It is not the origin directory itself */
+				if (obj->attr & AM_DIR) {		/* This object is a sub-directory */
+#if _FS_EXFAT
+					if (fs->fs_type == FS_EXFAT) {
+						obj->c_scl = obj->sclust;	/* Save containing directory inforamation */
+						obj->c_size = ((DWORD)obj->objsize & 0xFFFFFF00) | obj->stat;
+						obj->c_ofs = dp->blk_ofs;
+						obj->sclust = ld_dword(fs->dirbuf + XDIR_FstClus);	/* Get object location and status */
+						obj->objsize = ld_qword(fs->dirbuf + XDIR_FileSize);
+						obj->stat = fs->dirbuf[XDIR_GenFlags] & 2;
+					} else
+#endif
+					{
+						obj->sclust = ld_clust(fs, dp->dir);	/* Get object location */
+					}
+				} else {						/* This object is a file */
+					res = FR_NO_PATH;
+				}
+			}
+			if (res == FR_OK) {
+				obj->id = fs->id;
+				res = dir_sdi(dp, 0);			/* Rewind directory */
+#if _FS_LOCK != 0
+				if (res == FR_OK) {
+					if (obj->sclust) {
+						obj->lockid = inc_lock(dp, 0);	/* Lock the sub directory */
+						if (!obj->lockid) res = FR_TOO_MANY_OPEN_FILES;
+					} else {
+						obj->lockid = 0;	/* Root directory need not to be locked */
+					}
+				}
+#endif
+			}
+		}
+		FREE_NAMBUF();
+		if (res == FR_NO_FILE) res = FR_NO_PATH;
+	}
+	if (res != FR_OK) obj->fs = 0;		/* Invalidate the directory object if function faild */
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Close Directory                                                       */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_closedir (
+	DIR *dp		/* Pointer to the directory object to be closed */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+
+
+	res = validate(&dp->obj, &fs);			/* Check validity of the file object */
+	if (res == FR_OK) {
+#if _FS_LOCK != 0
+		if (dp->obj.lockid) {				/* Decrement sub-directory open counter */
+			res = dec_lock(dp->obj.lockid);
+		}
+		if (res == FR_OK)
+#endif
+		{
+			dp->obj.fs = 0;			/* Invalidate directory object */
+		}
+#if _FS_REENTRANT
+		unlock_fs(fs, FR_OK);		/* Unlock volume */
+#endif
+	}
+	return res;
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Read Directory Entries in Sequence                                    */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_readdir (
+	DIR* dp,			/* Pointer to the open directory object */
+	FILINFO* fno		/* Pointer to file information to return */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DEF_NAMBUF
+
+
+	res = validate(&dp->obj, &fs);	/* Check validity of the directory object */
+	if (res == FR_OK) {
+		if (!fno) {
+			res = dir_sdi(dp, 0);			/* Rewind the directory object */
+		} else {
+			INIT_NAMBUF(fs);
+			res = dir_read(dp, 0);			/* Read an item */
+			if (res == FR_NO_FILE) res = FR_OK;	/* Ignore end of directory */
+			if (res == FR_OK) {				/* A valid entry is found */
+				get_fileinfo(dp, fno);		/* Get the object information */
+				res = dir_next(dp, 0);		/* Increment index for next */
+				if (res == FR_NO_FILE) res = FR_OK;	/* Ignore end of directory now */
+			}
+			FREE_NAMBUF();
+		}
+	}
+	LEAVE_FF(fs, res);
+}
+
+
+
+#if _USE_FIND
+/*-----------------------------------------------------------------------*/
+/* Find Next File                                                        */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_findnext (
+	DIR* dp,		/* Pointer to the open directory object */
+	FILINFO* fno	/* Pointer to the file information structure */
+)
+{
+	FRESULT res;
+
+
+	for (;;) {
+		res = f_readdir(dp, fno);		/* Get a directory item */
+		if (res != FR_OK || !fno || !fno->fname[0]) break;	/* Terminate if any error or end of directory */
+		if (pattern_matching(dp->pat, fno->fname, 0, 0)) break;		/* Test for the file name */
+#if _USE_LFN != 0 && _USE_FIND == 2
+		if (pattern_matching(dp->pat, fno->altname, 0, 0)) break;	/* Test for alternative name if exist */
+#endif
+	}
+	return res;
+}
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Find First File                                                       */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_findfirst (
+	DIR* dp,				/* Pointer to the blank directory object */
+	FILINFO* fno,			/* Pointer to the file information structure */
+	const TCHAR* path,		/* Pointer to the directory to open */
+	const TCHAR* pattern	/* Pointer to the matching pattern */
+)
+{
+	FRESULT res;
+
+
+	dp->pat = pattern;		/* Save pointer to pattern string */
+	res = f_opendir(dp, path);		/* Open the target directory */
+	if (res == FR_OK) {
+		res = f_findnext(dp, fno);	/* Find the first item */
+	}
+	return res;
+}
+
+#endif	/* _USE_FIND */
+
+
+
+#if _FS_MINIMIZE == 0
+/*-----------------------------------------------------------------------*/
+/* Get File Status                                                       */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_stat (
+	const TCHAR* path,	/* Pointer to the file path */
+	FILINFO* fno		/* Pointer to file information to return */
+)
+{
+	FRESULT res;
+	DIR dj;
+	DEF_NAMBUF
+
+
+	/* Get logical drive */
+	res = find_volume(&path, &dj.obj.fs, 0);
+	if (res == FR_OK) {
+		INIT_NAMBUF(dj.obj.fs);
+		res = follow_path(&dj, path);	/* Follow the file path */
+		if (res == FR_OK) {				/* Follow completed */
+			if (dj.fn[NSFLAG] & NS_NONAME) {	/* It is origin directory */
+				res = FR_INVALID_NAME;
+			} else {							/* Found an object */
+				if (fno) get_fileinfo(&dj, fno);
+			}
+		}
+		FREE_NAMBUF();
+	}
+
+	LEAVE_FF(dj.obj.fs, res);
+}
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Get Number of Free Clusters                                           */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_getfree (
+	const TCHAR* path,	/* Path name of the logical drive number */
+	DWORD* nclst,		/* Pointer to a variable to return number of free clusters */
+	FATFS** fatfs		/* Pointer to return pointer to corresponding file system object */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD nfree, clst, sect, stat;
+	UINT i;
+	BYTE *p;
+	_FDID obj;
+
+
+	/* Get logical drive */
+	res = find_volume(&path, &fs, 0);
+	if (res == FR_OK) {
+		*fatfs = fs;				/* Return ptr to the fs object */
+		/* If free_clst is valid, return it without full cluster scan */
+		if (fs->free_clst <= fs->n_fatent - 2) {
+			*nclst = fs->free_clst;
+		} else {
+			/* Get number of free clusters */
+			nfree = 0;
+			if (fs->fs_type == FS_FAT12) {	/* FAT12: Sector unalighed FAT entries */
+				clst = 2; obj.fs = fs;
+				do {
+					stat = get_fat(&obj, clst);
+					if (stat == 0xFFFFFFFF) { res = FR_DISK_ERR; break; }
+					if (stat == 1) { res = FR_INT_ERR; break; }
+					if (stat == 0) nfree++;
+				} while (++clst < fs->n_fatent);
+			} else {
+#if _FS_EXFAT
+				if (fs->fs_type == FS_EXFAT) {	/* exFAT: Scan bitmap table */
+					BYTE bm;
+					UINT b;
+
+					clst = fs->n_fatent - 2;
+					sect = fs->database;
+					i = 0;
+					do {
+						if (i == 0 && (res = move_window(fs, sect++)) != FR_OK) break;
+						for (b = 8, bm = fs->win[i]; b && clst; b--, clst--) {
+							if (!(bm & 1)) nfree++;
+							bm >>= 1;
+						}
+						i = (i + 1) % SS(fs);
+					} while (clst);
+				} else
+#endif
+				{	/* FAT16/32: Sector alighed FAT entries */
+					clst = fs->n_fatent; sect = fs->fatbase;
+					i = 0; p = 0;
+					do {
+						if (i == 0) {
+							res = move_window(fs, sect++);
+							if (res != FR_OK) break;
+							p = fs->win;
+							i = SS(fs);
+						}
+						if (fs->fs_type == FS_FAT16) {
+							if (ld_word(p) == 0) nfree++;
+							p += 2; i -= 2;
+						} else {
+							if ((ld_dword(p) & 0x0FFFFFFF) == 0) nfree++;
+							p += 4; i -= 4;
+						}
+					} while (--clst);
+				}
+			}
+			*nclst = nfree;			/* Return the free clusters */
+			fs->free_clst = nfree;	/* Now free_clst is valid */
+			fs->fsi_flag |= 1;		/* FSInfo is to be updated */
+		}
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Truncate File                                                         */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_truncate (
+	FIL* fp		/* Pointer to the file object */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD ncl;
+
+
+	res = validate(&fp->obj, &fs);	/* Check validity of the file object */
+	if (res != FR_OK || (res = (FRESULT)fp->err) != FR_OK) LEAVE_FF(fs, res);
+	if (!(fp->flag & FA_WRITE)) LEAVE_FF(fs, FR_DENIED);	/* Check access mode */
+
+	if (fp->obj.objsize > fp->fptr) {
+		if (fp->fptr == 0) {	/* When set file size to zero, remove entire cluster chain */
+			res = remove_chain(&fp->obj, fp->obj.sclust, 0);
+			fp->obj.sclust = 0;
+		} else {				/* When truncate a part of the file, remove remaining clusters */
+			ncl = get_fat(&fp->obj, fp->clust);
+			res = FR_OK;
+			if (ncl == 0xFFFFFFFF) res = FR_DISK_ERR;
+			if (ncl == 1) res = FR_INT_ERR;
+			if (res == FR_OK && ncl < fs->n_fatent) {
+				res = remove_chain(&fp->obj, ncl, fp->clust);
+			}
+		}
+		fp->obj.objsize = fp->fptr;	/* Set file size to current R/W point */
+		fp->flag |= FA_MODIFIED;
+#if !_FS_TINY
+		if (res == FR_OK && (fp->flag & FA_DIRTY)) {
+			if (disk_write(fs->drv, fp->buf, fp->sect, 1) != RES_OK) {
+				res = FR_DISK_ERR;
+			} else {
+				fp->flag &= (BYTE)~FA_DIRTY;
+			}
+		}
+#endif
+		if (res != FR_OK) ABORT(fs, res);
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Delete a File/Directory                                               */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_unlink (
+	const TCHAR* path		/* Pointer to the file or directory path */
+)
+{
+	FRESULT res;
+	DIR dj, sdj;
+	DWORD dclst = 0;
+	FATFS *fs;
+#if _FS_EXFAT
+	_FDID obj;
+#endif
+	DEF_NAMBUF
+
+
+	/* Get logical drive */
+	res = find_volume(&path, &fs, FA_WRITE);
+	dj.obj.fs = fs;
+	if (res == FR_OK) {
+		INIT_NAMBUF(fs);
+		res = follow_path(&dj, path);		/* Follow the file path */
+		if (_FS_RPATH && res == FR_OK && (dj.fn[NSFLAG] & NS_DOT)) {
+			res = FR_INVALID_NAME;			/* Cannot remove dot entry */
+		}
+#if _FS_LOCK != 0
+		if (res == FR_OK) res = chk_lock(&dj, 2);	/* Check if it is an open object */
+#endif
+		if (res == FR_OK) {					/* The object is accessible */
+			if (dj.fn[NSFLAG] & NS_NONAME) {
+				res = FR_INVALID_NAME;		/* Cannot remove the origin directory */
+			} else {
+				if (dj.obj.attr & AM_RDO) {
+					res = FR_DENIED;		/* Cannot remove R/O object */
+				}
+			}
+			if (res == FR_OK) {
+#if _FS_EXFAT
+				obj.fs = fs;
+				if (fs->fs_type == FS_EXFAT) {
+					obj.sclust = dclst = ld_dword(fs->dirbuf + XDIR_FstClus);
+					obj.objsize = ld_qword(fs->dirbuf + XDIR_FileSize);
+					obj.stat = fs->dirbuf[XDIR_GenFlags] & 2;
+				} else
+#endif
+				{
+					dclst = ld_clust(fs, dj.dir);
+				}
+				if (dj.obj.attr & AM_DIR) {			/* Is it a sub-directory ? */
+#if _FS_RPATH != 0
+					if (dclst == fs->cdir) {		 		/* Is it the current directory? */
+						res = FR_DENIED;
+					} else
+#endif
+					{
+						sdj.obj.fs = fs;						/* Open the sub-directory */
+						sdj.obj.sclust = dclst;
+#if _FS_EXFAT
+						if (fs->fs_type == FS_EXFAT) {
+							sdj.obj.objsize = obj.objsize;
+							sdj.obj.stat = obj.stat;
+						}
+#endif
+						res = dir_sdi(&sdj, 0);
+						if (res == FR_OK) {
+							res = dir_read(&sdj, 0);			/* Read an item */
+							if (res == FR_OK) res = FR_DENIED;	/* Not empty? */
+							if (res == FR_NO_FILE) res = FR_OK;	/* Empty? */
+						}
+					}
+				}
+			}
+			if (res == FR_OK) {
+				res = dir_remove(&dj);			/* Remove the directory entry */
+				if (res == FR_OK && dclst) {	/* Remove the cluster chain if exist */
+#if _FS_EXFAT
+					res = remove_chain(&obj, dclst, 0);
+#else
+					res = remove_chain(&dj.obj, dclst, 0);
+#endif
+				}
+				if (res == FR_OK) res = sync_fs(fs);
+			}
+		}
+		FREE_NAMBUF();
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Create a Directory                                                    */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_mkdir (
+	const TCHAR* path		/* Pointer to the directory path */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+	BYTE *dir;
+	UINT n;
+	DWORD dsc, dcl, pcl, tm;
+	DEF_NAMBUF
+
+
+	/* Get logical drive */
+	res = find_volume(&path, &fs, FA_WRITE);
+	dj.obj.fs = fs;
+	if (res == FR_OK) {
+		INIT_NAMBUF(fs);
+		res = follow_path(&dj, path);			/* Follow the file path */
+		if (res == FR_OK) res = FR_EXIST;		/* Any object with same name is already existing */
+		if (_FS_RPATH && res == FR_NO_FILE && (dj.fn[NSFLAG] & NS_DOT)) {
+			res = FR_INVALID_NAME;
+		}
+		if (res == FR_NO_FILE) {				/* Can create a new directory */
+			dcl = create_chain(&dj.obj, 0);		/* Allocate a cluster for the new directory table */
+			dj.obj.objsize = (DWORD)fs->csize * SS(fs);
+			res = FR_OK;
+			if (dcl == 0) res = FR_DENIED;		/* No space to allocate a new cluster */
+			if (dcl == 1) res = FR_INT_ERR;
+			if (dcl == 0xFFFFFFFF) res = FR_DISK_ERR;
+			if (res == FR_OK) res = sync_window(fs);	/* Flush FAT */
+			tm = GET_FATTIME();
+			if (res == FR_OK) {					/* Initialize the new directory table */
+				dsc = clust2sect(fs, dcl);
+				dir = fs->win;
+				mem_set(dir, 0, SS(fs));
+				if (!_FS_EXFAT || fs->fs_type != FS_EXFAT) {
+					mem_set(dir + DIR_Name, ' ', 11);	/* Create "." entry */
+					dir[DIR_Name] = '.';
+					dir[DIR_Attr] = AM_DIR;
+					st_dword(dir + DIR_ModTime, tm);
+					st_clust(fs, dir, dcl);
+					mem_cpy(dir + SZDIRE, dir, SZDIRE); 	/* Create ".." entry */
+					dir[SZDIRE + 1] = '.'; pcl = dj.obj.sclust;
+					if (fs->fs_type == FS_FAT32 && pcl == fs->dirbase) pcl = 0;
+					st_clust(fs, dir + SZDIRE, pcl);
+				}
+				for (n = fs->csize; n; n--) {	/* Write dot entries and clear following sectors */
+					fs->winsect = dsc++;
+					fs->wflag = 1;
+					res = sync_window(fs);
+					if (res != FR_OK) break;
+					mem_set(dir, 0, SS(fs));
+				}
+			}
+			if (res == FR_OK) res = dir_register(&dj);	/* Register the object to the directoy */
+			if (res == FR_OK) {
+#if _FS_EXFAT
+				if (fs->fs_type == FS_EXFAT) {	/* Initialize directory entry block */
+					st_dword(fs->dirbuf + XDIR_ModTime, tm);	/* Created time */
+					st_dword(fs->dirbuf + XDIR_FstClus, dcl);	/* Table start cluster */
+					st_dword(fs->dirbuf + XDIR_FileSize, (DWORD)dj.obj.objsize);	/* File size needs to be valid */
+					st_dword(fs->dirbuf + XDIR_ValidFileSize, (DWORD)dj.obj.objsize);
+					fs->dirbuf[XDIR_GenFlags] = 3;				/* Initialize the object flag (contiguous) */
+					fs->dirbuf[XDIR_Attr] = AM_DIR;				/* Attribute */
+					res = store_xdir(&dj);
+				} else
+#endif
+				{
+					dir = dj.dir;
+					st_dword(dir + DIR_ModTime, tm);	/* Created time */
+					st_clust(fs, dir, dcl);				/* Table start cluster */
+					dir[DIR_Attr] = AM_DIR;				/* Attribute */
+					fs->wflag = 1;
+				}
+				if (res == FR_OK) res = sync_fs(fs);
+			} else {
+				remove_chain(&dj.obj, dcl, 0);		/* Could not register, remove cluster chain */
+			}
+		}
+		FREE_NAMBUF();
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Rename a File/Directory                                               */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_rename (
+	const TCHAR* path_old,	/* Pointer to the object name to be renamed */
+	const TCHAR* path_new	/* Pointer to the new name */
+)
+{
+	FRESULT res;
+	DIR djo, djn;
+	FATFS *fs;
+	BYTE buf[_FS_EXFAT ? SZDIRE * 2 : 24], *dir;
+	DWORD dw;
+	DEF_NAMBUF
+
+
+	get_ldnumber(&path_new);						/* Ignore drive number of new name */
+	res = find_volume(&path_old, &fs, FA_WRITE);	/* Get logical drive of the old object */
+	if (res == FR_OK) {
+		djo.obj.fs = fs;
+		INIT_NAMBUF(fs);
+		res = follow_path(&djo, path_old);		/* Check old object */
+		if (res == FR_OK && (djo.fn[NSFLAG] & (NS_DOT | NS_NONAME))) res = FR_INVALID_NAME;	/* Check validity of name */
+#if _FS_LOCK != 0
+		if (res == FR_OK) res = chk_lock(&djo, 2);
+#endif
+		if (res == FR_OK) {						/* Object to be renamed is found */
+#if _FS_EXFAT
+			if (fs->fs_type == FS_EXFAT) {	/* At exFAT */
+				BYTE nf, nn;
+				WORD nh;
+
+				mem_cpy(buf, fs->dirbuf, SZDIRE * 2);	/* Save 85+C0 entry of old object */
+				mem_cpy(&djn, &djo, sizeof djo);
+				res = follow_path(&djn, path_new);		/* Make sure if new object name is not in use */
+				if (res == FR_OK) {						/* Is new name already in use by any other object? */
+					res = (djn.obj.sclust == djo.obj.sclust && djn.dptr == djo.dptr) ? FR_NO_FILE : FR_EXIST;
+				}
+				if (res == FR_NO_FILE) { 				/* It is a valid path and no name collision */
+					res = dir_register(&djn);			/* Register the new entry */
+					if (res == FR_OK) {
+						nf = fs->dirbuf[XDIR_NumSec]; nn = fs->dirbuf[XDIR_NumName];
+						nh = ld_word(fs->dirbuf + XDIR_NameHash);
+						mem_cpy(fs->dirbuf, buf, SZDIRE * 2);
+						fs->dirbuf[XDIR_NumSec] = nf; fs->dirbuf[XDIR_NumName] = nn;
+						st_word(fs->dirbuf + XDIR_NameHash, nh);
+/* Start of critical section where any interruption can cause a cross-link */
+						res = store_xdir(&djn);
+					}
+				}
+			} else
+#endif
+			{	/* At FAT12/FAT16/FAT32 */
+				mem_cpy(buf, djo.dir + DIR_Attr, 21);	/* Save information about the object except name */
+				mem_cpy(&djn, &djo, sizeof (DIR));		/* Duplicate the directory object */
+				res = follow_path(&djn, path_new);		/* Make sure if new object name is not in use */
+				if (res == FR_OK) {						/* Is new name already in use by any other object? */
+					res = (djn.obj.sclust == djo.obj.sclust && djn.dptr == djo.dptr) ? FR_NO_FILE : FR_EXIST;
+				}
+				if (res == FR_NO_FILE) { 				/* It is a valid path and no name collision */
+					res = dir_register(&djn);			/* Register the new entry */
+					if (res == FR_OK) {
+						dir = djn.dir;					/* Copy information about object except name */
+						mem_cpy(dir + 13, buf + 2, 19);
+						dir[DIR_Attr] = buf[0] | AM_ARC;
+						fs->wflag = 1;
+						if ((dir[DIR_Attr] & AM_DIR) && djo.obj.sclust != djn.obj.sclust) {	/* Update .. entry in the sub-directory if needed */
+							dw = clust2sect(fs, ld_clust(fs, dir));
+							if (!dw) {
+								res = FR_INT_ERR;
+							} else {
+/* Start of critical section where any interruption can cause a cross-link */
+								res = move_window(fs, dw);
+								dir = fs->win + SZDIRE * 1;	/* Ptr to .. entry */
+								if (res == FR_OK && dir[1] == '.') {
+									st_clust(fs, dir, djn.obj.sclust);
+									fs->wflag = 1;
+								}
+							}
+						}
+					}
+				}
+			}
+			if (res == FR_OK) {
+				res = dir_remove(&djo);		/* Remove old entry */
+				if (res == FR_OK) {
+					res = sync_fs(fs);
+				}
+			}
+/* End of critical section */
+		}
+		FREE_NAMBUF();
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+#endif /* !_FS_READONLY */
+#endif /* _FS_MINIMIZE == 0 */
+#endif /* _FS_MINIMIZE <= 1 */
+#endif /* _FS_MINIMIZE <= 2 */
+
+
+
+#if _USE_CHMOD && !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Change Attribute                                                      */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_chmod (
+	const TCHAR* path,	/* Pointer to the file path */
+	BYTE attr,			/* Attribute bits */
+	BYTE mask			/* Attribute mask to change */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+	DEF_NAMBUF
+
+
+	res = find_volume(&path, &fs, FA_WRITE);	/* Get logical drive */
+	dj.obj.fs = fs;
+	if (res == FR_OK) {
+		INIT_NAMBUF(fs);
+		res = follow_path(&dj, path);	/* Follow the file path */
+		if (res == FR_OK && (dj.fn[NSFLAG] & (NS_DOT | NS_NONAME))) res = FR_INVALID_NAME;	/* Check object validity */
+		if (res == FR_OK) {
+			mask &= AM_RDO|AM_HID|AM_SYS|AM_ARC;	/* Valid attribute mask */
+#if _FS_EXFAT
+			if (fs->fs_type == FS_EXFAT) {
+				fs->dirbuf[XDIR_Attr] = (attr & mask) | (fs->dirbuf[XDIR_Attr] & (BYTE)~mask);	/* Apply attribute change */
+				res = store_xdir(&dj);
+			} else
+#endif
+			{
+				dj.dir[DIR_Attr] = (attr & mask) | (dj.dir[DIR_Attr] & (BYTE)~mask);	/* Apply attribute change */
+				fs->wflag = 1;
+			}
+			if (res == FR_OK) res = sync_fs(fs);
+		}
+		FREE_NAMBUF();
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Change Timestamp                                                      */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_utime (
+	const TCHAR* path,	/* Pointer to the file/directory name */
+	const FILINFO* fno	/* Pointer to the time stamp to be set */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+	DEF_NAMBUF
+
+
+	res = find_volume(&path, &fs, FA_WRITE);	/* Get logical drive */
+	dj.obj.fs = fs;
+	if (res == FR_OK) {
+		INIT_NAMBUF(fs);
+		res = follow_path(&dj, path);	/* Follow the file path */
+		if (res == FR_OK && (dj.fn[NSFLAG] & (NS_DOT | NS_NONAME))) res = FR_INVALID_NAME;	/* Check object validity */
+		if (res == FR_OK) {
+#if _FS_EXFAT
+			if (fs->fs_type == FS_EXFAT) {
+				st_dword(fs->dirbuf + XDIR_ModTime, (DWORD)fno->fdate << 16 | fno->ftime);
+				res = store_xdir(&dj);
+			} else
+#endif
+			{
+				st_dword(dj.dir + DIR_ModTime, (DWORD)fno->fdate << 16 | fno->ftime);
+				fs->wflag = 1;
+			}
+			if (res == FR_OK) res = sync_fs(fs);
+		}
+		FREE_NAMBUF();
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+#endif	/* _USE_CHMOD && !_FS_READONLY */
+
+
+
+#if _USE_LABEL
+/*-----------------------------------------------------------------------*/
+/* Get Volume Label                                                      */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_getlabel (
+	const TCHAR* path,	/* Path name of the logical drive number */
+	TCHAR* label,		/* Pointer to a buffer to return the volume label */
+	DWORD* vsn			/* Pointer to a variable to return the volume serial number */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+	UINT si, di;
+#if _LFN_UNICODE || _FS_EXFAT
+	WCHAR w;
+#endif
+
+	/* Get logical drive */
+	res = find_volume(&path, &fs, 0);
+
+	/* Get volume label */
+	if (res == FR_OK && label) {
+		dj.obj.fs = fs; dj.obj.sclust = 0;	/* Open root directory */
+		res = dir_sdi(&dj, 0);
+		if (res == FR_OK) {
+		 	res = dir_read(&dj, 1);			/* Find a volume label entry */
+		 	if (res == FR_OK) {
+#if _FS_EXFAT
+				if (fs->fs_type == FS_EXFAT) {
+					for (si = di = 0; si < dj.dir[XDIR_NumLabel]; si++) {	/* Extract volume label from 83 entry */
+						w = ld_word(dj.dir + XDIR_Label + si * 2);
+#if _LFN_UNICODE
+						label[di++] = w;
+#else
+						w = ff_convert(w, 0);	/* Unicode -> OEM */
+						if (w == 0) w = '?';	/* Replace wrong character */
+						if (_DF1S && w >= 0x100) label[di++] = (char)(w >> 8);
+						label[di++] = (char)w;
+#endif
+					}
+					label[di] = 0;
+				} else
+#endif
+				{
+					si = di = 0;		/* Extract volume label from AM_VOL entry with code comversion */
+					do {
+#if _LFN_UNICODE
+						w = (si < 11) ? dj.dir[si++] : ' ';
+						if (IsDBCS1(w) && si < 11 && IsDBCS2(dj.dir[si])) {
+							w = w << 8 | dj.dir[si++];
+						}
+						label[di++] = ff_convert(w, 1);	/* OEM -> Unicode */
+#else
+						label[di++] = dj.dir[si++];
+#endif
+					} while (di < 11);
+					do {				/* Truncate trailing spaces */
+						label[di] = 0;
+						if (di == 0) break;
+					} while (label[--di] == ' ');
+				}
+			}
+		}
+		if (res == FR_NO_FILE) {	/* No label entry and return nul string */
+			label[0] = 0;
+			res = FR_OK;
+		}
+	}
+
+	/* Get volume serial number */
+	if (res == FR_OK && vsn) {
+		res = move_window(fs, fs->volbase);
+		if (res == FR_OK) {
+			switch (fs->fs_type) {
+			case FS_EXFAT: di = BPB_VolIDEx; break;
+			case FS_FAT32: di = BS_VolID32; break;
+			default:       di = BS_VolID;
+			}
+			*vsn = ld_dword(fs->win + di);
+		}
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+
+
+#if !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Set Volume Label                                                      */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_setlabel (
+	const TCHAR* label	/* Pointer to the volume label to set */
+)
+{
+	FRESULT res;
+	DIR dj;
+	FATFS *fs;
+	BYTE dirvn[22];
+	UINT i, j, slen;
+	WCHAR w;
+	static const char badchr[] = "\"*+,.:;<=>\?[]|\x7F";
+
+
+	/* Get logical drive */
+	res = find_volume(&label, &fs, FA_WRITE);
+	if (res != FR_OK) LEAVE_FF(fs, res);
+	dj.obj.fs = fs;
+
+	/* Get length of given volume label */
+	for (slen = 0; (UINT)label[slen] >= ' '; slen++) ;	/* Get name length */
+
+#if _FS_EXFAT
+	if (fs->fs_type == FS_EXFAT) {	/* On the exFAT volume */
+		for (i = j = 0; i < slen; ) {	/* Create volume label in directory form */
+			w = label[i++];
+#if !_LFN_UNICODE
+			if (IsDBCS1(w)) {
+				w = (i < slen && IsDBCS2(label[i])) ? w << 8 | (BYTE)label[i++] : 0;
+			}
+			w = ff_convert(w, 1);
+#endif
+			if (w == 0 || chk_chr(badchr, w) || j == 22) {	/* Check validity check validity of the volume label */
+				LEAVE_FF(fs, FR_INVALID_NAME);
+			}
+			st_word(dirvn + j, w); j += 2;
+		}
+		slen = j;
+	} else
+#endif
+	{	/* On the FAT12/16/32 volume */
+		for ( ; slen && label[slen - 1] == ' '; slen--) ;	/* Remove trailing spaces */
+		if (slen) {		/* Is there a volume label to be set? */
+			dirvn[0] = 0; i = j = 0;	/* Create volume label in directory form */
+			do {
+#if _LFN_UNICODE
+				w = ff_convert(ff_wtoupper(label[i++]), 0);
+#else
+				w = (BYTE)label[i++];
+				if (IsDBCS1(w)) {
+					w = (j < 10 && i < slen && IsDBCS2(label[i])) ? w << 8 | (BYTE)label[i++] : 0;
+				}
+#if _USE_LFN != 0
+				w = ff_convert(ff_wtoupper(ff_convert(w, 1)), 0);
+#else
+				if (IsLower(w)) w -= 0x20;			/* To upper ASCII characters */
+#ifdef _EXCVT
+				if (w >= 0x80) w = ExCvt[w - 0x80];	/* To upper extended characters (SBCS cfg) */
+#else
+				if (!_DF1S && w >= 0x80) w = 0;		/* Reject extended characters (ASCII cfg) */
+#endif
+#endif
+#endif
+				if (w == 0 || chk_chr(badchr, w) || j >= (UINT)((w >= 0x100) ? 10 : 11)) {	/* Reject invalid characters for volume label */
+					LEAVE_FF(fs, FR_INVALID_NAME);
+				}
+				if (w >= 0x100) dirvn[j++] = (BYTE)(w >> 8);
+				dirvn[j++] = (BYTE)w;
+			} while (i < slen);
+			while (j < 11) dirvn[j++] = ' ';	/* Fill remaining name field */
+			if (dirvn[0] == DDEM) LEAVE_FF(fs, FR_INVALID_NAME);	/* Reject illegal name (heading DDEM) */
+		}
+	}
+
+	/* Set volume label */
+	dj.obj.sclust = 0;		/* Open root directory */
+	res = dir_sdi(&dj, 0);
+	if (res == FR_OK) {
+		res = dir_read(&dj, 1);	/* Get volume label entry */
+		if (res == FR_OK) {
+			if (_FS_EXFAT && fs->fs_type == FS_EXFAT) {
+				dj.dir[XDIR_NumLabel] = (BYTE)(slen / 2);	/* Change the volume label */
+				mem_cpy(dj.dir + XDIR_Label, dirvn, slen);
+			} else {
+				if (slen) {
+					mem_cpy(dj.dir, dirvn, 11);	/* Change the volume label */
+				} else {
+					dj.dir[DIR_Name] = DDEM;	/* Remove the volume label */
+				}
+			}
+			fs->wflag = 1;
+			res = sync_fs(fs);
+		} else {			/* No volume label entry is found or error */
+			if (res == FR_NO_FILE) {
+				res = FR_OK;
+				if (slen) {	/* Create a volume label entry */
+					res = dir_alloc(&dj, 1);	/* Allocate an entry */
+					if (res == FR_OK) {
+						mem_set(dj.dir, 0, SZDIRE);	/* Clear the entry */
+						if (_FS_EXFAT && fs->fs_type == FS_EXFAT) {
+							dj.dir[XDIR_Type] = 0x83;		/* Create 83 entry */
+							dj.dir[XDIR_NumLabel] = (BYTE)(slen / 2);
+							mem_cpy(dj.dir + XDIR_Label, dirvn, slen);
+						} else {
+							dj.dir[DIR_Attr] = AM_VOL;		/* Create volume label entry */
+							mem_cpy(dj.dir, dirvn, 11);
+						}
+						fs->wflag = 1;
+						res = sync_fs(fs);
+					}
+				}
+			}
+		}
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+#endif /* !_FS_READONLY */
+#endif /* _USE_LABEL */
+
+
+
+#if _USE_EXPAND && !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Allocate a Contiguous Blocks to the File                              */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_expand (
+	FIL* fp,		/* Pointer to the file object */
+	FSIZE_t fsz,	/* File size to be expanded to */
+	BYTE opt		/* Operation mode 0:Find and prepare or 1:Find and allocate */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD n, clst, stcl, scl, ncl, tcl, lclst;
+
+
+	res = validate(&fp->obj, &fs);		/* Check validity of the file object */
+	if (res != FR_OK || (res = (FRESULT)fp->err) != FR_OK) LEAVE_FF(fs, res);
+	if (fsz == 0 || fp->obj.objsize != 0 || !(fp->flag & FA_WRITE)) LEAVE_FF(fs, FR_DENIED);
+#if _FS_EXFAT
+	if (fs->fs_type != FS_EXFAT && fsz >= 0x100000000) LEAVE_FF(fs, FR_DENIED);	/* Check if in size limit */
+#endif
+	n = (DWORD)fs->csize * SS(fs);	/* Cluster size */
+	tcl = (DWORD)(fsz / n) + ((fsz & (n - 1)) ? 1 : 0);	/* Number of clusters required */
+	stcl = fs->last_clst; lclst = 0;
+	if (stcl < 2 || stcl >= fs->n_fatent) stcl = 2;
+
+#if _FS_EXFAT
+	if (fs->fs_type == FS_EXFAT) {
+		scl = find_bitmap(fs, stcl, tcl);			/* Find a contiguous cluster block */
+		if (scl == 0) res = FR_DENIED;				/* No contiguous cluster block was found */
+		if (scl == 0xFFFFFFFF) res = FR_DISK_ERR;
+		if (res == FR_OK) {
+			if (opt) {
+				res = change_bitmap(fs, scl, tcl, 1);	/* Mark the cluster block 'in use' */
+				lclst = scl + tcl - 1;
+			} else {
+				lclst = scl - 1;
+			}
+		}
+	} else
+#endif
+	{
+		scl = clst = stcl; ncl = 0;
+		for (;;) {	/* Find a contiguous cluster block */
+			n = get_fat(&fp->obj, clst);
+			if (++clst >= fs->n_fatent) clst = 2;
+			if (n == 1) { res = FR_INT_ERR; break; }
+			if (n == 0xFFFFFFFF) { res = FR_DISK_ERR; break; }
+			if (n == 0) {	/* Is it a free cluster? */
+				if (++ncl == tcl) break;	/* Break if a contiguous cluster block is found */
+			} else {
+				scl = clst; ncl = 0;		/* Not a free cluster */
+			}
+			if (clst == stcl) { res = FR_DENIED; break; }	/* No contiguous cluster? */
+		}
+		if (res == FR_OK) {
+			if (opt) {
+				for (clst = scl, n = tcl; n; clst++, n--) {	/* Create a cluster chain on the FAT */
+					res = put_fat(fs, clst, (n == 1) ? 0xFFFFFFFF : clst + 1);
+					if (res != FR_OK) break;
+					lclst = clst;
+				}
+			} else {
+				lclst = scl - 1;
+			}
+		}
+	}
+
+	if (res == FR_OK) {
+		fs->last_clst = lclst;		/* Set suggested start cluster to start next */
+		if (opt) {
+			fp->obj.sclust = scl;		/* Update object allocation information */
+			fp->obj.objsize = fsz;
+			if (_FS_EXFAT) fp->obj.stat = 2;	/* Set status 'contiguous chain' */
+			fp->flag |= FA_MODIFIED;
+			if (fs->free_clst  < fs->n_fatent - 2) {	/* Update FSINFO */
+				fs->free_clst -= tcl;
+				fs->fsi_flag |= 1;
+			}
+		}
+	}
+
+	LEAVE_FF(fs, res);
+}
+
+#endif /* _USE_EXPAND && !_FS_READONLY */
+
+
+
+#if _USE_FORWARD
+/*-----------------------------------------------------------------------*/
+/* Forward data to the stream directly                                   */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_forward (
+	FIL* fp, 						/* Pointer to the file object */
+	UINT (*func)(const BYTE*,UINT),	/* Pointer to the streaming function */
+	UINT btf,						/* Number of bytes to forward */
+	UINT* bf						/* Pointer to number of bytes forwarded */
+)
+{
+	FRESULT res;
+	FATFS *fs;
+	DWORD clst, sect;
+	FSIZE_t remain;
+	UINT rcnt, csect;
+	BYTE *dbuf;
+
+
+	*bf = 0;	/* Clear transfer byte counter */
+	res = validate(&fp->obj, &fs);		/* Check validity of the file object */
+	if (res != FR_OK || (res = (FRESULT)fp->err) != FR_OK) LEAVE_FF(fs, res);
+	if (!(fp->flag & FA_READ)) LEAVE_FF(fs, FR_DENIED);	/* Check access mode */
+
+	remain = fp->obj.objsize - fp->fptr;
+	if (btf > remain) btf = (UINT)remain;			/* Truncate btf by remaining bytes */
+
+	for ( ;  btf && (*func)(0, 0);					/* Repeat until all data transferred or stream goes busy */
+		fp->fptr += rcnt, *bf += rcnt, btf -= rcnt) {
+		csect = (UINT)(fp->fptr / SS(fs) & (fs->csize - 1));	/* Sector offset in the cluster */
+		if (fp->fptr % SS(fs) == 0) {				/* On the sector boundary? */
+			if (csect == 0) {						/* On the cluster boundary? */
+				clst = (fp->fptr == 0) ?			/* On the top of the file? */
+					fp->obj.sclust : get_fat(&fp->obj, fp->clust);
+				if (clst <= 1) ABORT(fs, FR_INT_ERR);
+				if (clst == 0xFFFFFFFF) ABORT(fs, FR_DISK_ERR);
+				fp->clust = clst;					/* Update current cluster */
+			}
+		}
+		sect = clust2sect(fs, fp->clust);			/* Get current data sector */
+		if (!sect) ABORT(fs, FR_INT_ERR);
+		sect += csect;
+#if _FS_TINY
+		if (move_window(fs, sect) != FR_OK) ABORT(fs, FR_DISK_ERR);	/* Move sector window to the file data */
+		dbuf = fs->win;
+#else
+		if (fp->sect != sect) {		/* Fill sector cache with file data */
+#if !_FS_READONLY
+			if (fp->flag & FA_DIRTY) {		/* Write-back dirty sector cache */
+				if (disk_write(fs->drv, fp->buf, fp->sect, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);
+				fp->flag &= (BYTE)~FA_DIRTY;
+			}
+#endif
+			if (disk_read(fs->drv, fp->buf, sect, 1) != RES_OK) ABORT(fs, FR_DISK_ERR);
+		}
+		dbuf = fp->buf;
+#endif
+		fp->sect = sect;
+		rcnt = SS(fs) - (UINT)fp->fptr % SS(fs);	/* Number of bytes left in the sector */
+		if (rcnt > btf) rcnt = btf;					/* Clip it by btr if needed */
+		rcnt = (*func)(dbuf + ((UINT)fp->fptr % SS(fs)), rcnt);	/* Forward the file data */
+		if (!rcnt) ABORT(fs, FR_INT_ERR);
+	}
+
+	LEAVE_FF(fs, FR_OK);
+}
+#endif /* _USE_FORWARD */
+
+
+
+#if _USE_MKFS && !_FS_READONLY
+/*-----------------------------------------------------------------------*/
+/* Create FAT file system on the logical drive                           */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_mkfs (
+	const TCHAR* path,	/* Logical drive number */
+	BYTE opt,			/* Format option */
+	DWORD au,			/* Size of allocation unit [byte] */
+	void* work,			/* Pointer to working buffer */
+	UINT len			/* Size of working buffer */
+)
+{
+	const UINT n_fats = 1;		/* Number of FATs for FAT12/16/32 volume (1 or 2) */
+	const UINT n_rootdir = 512;	/* Number of root directory entries for FAT12/16 volume */
+	static const WORD cst[] = {1, 4, 16, 64, 256, 512, 0};	/* Cluster size boundary for FAT12/16 volume (4Ks unit) */
+	static const WORD cst32[] = {1, 2, 4, 8, 16, 32, 0};	/* Cluster size boundary for FAT32 volume (128Ks unit) */
+	BYTE fmt, sys, *buf, *pte, pdrv, part;
+	WORD ss;
+	DWORD szb_buf, sz_buf, sz_blk, n_clst, pau, sect, nsect, n;
+	DWORD b_vol, b_fat, b_data;				/* Base LBA for volume, fat, data */
+	DWORD sz_vol, sz_rsv, sz_fat, sz_dir;	/* Size for volume, fat, dir, data */
+	UINT i;
+	int vol;
+	DSTATUS stat;
+#if _USE_TRIM || _FS_EXFAT
+	DWORD tbl[3];
+#endif
+
+
+	/* Check mounted drive and clear work area */
+	vol = get_ldnumber(&path);					/* Get target logical drive */
+	if (vol < 0) return FR_INVALID_DRIVE;
+	if (FatFs[vol]) FatFs[vol]->fs_type = 0;	/* Clear mounted volume */
+	pdrv = LD2PD(vol);	/* Physical drive */
+	part = LD2PT(vol);	/* Partition (0:create as new, 1-4:get from partition table) */
+
+	/* Check physical drive status */
+	stat = disk_initialize(pdrv);
+	if (stat & STA_NOINIT) return FR_NOT_READY;
+	if (stat & STA_PROTECT) return FR_WRITE_PROTECTED;
+	if (disk_ioctl(pdrv, GET_BLOCK_SIZE, &sz_blk) != RES_OK || !sz_blk || sz_blk > 32768 || (sz_blk & (sz_blk - 1))) sz_blk = 1;	/* Erase block to align data area */
+#if _MAX_SS != _MIN_SS		/* Get sector size of the medium */
+	if (disk_ioctl(pdrv, GET_SECTOR_SIZE, &ss) != RES_OK) return FR_DISK_ERR;
+	if (ss > _MAX_SS || ss < _MIN_SS || (ss & (ss - 1))) return FR_DISK_ERR;
+#else
+	ss = _MAX_SS;
+#endif
+	if ((au != 0 && au < ss) || au > 0x1000000 || (au & (au - 1))) return FR_INVALID_PARAMETER;	/* Check if au is valid */
+	au /= ss;	/* Cluster size in unit of sector */
+
+	/* Get working buffer */
+	buf = (BYTE*)work;		/* Working buffer */
+	sz_buf = len / ss;		/* Size of working buffer (sector) */
+	szb_buf = sz_buf * ss;	/* Size of working buffer (byte) */
+	if (!szb_buf) return FR_MKFS_ABORTED;
+
+	/* Determine where the volume to be located (b_vol, sz_vol) */
+	if (_MULTI_PARTITION && part != 0) {
+		/* Get partition information from partition table in the MBR */
+		if (disk_read(pdrv, buf, 0, 1) != RES_OK) return FR_DISK_ERR;	/* Load MBR */
+		if (ld_word(buf + BS_55AA) != 0xAA55) return FR_MKFS_ABORTED;	/* Check if MBR is valid */
+		pte = buf + (MBR_Table + (part - 1) * SZ_PTE);
+		if (!pte[PTE_System]) return FR_MKFS_ABORTED;	/* No partition? */
+		b_vol = ld_dword(pte + PTE_StLba);		/* Get volume start sector */
+		sz_vol = ld_dword(pte + PTE_SizLba);	/* Get volume size */
+	} else {
+		/* Create a single-partition in this function */
+		if (disk_ioctl(pdrv, GET_SECTOR_COUNT, &sz_vol) != RES_OK) return FR_DISK_ERR;
+		b_vol = (opt & FM_SFD) ? 0 : 63;		/* Volume start sector */
+		if (sz_vol < b_vol) return FR_MKFS_ABORTED;
+		sz_vol -= b_vol;						/* Volume size */
+	}
+	if (sz_vol < 128) return FR_MKFS_ABORTED;	/* Check if volume size is >=128s */
+
+	/* Pre-determine the FAT type */
+	do {
+		if (_FS_EXFAT && (opt & FM_EXFAT)) {	/* exFAT possible? */
+			if ((opt & FM_ANY) == FM_EXFAT || sz_vol >= 0x4000000 || au > 128) {	/* exFAT only, vol >= 64Ms or au > 128s ? */
+				fmt = FS_EXFAT; break;
+			}
+		}
+		if (au > 128) return FR_INVALID_PARAMETER;	/* Too large au for FAT/FAT32 */
+		if (opt & FM_FAT32) {	/* FAT32 possible? */
+			if ((opt & FM_ANY) == FM_FAT32 || !(opt & FM_FAT)) {	/* FAT32 only or no-FAT? */
+				fmt = FS_FAT32; break;
+			}
+		}
+		if (!(opt & FM_FAT)) return FR_INVALID_PARAMETER;	/* no-FAT? */
+		fmt = FS_FAT16;
+	} while (0);
+
+#if _FS_EXFAT
+	if (fmt == FS_EXFAT) {	/* Create an exFAT volume */
+		DWORD szb_bit, szb_case, sum, nb, cl;
+		WCHAR ch, si;
+		UINT j, st;
+		BYTE b;
+
+		if (sz_vol < 0x1000) return FR_MKFS_ABORTED;	/* Too small volume? */
+#if _USE_TRIM
+		tbl[0] = b_vol; tbl[1] = b_vol + sz_vol - 1;	/* Inform the device the volume area can be erased */
+		disk_ioctl(pdrv, CTRL_TRIM, tbl);
+#endif
+		/* Determine FAT location, data location and number of clusters */
+		if (!au) {	/* au auto-selection */
+			au = 8;
+			if (sz_vol >= 0x80000) au = 64;		/* >= 512Ks */
+			if (sz_vol >= 0x4000000) au = 256;	/* >= 64Ms */
+		}
+		b_fat = b_vol + 32;										/* FAT start at offset 32 */
+		sz_fat = ((sz_vol / au + 2) * 4 + ss - 1) / ss;			/* Number of FAT sectors */
+		b_data = (b_fat + sz_fat + sz_blk - 1) & ~(sz_blk - 1);	/* Align data area to the erase block boundary */
+		if (b_data >= sz_vol / 2) return FR_MKFS_ABORTED;		/* Too small volume? */
+		n_clst = (sz_vol - (b_data - b_vol)) / au;				/* Number of clusters */
+		if (n_clst <16) return FR_MKFS_ABORTED;					/* Too few clusters? */
+		if (n_clst > MAX_EXFAT) return FR_MKFS_ABORTED;			/* Too many clusters? */
+
+		szb_bit = (n_clst + 7) / 8;						/* Size of allocation bitmap */
+		tbl[0] = (szb_bit + au * ss - 1) / (au * ss);	/* Number of allocation bitmap clusters */
+
+		/* Create a compressed up-case table */
+		sect = b_data + au * tbl[0];	/* Table start sector */
+		sum = 0;						/* Table checksum to be stored in the 82 entry */
+		st = si = i = j = szb_case = 0;
+		do {
+			switch (st) {
+			case 0:
+				ch = ff_wtoupper(si);	/* Get an up-case char */
+				if (ch != si) {
+					si++; break;		/* Store the up-case char if exist */
+				}
+				for (j = 1; (WCHAR)(si + j) && (WCHAR)(si + j) == ff_wtoupper((WCHAR)(si + j)); j++) ;	/* Get run length of no-case block */
+				if (j >= 128) {
+					ch = 0xFFFF; st = 2; break;	/* Compress the no-case block if run is >= 128 */
+				}
+				st = 1;			/* Do not compress short run */
+				/* continue */
+			case 1:
+				ch = si++;		/* Fill the short run */
+				if (--j == 0) st = 0;
+				break;
+			default:
+				ch = (WCHAR)j; si += j;	/* Number of chars to skip */
+				st = 0;
+			}
+			sum = xsum32(buf[i + 0] = (BYTE)ch, sum);		/* Put it into the write buffer */
+			sum = xsum32(buf[i + 1] = (BYTE)(ch >> 8), sum);
+			i += 2; szb_case += 2;
+			if (!si || i == szb_buf) {		/* Write buffered data when buffer full or end of process */
+				n = (i + ss - 1) / ss;
+				if (disk_write(pdrv, buf, sect, n) != RES_OK) return FR_DISK_ERR;
+				sect += n; i = 0;
+			}
+		} while (si);
+		tbl[1] = (szb_case + au * ss - 1) / (au * ss);	/* Number of up-case table clusters */
+		tbl[2] = 1;										/* Number of root dir clusters */
+
+		/* Initialize the allocation bitmap */
+		sect = b_data; nsect = (szb_bit + ss - 1) / ss;	/* Start of bitmap and number of sectors */
+		nb = tbl[0] + tbl[1] + tbl[2];					/* Number of clusters in-use by system */
+		do {
+			mem_set(buf, 0, szb_buf);
+			for (i = 0; nb >= 8 && i < szb_buf; buf[i++] = 0xFF, nb -= 8) ;
+			for (b = 1; nb && i < szb_buf; buf[i] |= b, b <<= 1, nb--) ;
+			n = (nsect > sz_buf) ? sz_buf : nsect;		/* Write the buffered data */
+			if (disk_write(pdrv, buf, sect, n) != RES_OK) return FR_DISK_ERR;
+			sect += n; nsect -= n;
+		} while (nsect);
+
+		/* Initialize the FAT */
+		sect = b_fat; nsect = sz_fat;	/* Start of FAT and number of FAT sectors */
+		j = nb = cl = 0;
+		do {
+			mem_set(buf, 0, szb_buf); i = 0;	/* Clear work area and reset write index */
+			if (cl == 0) {	/* Set entry 0 and 1 */
+				st_dword(buf + i, 0xFFFFFFF8); i += 4; cl++;
+				st_dword(buf + i, 0xFFFFFFFF); i += 4; cl++;
+			}
+			do {			/* Create chains of bitmap, up-case and root dir */
+				while (nb && i < szb_buf) {			/* Create a chain */
+					st_dword(buf + i, (nb > 1) ? cl + 1 : 0xFFFFFFFF);
+					i += 4; cl++; nb--;
+				}
+				if (!nb && j < 3) nb = tbl[j++];	/* Next chain */
+			} while (nb && i < szb_buf);
+			n = (nsect > sz_buf) ? sz_buf : nsect;	/* Write the buffered data */
+			if (disk_write(pdrv, buf, sect, n) != RES_OK) return FR_DISK_ERR;
+			sect += n; nsect -= n;
+		} while (nsect);
+
+		/* Initialize the root directory */
+		mem_set(buf, 0, szb_buf);
+		buf[SZDIRE * 0 + 0] = 0x83;		/* 83 entry (volume label) */
+		buf[SZDIRE * 1 + 0] = 0x81;		/* 81 entry (allocation bitmap) */
+		st_dword(buf + SZDIRE * 1 + 20, 2);
+		st_dword(buf + SZDIRE * 1 + 24, szb_bit);
+		buf[SZDIRE * 2 + 0] = 0x82;		/* 82 entry (up-case table) */
+		st_dword(buf + SZDIRE * 2 + 4, sum);
+		st_dword(buf + SZDIRE * 2 + 20, 2 + tbl[0]);
+		st_dword(buf + SZDIRE * 2 + 24, szb_case);
+		sect = b_data + au * (tbl[0] + tbl[1]);	nsect = au;	/* Start of the root directory and number of sectors */
+		do {	/* Fill root directory sectors */
+			n = (nsect > sz_buf) ? sz_buf : nsect;
+			if (disk_write(pdrv, buf, sect, n) != RES_OK) return FR_DISK_ERR;
+			mem_set(buf, 0, ss);
+			sect += n; nsect -= n;
+		} while (nsect);
+
+		/* Create two set of the exFAT VBR blocks */
+		sect = b_vol;
+		for (n = 0; n < 2; n++) {
+			/* Main record (+0) */
+			mem_set(buf, 0, ss);
+			mem_cpy(buf + BS_JmpBoot, "\xEB\x76\x90" "EXFAT   ", 11);	/* Boot jump code (x86), OEM name */
+			st_dword(buf + BPB_VolOfsEx, b_vol);					/* Volume offset in the physical drive [sector] */
+			st_dword(buf + BPB_TotSecEx, sz_vol);					/* Volume size [sector] */
+			st_dword(buf + BPB_FatOfsEx, b_fat - b_vol);			/* FAT offset [sector] */
+			st_dword(buf + BPB_FatSzEx, sz_fat);					/* FAT size [sector] */
+			st_dword(buf + BPB_DataOfsEx, b_data - b_vol);			/* Data offset [sector] */
+			st_dword(buf + BPB_NumClusEx, n_clst);					/* Number of clusters */
+			st_dword(buf + BPB_RootClusEx, 2 + tbl[0] + tbl[1]);	/* Root dir cluster # */
+			st_dword(buf + BPB_VolIDEx, GET_FATTIME());				/* VSN */
+			st_word(buf + BPB_FSVerEx, 0x100);						/* File system version (1.00) */
+			for (buf[BPB_BytsPerSecEx] = 0, i = ss; i >>= 1; buf[BPB_BytsPerSecEx]++) ;	/* Log2 of sector size [byte] */
+			for (buf[BPB_SecPerClusEx] = 0, i = au; i >>= 1; buf[BPB_SecPerClusEx]++) ;	/* Log2 of cluster size [sector] */
+			buf[BPB_NumFATsEx] = 1;					/* Number of FATs */
+			buf[BPB_DrvNumEx] = 0x80;				/* Drive number (for int13) */
+			st_word(buf + BS_BootCodeEx, 0xFEEB);	/* Boot code (x86) */
+			st_word(buf + BS_55AA, 0xAA55);			/* Signature (placed here regardless of sector size) */
+			for (i = sum = 0; i < ss; i++) {		/* VBR checksum */
+				if (i != BPB_VolFlagEx && i != BPB_VolFlagEx + 1 && i != BPB_PercInUseEx) sum = xsum32(buf[i], sum);
+			}
+			if (disk_write(pdrv, buf, sect++, 1) != RES_OK) return FR_DISK_ERR;
+			/* Extended bootstrap record (+1..+8) */
+			mem_set(buf, 0, ss);
+			st_word(buf + ss - 2, 0xAA55);	/* Signature (placed at end of sector) */
+			for (j = 1; j < 9; j++) {
+				for (i = 0; i < ss; sum = xsum32(buf[i++], sum)) ;	/* VBR checksum */
+				if (disk_write(pdrv, buf, sect++, 1) != RES_OK) return FR_DISK_ERR;
+			}
+			/* OEM/Reserved record (+9..+10) */
+			mem_set(buf, 0, ss);
+			for ( ; j < 11; j++) {
+				for (i = 0; i < ss; sum = xsum32(buf[i++], sum)) ;	/* VBR checksum */
+				if (disk_write(pdrv, buf, sect++, 1) != RES_OK) return FR_DISK_ERR;
+			}
+			/* Sum record (+11) */
+			for (i = 0; i < ss; i += 4) st_dword(buf + i, sum);		/* Fill with checksum value */
+			if (disk_write(pdrv, buf, sect++, 1) != RES_OK) return FR_DISK_ERR;
+		}
+
+	} else
+#endif	/* _FS_EXFAT */
+	{	/* Create an FAT12/16/32 volume */
+		do {
+			pau = au;
+			/* Pre-determine number of clusters and FAT sub-type */
+			if (fmt == FS_FAT32) {	/* FAT32 volume */
+				if (!pau) {	/* au auto-selection */
+					n = sz_vol / 0x20000;	/* Volume size in unit of 128KS */
+					for (i = 0, pau = 1; cst32[i] && cst32[i] <= n; i++, pau <<= 1) ;	/* Get from table */
+				}
+				n_clst = sz_vol / pau;	/* Number of clusters */
+				sz_fat = (n_clst * 4 + 8 + ss - 1) / ss;	/* FAT size [sector] */
+				sz_rsv = 32;	/* Number of reserved sectors */
+				sz_dir = 0;		/* No static directory */
+				if (n_clst <= MAX_FAT16 || n_clst > MAX_FAT32) return FR_MKFS_ABORTED;
+			} else {				/* FAT12/16 volume */
+				if (!pau) {	/* au auto-selection */
+					n = sz_vol / 0x1000;	/* Volume size in unit of 4KS */
+					for (i = 0, pau = 1; cst[i] && cst[i] <= n; i++, pau <<= 1) ;	/* Get from table */
+				}
+				n_clst = sz_vol / pau;
+				if (n_clst > MAX_FAT12) {
+					n = n_clst * 2 + 4;		/* FAT size [byte] */
+				} else {
+					fmt = FS_FAT12;
+					n = (n_clst * 3 + 1) / 2 + 3;	/* FAT size [byte] */
+				}
+				sz_fat = (n + ss - 1) / ss;		/* FAT size [sector] */
+				sz_rsv = 1;						/* Number of reserved sectors */
+				sz_dir = (DWORD)n_rootdir * SZDIRE / ss;	/* Rootdir size [sector] */
+			}
+			b_fat = b_vol + sz_rsv;						/* FAT base */
+			b_data = b_fat + sz_fat * n_fats + sz_dir;	/* Data base */
+
+			/* Align data base to erase block boundary (for flash memory media) */
+			n = ((b_data + sz_blk - 1) & ~(sz_blk - 1)) - b_data;	/* Next nearest erase block from current data base */
+			if (fmt == FS_FAT32) {		/* FAT32: Move FAT base */
+				sz_rsv += n; b_fat += n;
+			} else {					/* FAT12/16: Expand FAT size */
+				sz_fat += n / n_fats;
+			}
+
+			/* Determine number of clusters and final check of validity of the FAT sub-type */
+			if (sz_vol < b_data + pau * 16 - b_vol) return FR_MKFS_ABORTED;	/* Too small volume */
+			n_clst = (sz_vol - sz_rsv - sz_fat * n_fats - sz_dir) / pau;
+			if (fmt == FS_FAT32) {
+				if (n_clst <= MAX_FAT16) {	/* Too few clusters for FAT32 */
+					if (!au && (au = pau / 2) != 0) continue;	/* Adjust cluster size and retry */
+					return FR_MKFS_ABORTED;
+				}
+			}
+			if (fmt == FS_FAT16) {
+				if (n_clst > MAX_FAT16) {	/* Too many clusters for FAT16 */
+					if (!au && (pau * 2) <= 64) {
+						au = pau * 2; continue;		/* Adjust cluster size and retry */
+					}
+					if ((opt & FM_FAT32)) {
+						fmt = FS_FAT32; continue;	/* Switch type to FAT32 and retry */
+					}
+					if (!au && (au = pau * 2) <= 128) continue;	/* Adjust cluster size and retry */
+					return FR_MKFS_ABORTED;
+				}
+				if  (n_clst <= MAX_FAT12) {	/* Too few clusters for FAT16 */
+					if (!au && (au = pau * 2) <= 128) continue;	/* Adjust cluster size and retry */
+					return FR_MKFS_ABORTED;
+				}
+			}
+			if (fmt == FS_FAT12 && n_clst > MAX_FAT12) return FR_MKFS_ABORTED;	/* Too many clusters for FAT12 */
+
+			/* Ok, it is the valid cluster configuration */
+			break;
+		} while (1);
+
+#if _USE_TRIM
+		tbl[0] = b_vol; tbl[1] = b_vol + sz_vol - 1;	/* Inform the device the volume area can be erased */
+		disk_ioctl(pdrv, CTRL_TRIM, tbl);
+#endif
+		/* Create FAT VBR */
+		mem_set(buf, 0, ss);
+		mem_cpy(buf + BS_JmpBoot, "\xEB\xFE\x90" "MSDOS5.0", 11);/* Boot jump code (x86), OEM name */
+		st_word(buf + BPB_BytsPerSec, ss);				/* Sector size [byte] */
+		buf[BPB_SecPerClus] = (BYTE)pau;				/* Cluster size [sector] */
+		st_word(buf + BPB_RsvdSecCnt, (WORD)sz_rsv);	/* Size of reserved area */
+		buf[BPB_NumFATs] = (BYTE)n_fats;				/* Number of FATs */
+		st_word(buf + BPB_RootEntCnt, (WORD)((fmt == FS_FAT32) ? 0 : n_rootdir));	/* Number of root directory entries */
+		if (sz_vol < 0x10000) {
+			st_word(buf + BPB_TotSec16, (WORD)sz_vol);	/* Volume size in 16-bit LBA */
+		} else {
+			st_dword(buf + BPB_TotSec32, sz_vol);		/* Volume size in 32-bit LBA */
+		}
+		buf[BPB_Media] = 0xF8;							/* Media descriptor byte */
+		st_word(buf + BPB_SecPerTrk, 63);				/* Number of sectors per track (for int13) */
+		st_word(buf + BPB_NumHeads, 255);				/* Number of heads (for int13) */
+		st_dword(buf + BPB_HiddSec, b_vol);				/* Volume offset in the physical drive [sector] */
+		if (fmt == FS_FAT32) {
+			st_dword(buf + BS_VolID32, GET_FATTIME());	/* VSN */
+			st_dword(buf + BPB_FATSz32, sz_fat);		/* FAT size [sector] */
+			st_dword(buf + BPB_RootClus32, 2);			/* Root directory cluster # (2) */
+			st_word(buf + BPB_FSInfo32, 1);				/* Offset of FSINFO sector (VBR + 1) */
+			st_word(buf + BPB_BkBootSec32, 6);			/* Offset of backup VBR (VBR + 6) */
+			buf[BS_DrvNum32] = 0x80;					/* Drive number (for int13) */
+			buf[BS_BootSig32] = 0x29;					/* Extended boot signature */
+			mem_cpy(buf + BS_VolLab32, "NO NAME    " "FAT32   ", 19);	/* Volume label, FAT signature */
+		} else {
+			st_dword(buf + BS_VolID, GET_FATTIME());	/* VSN */
+			st_word(buf + BPB_FATSz16, (WORD)sz_fat);	/* FAT size [sector] */
+			buf[BS_DrvNum] = 0x80;						/* Drive number (for int13) */
+			buf[BS_BootSig] = 0x29;						/* Extended boot signature */
+			mem_cpy(buf + BS_VolLab, "NO NAME    " "FAT     ", 19);	/* Volume label, FAT signature */
+		}
+		st_word(buf + BS_55AA, 0xAA55);					/* Signature (offset is fixed here regardless of sector size) */
+		if (disk_write(pdrv, buf, b_vol, 1) != RES_OK) return FR_DISK_ERR;	/* Write it to the VBR sector */
+
+		/* Create FSINFO record if needed */
+		if (fmt == FS_FAT32) {
+			disk_write(pdrv, buf, b_vol + 6, 1);		/* Write backup VBR (VBR + 6) */
+			mem_set(buf, 0, ss);
+			st_dword(buf + FSI_LeadSig, 0x41615252);
+			st_dword(buf + FSI_StrucSig, 0x61417272);
+			st_dword(buf + FSI_Free_Count, n_clst - 1);	/* Number of free clusters */
+			st_dword(buf + FSI_Nxt_Free, 2);			/* Last allocated cluster# */
+			st_word(buf + BS_55AA, 0xAA55);
+			disk_write(pdrv, buf, b_vol + 7, 1);		/* Write backup FSINFO (VBR + 7) */
+			disk_write(pdrv, buf, b_vol + 1, 1);		/* Write original FSINFO (VBR + 1) */
+		}
+
+		/* Initialize FAT area */
+		mem_set(buf, 0, (UINT)szb_buf);
+		sect = b_fat;		/* FAT start sector */
+		for (i = 0; i < n_fats; i++) {			/* Initialize FATs each */
+			if (fmt == FS_FAT32) {
+				st_dword(buf + 0, 0xFFFFFFF8);	/* Entry 0 */
+				st_dword(buf + 4, 0xFFFFFFFF);	/* Entry 1 */
+				st_dword(buf + 8, 0x0FFFFFFF);	/* Entry 2 (root directory) */
+			} else {
+				st_dword(buf + 0, (fmt == FS_FAT12) ? 0xFFFFF8 : 0xFFFFFFF8);	/* Entry 0 and 1 */
+			}
+			nsect = sz_fat;		/* Number of FAT sectors */
+			do {	/* Fill FAT sectors */
+				n = (nsect > sz_buf) ? sz_buf : nsect;
+				if (disk_write(pdrv, buf, sect, (UINT)n) != RES_OK) return FR_DISK_ERR;
+				mem_set(buf, 0, ss);
+				sect += n; nsect -= n;
+			} while (nsect);
+		}
+
+		/* Initialize root directory (fill with zero) */
+		nsect = (fmt == FS_FAT32) ? pau : sz_dir;	/* Number of root directory sectors */
+		do {
+			n = (nsect > sz_buf) ? sz_buf : nsect;
+			if (disk_write(pdrv, buf, sect, (UINT)n) != RES_OK) return FR_DISK_ERR;
+			sect += n; nsect -= n;
+		} while (nsect);
+	}
+
+	/* Determine system ID in the partition table */
+	if (_FS_EXFAT && fmt == FS_EXFAT) {
+		sys = 0x07;			/* HPFS/NTFS/exFAT */
+	} else {
+		if (fmt == FS_FAT32) {
+			sys = 0x0C;		/* FAT32X */
+		} else {
+			if (sz_vol >= 0x10000) {
+				sys = 0x06;	/* FAT12/16 (>=64KS) */
+			} else {
+				sys = (fmt == FS_FAT16) ? 0x04 : 0x01;	/* FAT16 (<64KS) : FAT12 (<64KS) */
+			}
+		}
+	}
+
+	if (_MULTI_PARTITION && part != 0) {
+		/* Update system ID in the partition table */
+		if (disk_read(pdrv, buf, 0, 1) != RES_OK) return FR_DISK_ERR;	/* Read the MBR */
+		buf[MBR_Table + (part - 1) * SZ_PTE + PTE_System] = sys;		/* Set system type */
+		if (disk_write(pdrv, buf, 0, 1) != RES_OK) return FR_DISK_ERR;	/* Write it back to the MBR */
+	} else {
+		if (!(opt & FM_SFD)) {
+			/* Create partition table in FDISK format */
+			mem_set(buf, 0, ss);
+			st_word(buf + BS_55AA, 0xAA55);		/* MBR signature */
+			pte = buf + MBR_Table;				/* Create partition table for single partition in the drive */
+			pte[PTE_Boot] = 0;					/* Boot indicator */
+			pte[PTE_StHead] = 1;				/* Start head */
+			pte[PTE_StSec] = 1;					/* Start sector */
+			pte[PTE_StCyl] = 0;					/* Start cylinder */
+			pte[PTE_System] = sys;				/* System type */
+			n = (b_vol + sz_vol) / (63 * 255);	/* (End CHS is incorrect) */
+			pte[PTE_EdHead] = 254;				/* End head */
+			pte[PTE_EdSec] = (BYTE)(n >> 2 | 63);	/* End sector */
+			pte[PTE_EdCyl] = (BYTE)n;			/* End cylinder */
+			st_dword(pte + PTE_StLba, b_vol);	/* Start offset in LBA */
+			st_dword(pte + PTE_SizLba, sz_vol);	/* Size in sectors */
+			if (disk_write(pdrv, buf, 0, 1) != RES_OK) return FR_DISK_ERR;	/* Write it to the MBR */
+		}
+	}
+
+	if (disk_ioctl(pdrv, CTRL_SYNC, 0) != RES_OK) return FR_DISK_ERR;
+
+	return FR_OK;
+}
+
+
+
+#if _MULTI_PARTITION
+/*-----------------------------------------------------------------------*/
+/* Create partition table on the physical drive                          */
+/*-----------------------------------------------------------------------*/
+
+FRESULT f_fdisk (
+	BYTE pdrv,			/* Physical drive number */
+	const DWORD* szt,	/* Pointer to the size table for each partitions */
+	void* work			/* Pointer to the working buffer */
+)
+{
+	UINT i, n, sz_cyl, tot_cyl, b_cyl, e_cyl, p_cyl;
+	BYTE s_hd, e_hd, *p, *buf = (BYTE*)work;
+	DSTATUS stat;
+	DWORD sz_disk, sz_part, s_part;
+
+
+	stat = disk_initialize(pdrv);
+	if (stat & STA_NOINIT) return FR_NOT_READY;
+	if (stat & STA_PROTECT) return FR_WRITE_PROTECTED;
+	if (disk_ioctl(pdrv, GET_SECTOR_COUNT, &sz_disk)) return FR_DISK_ERR;
+
+	/* Determine the CHS without any care of the drive geometry */
+	for (n = 16; n < 256 && sz_disk / n / 63 > 1024; n *= 2) ;
+	if (n == 256) n--;
+	e_hd = n - 1;
+	sz_cyl = 63 * n;
+	tot_cyl = sz_disk / sz_cyl;
+
+	/* Create partition table */
+	mem_set(buf, 0, _MAX_SS);
+	p = buf + MBR_Table; b_cyl = 0;
+	for (i = 0; i < 4; i++, p += SZ_PTE) {
+		p_cyl = (szt[i] <= 100U) ? (DWORD)tot_cyl * szt[i] / 100 : szt[i] / sz_cyl;
+		if (!p_cyl) continue;
+		s_part = (DWORD)sz_cyl * b_cyl;
+		sz_part = (DWORD)sz_cyl * p_cyl;
+		if (i == 0) {	/* Exclude first track of cylinder 0 */
+			s_hd = 1;
+			s_part += 63; sz_part -= 63;
+		} else {
+			s_hd = 0;
+		}
+		e_cyl = b_cyl + p_cyl - 1;
+		if (e_cyl >= tot_cyl) return FR_INVALID_PARAMETER;
+
+		/* Set partition table */
+		p[1] = s_hd;						/* Start head */
+		p[2] = (BYTE)((b_cyl >> 2) + 1);	/* Start sector */
+		p[3] = (BYTE)b_cyl;					/* Start cylinder */
+		p[4] = 0x06;						/* System type (temporary setting) */
+		p[5] = e_hd;						/* End head */
+		p[6] = (BYTE)((e_cyl >> 2) + 63);	/* End sector */
+		p[7] = (BYTE)e_cyl;					/* End cylinder */
+		st_dword(p + 8, s_part);			/* Start sector in LBA */
+		st_dword(p + 12, sz_part);			/* Partition size */
+
+		/* Next partition */
+		b_cyl += p_cyl;
+	}
+	st_word(p, 0xAA55);
+
+	/* Write it to the MBR */
+	return (disk_write(pdrv, buf, 0, 1) != RES_OK || disk_ioctl(pdrv, CTRL_SYNC, 0) != RES_OK) ? FR_DISK_ERR : FR_OK;
+}
+
+#endif /* _MULTI_PARTITION */
+#endif /* _USE_MKFS && !_FS_READONLY */
+
+
+
+
+#if _USE_STRFUNC
+/*-----------------------------------------------------------------------*/
+/* Get a string from the file                                            */
+/*-----------------------------------------------------------------------*/
+
+TCHAR* f_gets (
+	TCHAR* buff,	/* Pointer to the string buffer to read */
+	int len,		/* Size of string buffer (characters) */
+	FIL* fp			/* Pointer to the file object */
+)
+{
+	int n = 0;
+	TCHAR c, *p = buff;
+	BYTE s[2];
+	UINT rc;
+
+
+	while (n < len - 1) {	/* Read characters until buffer gets filled */
+#if _LFN_UNICODE
+#if _STRF_ENCODE == 3		/* Read a character in UTF-8 */
+		f_read(fp, s, 1, &rc);
+		if (rc != 1) break;
+		c = s[0];
+		if (c >= 0x80) {
+			if (c < 0xC0) continue;	/* Skip stray trailer */
+			if (c < 0xE0) {			/* Two-byte sequence */
+				f_read(fp, s, 1, &rc);
+				if (rc != 1) break;
+				c = (c & 0x1F) << 6 | (s[0] & 0x3F);
+				if (c < 0x80) c = '?';
+			} else {
+				if (c < 0xF0) {		/* Three-byte sequence */
+					f_read(fp, s, 2, &rc);
+					if (rc != 2) break;
+					c = c << 12 | (s[0] & 0x3F) << 6 | (s[1] & 0x3F);
+					if (c < 0x800) c = '?';
+				} else {			/* Reject four-byte sequence */
+					c = '?';
+				}
+			}
+		}
+#elif _STRF_ENCODE == 2		/* Read a character in UTF-16BE */
+		f_read(fp, s, 2, &rc);
+		if (rc != 2) break;
+		c = s[1] + (s[0] << 8);
+#elif _STRF_ENCODE == 1		/* Read a character in UTF-16LE */
+		f_read(fp, s, 2, &rc);
+		if (rc != 2) break;
+		c = s[0] + (s[1] << 8);
+#else						/* Read a character in ANSI/OEM */
+		f_read(fp, s, 1, &rc);
+		if (rc != 1) break;
+		c = s[0];
+		if (IsDBCS1(c)) {
+			f_read(fp, s, 1, &rc);
+			if (rc != 1) break;
+			c = (c << 8) + s[0];
+		}
+		c = ff_convert(c, 1);	/* OEM -> Unicode */
+		if (!c) c = '?';
+#endif
+#else						/* Read a character without conversion */
+		f_read(fp, s, 1, &rc);
+		if (rc != 1) break;
+		c = s[0];
+#endif
+		if (_USE_STRFUNC == 2 && c == '\r') continue;	/* Strip '\r' */
+		*p++ = c;
+		n++;
+		if (c == '\n') break;		/* Break on EOL */
+	}
+	*p = 0;
+	return n ? buff : 0;			/* When no data read (eof or error), return with error. */
+}
+
+
+
+
+#if !_FS_READONLY
+#include <stdarg.h>
+/*-----------------------------------------------------------------------*/
+/* Put a character to the file                                           */
+/*-----------------------------------------------------------------------*/
+
+typedef struct {
+	FIL *fp;		/* Ptr to the writing file */
+	int idx, nchr;	/* Write index of buf[] (-1:error), number of chars written */
+	BYTE buf[64];	/* Write buffer */
+} putbuff;
+
+
+static
+void putc_bfd (		/* Buffered write with code conversion */
+	putbuff* pb,
+	TCHAR c
+)
+{
+	UINT bw;
+	int i;
+
+
+	if (_USE_STRFUNC == 2 && c == '\n') {	 /* LF -> CRLF conversion */
+		putc_bfd(pb, '\r');
+	}
+
+	i = pb->idx;		/* Write index of pb->buf[] */
+	if (i < 0) return;
+
+#if _LFN_UNICODE
+#if _STRF_ENCODE == 3			/* Write a character in UTF-8 */
+	if (c < 0x80) {				/* 7-bit */
+		pb->buf[i++] = (BYTE)c;
+	} else {
+		if (c < 0x800) {		/* 11-bit */
+			pb->buf[i++] = (BYTE)(0xC0 | c >> 6);
+		} else {				/* 16-bit */
+			pb->buf[i++] = (BYTE)(0xE0 | c >> 12);
+			pb->buf[i++] = (BYTE)(0x80 | (c >> 6 & 0x3F));
+		}
+		pb->buf[i++] = (BYTE)(0x80 | (c & 0x3F));
+	}
+#elif _STRF_ENCODE == 2			/* Write a character in UTF-16BE */
+	pb->buf[i++] = (BYTE)(c >> 8);
+	pb->buf[i++] = (BYTE)c;
+#elif _STRF_ENCODE == 1			/* Write a character in UTF-16LE */
+	pb->buf[i++] = (BYTE)c;
+	pb->buf[i++] = (BYTE)(c >> 8);
+#else							/* Write a character in ANSI/OEM */
+	c = ff_convert(c, 0);	/* Unicode -> OEM */
+	if (!c) c = '?';
+	if (c >= 0x100)
+		pb->buf[i++] = (BYTE)(c >> 8);
+	pb->buf[i++] = (BYTE)c;
+#endif
+#else							/* Write a character without conversion */
+	pb->buf[i++] = (BYTE)c;
+#endif
+
+	if (i >= (int)(sizeof pb->buf) - 3) {	/* Write buffered characters to the file */
+		f_write(pb->fp, pb->buf, (UINT)i, &bw);
+		i = (bw == (UINT)i) ? 0 : -1;
+	}
+	pb->idx = i;
+	pb->nchr++;
+}
+
+
+static
+int putc_flush (		/* Flush left characters in the buffer */
+	putbuff* pb
+)
+{
+	UINT nw;
+
+	if (   pb->idx >= 0	/* Flush buffered characters to the file */
+		&& f_write(pb->fp, pb->buf, (UINT)pb->idx, &nw) == FR_OK
+		&& (UINT)pb->idx == nw) return pb->nchr;
+	return EOF;
+}
+
+
+static
+void putc_init (		/* Initialize write buffer */
+	putbuff* pb,
+	FIL* fp
+)
+{
+	pb->fp = fp;
+	pb->nchr = pb->idx = 0;
+}
+
+
+
+int f_putc (
+	TCHAR c,	/* A character to be output */
+	FIL* fp		/* Pointer to the file object */
+)
+{
+	putbuff pb;
+
+
+	putc_init(&pb, fp);
+	putc_bfd(&pb, c);	/* Put the character */
+	return putc_flush(&pb);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Put a string to the file                                              */
+/*-----------------------------------------------------------------------*/
+
+int f_puts (
+	const TCHAR* str,	/* Pointer to the string to be output */
+	FIL* fp				/* Pointer to the file object */
+)
+{
+	putbuff pb;
+
+
+	putc_init(&pb, fp);
+	while (*str) putc_bfd(&pb, *str++);		/* Put the string */
+	return putc_flush(&pb);
+}
+
+
+
+
+/*-----------------------------------------------------------------------*/
+/* Put a formatted string to the file                                    */
+/*-----------------------------------------------------------------------*/
+
+int f_printf (
+	FIL* fp,			/* Pointer to the file object */
+	const TCHAR* fmt,	/* Pointer to the format string */
+	...					/* Optional arguments... */
+)
+{
+	va_list arp;
+	putbuff pb;
+	BYTE f, r;
+	UINT i, j, w;
+	DWORD v;
+	TCHAR c, d, str[32], *p;
+
+
+	putc_init(&pb, fp);
+
+	va_start(arp, fmt);
+
+	for (;;) {
+		c = *fmt++;
+		if (c == 0) break;			/* End of string */
+		if (c != '%') {				/* Non escape character */
+			putc_bfd(&pb, c);
+			continue;
+		}
+		w = f = 0;
+		c = *fmt++;
+		if (c == '0') {				/* Flag: '0' padding */
+			f = 1; c = *fmt++;
+		} else {
+			if (c == '-') {			/* Flag: left justified */
+				f = 2; c = *fmt++;
+			}
+		}
+		while (IsDigit(c)) {		/* Precision */
+			w = w * 10 + c - '0';
+			c = *fmt++;
+		}
+		if (c == 'l' || c == 'L') {	/* Prefix: Size is long int */
+			f |= 4; c = *fmt++;
+		}
+		if (!c) break;
+		d = c;
+		if (IsLower(d)) d -= 0x20;
+		switch (d) {				/* Type is... */
+		case 'S' :					/* String */
+			p = va_arg(arp, TCHAR*);
+			for (j = 0; p[j]; j++) ;
+			if (!(f & 2)) {
+				while (j++ < w) putc_bfd(&pb, ' ');
+			}
+			while (*p) putc_bfd(&pb, *p++);
+			while (j++ < w) putc_bfd(&pb, ' ');
+			continue;
+		case 'C' :					/* Character */
+			putc_bfd(&pb, (TCHAR)va_arg(arp, int)); continue;
+		case 'B' :					/* Binary */
+			r = 2; break;
+		case 'O' :					/* Octal */
+			r = 8; break;
+		case 'D' :					/* Signed decimal */
+		case 'U' :					/* Unsigned decimal */
+			r = 10; break;
+		case 'X' :					/* Hexdecimal */
+			r = 16; break;
+		default:					/* Unknown type (pass-through) */
+			putc_bfd(&pb, c); continue;
+		}
+
+		/* Get an argument and put it in numeral */
+		v = (f & 4) ? (DWORD)va_arg(arp, long) : ((d == 'D') ? (DWORD)(long)va_arg(arp, int) : (DWORD)va_arg(arp, unsigned int));
+		if (d == 'D' && (v & 0x80000000)) {
+			v = 0 - v;
+			f |= 8;
+		}
+		i = 0;
+		do {
+			d = (TCHAR)(v % r); v /= r;
+			if (d > 9) d += (c == 'x') ? 0x27 : 0x07;
+			str[i++] = d + '0';
+		} while (v && i < sizeof str / sizeof str[0]);
+		if (f & 8) str[i++] = '-';
+		j = i; d = (f & 1) ? '0' : ' ';
+		while (!(f & 2) && j++ < w) putc_bfd(&pb, d);
+		do putc_bfd(&pb, str[--i]); while (i);
+		while (j++ < w) putc_bfd(&pb, d);
+	}
+
+	va_end(arp);
+
+	return putc_flush(&pb);
+}
+
+#endif /* !_FS_READONLY */
+#endif /* _USE_STRFUNC */
diff --git a/crazyflie-firmware-src/src/lib/FatFS/ff.h b/crazyflie-firmware-src/src/lib/FatFS/ff.h
new file mode 100644
index 0000000000000000000000000000000000000000..981a88634fa0f1c9f53738fceac6fdb68587f3a6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/ff.h
@@ -0,0 +1,366 @@
+/*----------------------------------------------------------------------------/
+/  FatFs - Generic FAT file system module  R0.12b                             /
+/-----------------------------------------------------------------------------/
+/
+/ Copyright (C) 2016, ChaN, all right reserved.
+/
+/ FatFs module is an open source software. Redistribution and use of FatFs in
+/ source and binary forms, with or without modification, are permitted provided
+/ that the following condition is met:
+
+/ 1. Redistributions of source code must retain the above copyright notice,
+/    this condition and the following disclaimer.
+/
+/ This software is provided by the copyright holder and contributors "AS IS"
+/ and any warranties related to this software are DISCLAIMED.
+/ The copyright owner or contributors be NOT LIABLE for any damages caused
+/ by use of this software.
+/----------------------------------------------------------------------------*/
+
+
+#ifndef _FATFS
+#define _FATFS	68020	/* Revision ID */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include "integer.h"	/* Basic integer types */
+#include "ffconf.h"		/* FatFs configuration options */
+
+#if _FATFS != _FFCONF
+#error Wrong configuration file (ffconf.h).
+#endif
+
+
+
+/* Definitions of volume management */
+
+#if _MULTI_PARTITION		/* Multiple partition configuration */
+typedef struct {
+	BYTE pd;	/* Physical drive number */
+	BYTE pt;	/* Partition: 0:Auto detect, 1-4:Forced partition) */
+} PARTITION;
+extern PARTITION VolToPart[];	/* Volume - Partition resolution table */
+#define LD2PD(vol) (VolToPart[vol].pd)	/* Get physical drive number */
+#define LD2PT(vol) (VolToPart[vol].pt)	/* Get partition index */
+
+#else							/* Single partition configuration */
+#define LD2PD(vol) (BYTE)(vol)	/* Each logical drive is bound to the same physical drive number */
+#define LD2PT(vol) 0			/* Find first valid partition or in SFD */
+
+#endif
+
+
+
+/* Type of path name strings on FatFs API */
+
+#if _LFN_UNICODE			/* Unicode (UTF-16) string */
+#if _USE_LFN == 0
+#error _LFN_UNICODE must be 0 at non-LFN cfg.
+#endif
+#ifndef _INC_TCHAR
+typedef WCHAR TCHAR;
+#define _T(x) L ## x
+#define _TEXT(x) L ## x
+#endif
+#else						/* ANSI/OEM string */
+#ifndef _INC_TCHAR
+typedef char TCHAR;
+#define _T(x) x
+#define _TEXT(x) x
+#endif
+#endif
+
+
+
+/* Type of file size variables */
+
+#if _FS_EXFAT
+#if _USE_LFN == 0
+#error LFN must be enabled when enable exFAT
+#endif
+typedef QWORD FSIZE_t;
+#else
+typedef DWORD FSIZE_t;
+#endif
+
+
+
+/* File system object structure (FATFS) */
+
+typedef struct {
+	BYTE	fs_type;		/* File system type (0:N/A) */
+	BYTE	drv;			/* Physical drive number */
+	BYTE	n_fats;			/* Number of FATs (1 or 2) */
+	BYTE	wflag;			/* win[] flag (b0:dirty) */
+	BYTE	fsi_flag;		/* FSINFO flags (b7:disabled, b0:dirty) */
+	WORD	id;				/* File system mount ID */
+	WORD	n_rootdir;		/* Number of root directory entries (FAT12/16) */
+	WORD	csize;			/* Cluster size [sectors] */
+#if _MAX_SS != _MIN_SS
+	WORD	ssize;			/* Sector size (512, 1024, 2048 or 4096) */
+#endif
+#if _USE_LFN != 0
+	WCHAR*	lfnbuf;			/* LFN working buffer */
+#endif
+#if _FS_EXFAT
+	BYTE*	dirbuf;			/* Directory entry block scratchpad buffer */
+#endif
+#if _FS_REENTRANT
+	_SYNC_t	sobj;			/* Identifier of sync object */
+#endif
+#if !_FS_READONLY
+	DWORD	last_clst;		/* Last allocated cluster */
+	DWORD	free_clst;		/* Number of free clusters */
+#endif
+#if _FS_RPATH != 0
+	DWORD	cdir;			/* Current directory start cluster (0:root) */
+#if _FS_EXFAT
+	DWORD	cdc_scl;		/* Containing directory start cluster (invalid when cdir is 0) */
+	DWORD	cdc_size;		/* b31-b8:Size of containing directory, b7-b0: Chain status */
+	DWORD	cdc_ofs;		/* Offset in the containing directory (invalid when cdir is 0) */
+#endif
+#endif
+	DWORD	n_fatent;		/* Number of FAT entries (number of clusters + 2) */
+	DWORD	fsize;			/* Size of an FAT [sectors] */
+	DWORD	volbase;		/* Volume base sector */
+	DWORD	fatbase;		/* FAT base sector */
+	DWORD	dirbase;		/* Root directory base sector/cluster */
+	DWORD	database;		/* Data base sector */
+	DWORD	winsect;		/* Current sector appearing in the win[] */
+	BYTE	win[_MAX_SS];	/* Disk access window for Directory, FAT (and file data at tiny cfg) */
+} FATFS;
+
+
+
+/* Object ID and allocation information (_FDID) */
+
+typedef struct {
+	FATFS*	fs;			/* Pointer to the owner file system object */
+	WORD	id;			/* Owner file system mount ID */
+	BYTE	attr;		/* Object attribute */
+	BYTE	stat;		/* Object chain status (b1-0: =0:not contiguous, =2:contiguous (no data on FAT), =3:got flagmented, b2:sub-directory stretched) */
+	DWORD	sclust;		/* Object start cluster (0:no cluster or root directory) */
+	FSIZE_t	objsize;	/* Object size (valid when sclust != 0) */
+#if _FS_EXFAT
+	DWORD	n_cont;		/* Size of coutiguous part, clusters - 1 (valid when stat == 3) */
+	DWORD	c_scl;		/* Containing directory start cluster (valid when sclust != 0) */
+	DWORD	c_size;		/* b31-b8:Size of containing directory, b7-b0: Chain status (valid when c_scl != 0) */
+	DWORD	c_ofs;		/* Offset in the containing directory (valid when sclust != 0) */
+#endif
+#if _FS_LOCK != 0
+	UINT	lockid;		/* File lock ID origin from 1 (index of file semaphore table Files[]) */
+#endif
+} _FDID;
+
+
+
+/* File object structure (FIL) */
+
+typedef struct {
+	_FDID	obj;			/* Object identifier (must be the 1st member to detect invalid object pointer) */
+	BYTE	flag;			/* File status flags */
+	BYTE	err;			/* Abort flag (error code) */
+	FSIZE_t	fptr;			/* File read/write pointer (Zeroed on file open) */
+	DWORD	clust;			/* Current cluster of fpter (invalid when fprt is 0) */
+	DWORD	sect;			/* Sector number appearing in buf[] (0:invalid) */
+#if !_FS_READONLY
+	DWORD	dir_sect;		/* Sector number containing the directory entry */
+	BYTE*	dir_ptr;		/* Pointer to the directory entry in the win[] */
+#endif
+#if _USE_FASTSEEK
+	DWORD*	cltbl;			/* Pointer to the cluster link map table (nulled on open, set by application) */
+#endif
+#if !_FS_TINY
+	BYTE	buf[_MAX_SS];	/* File private data read/write window */
+#endif
+} FIL;
+
+
+
+/* Directory object structure (DIR) */
+
+typedef struct {
+	_FDID	obj;			/* Object identifier */
+	DWORD	dptr;			/* Current read/write offset */
+	DWORD	clust;			/* Current cluster */
+	DWORD	sect;			/* Current sector */
+	BYTE*	dir;			/* Pointer to the directory item in the win[] */
+	BYTE	fn[12];			/* SFN (in/out) {body[8],ext[3],status[1]} */
+#if _USE_LFN != 0
+	DWORD	blk_ofs;		/* Offset of current entry block being processed (0xFFFFFFFF:Invalid) */
+#endif
+#if _USE_FIND
+	const TCHAR* pat;		/* Pointer to the name matching pattern */
+#endif
+} DIR;
+
+
+
+/* File information structure (FILINFO) */
+
+typedef struct {
+	FSIZE_t	fsize;			/* File size */
+	WORD	fdate;			/* Modified date */
+	WORD	ftime;			/* Modified time */
+	BYTE	fattrib;		/* File attribute */
+#if _USE_LFN != 0
+	TCHAR	altname[13];			/* Altenative file name */
+	TCHAR	fname[_MAX_LFN + 1];	/* Primary file name */
+#else
+	TCHAR	fname[13];		/* File name */
+#endif
+} FILINFO;
+
+
+
+/* File function return code (FRESULT) */
+
+typedef enum {
+	FR_OK = 0,				/* (0) Succeeded */
+	FR_DISK_ERR,			/* (1) A hard error occurred in the low level disk I/O layer */
+	FR_INT_ERR,				/* (2) Assertion failed */
+	FR_NOT_READY,			/* (3) The physical drive cannot work */
+	FR_NO_FILE,				/* (4) Could not find the file */
+	FR_NO_PATH,				/* (5) Could not find the path */
+	FR_INVALID_NAME,		/* (6) The path name format is invalid */
+	FR_DENIED,				/* (7) Access denied due to prohibited access or directory full */
+	FR_EXIST,				/* (8) Access denied due to prohibited access */
+	FR_INVALID_OBJECT,		/* (9) The file/directory object is invalid */
+	FR_WRITE_PROTECTED,		/* (10) The physical drive is write protected */
+	FR_INVALID_DRIVE,		/* (11) The logical drive number is invalid */
+	FR_NOT_ENABLED,			/* (12) The volume has no work area */
+	FR_NO_FILESYSTEM,		/* (13) There is no valid FAT volume */
+	FR_MKFS_ABORTED,		/* (14) The f_mkfs() aborted due to any problem */
+	FR_TIMEOUT,				/* (15) Could not get a grant to access the volume within defined period */
+	FR_LOCKED,				/* (16) The operation is rejected according to the file sharing policy */
+	FR_NOT_ENOUGH_CORE,		/* (17) LFN working buffer could not be allocated */
+	FR_TOO_MANY_OPEN_FILES,	/* (18) Number of open files > _FS_LOCK */
+	FR_INVALID_PARAMETER	/* (19) Given parameter is invalid */
+} FRESULT;
+
+
+
+/*--------------------------------------------------------------*/
+/* FatFs module application interface                           */
+
+FRESULT f_open (FIL* fp, const TCHAR* path, BYTE mode);				/* Open or create a file */
+FRESULT f_close (FIL* fp);											/* Close an open file object */
+FRESULT f_read (FIL* fp, void* buff, UINT btr, UINT* br);			/* Read data from the file */
+FRESULT f_write (FIL* fp, const void* buff, UINT btw, UINT* bw);	/* Write data to the file */
+FRESULT f_lseek (FIL* fp, FSIZE_t ofs);								/* Move file pointer of the file object */
+FRESULT f_truncate (FIL* fp);										/* Truncate the file */
+FRESULT f_sync (FIL* fp);											/* Flush cached data of the writing file */
+FRESULT f_opendir (DIR* dp, const TCHAR* path);						/* Open a directory */
+FRESULT f_closedir (DIR* dp);										/* Close an open directory */
+FRESULT f_readdir (DIR* dp, FILINFO* fno);							/* Read a directory item */
+FRESULT f_findfirst (DIR* dp, FILINFO* fno, const TCHAR* path, const TCHAR* pattern);	/* Find first file */
+FRESULT f_findnext (DIR* dp, FILINFO* fno);							/* Find next file */
+FRESULT f_mkdir (const TCHAR* path);								/* Create a sub directory */
+FRESULT f_unlink (const TCHAR* path);								/* Delete an existing file or directory */
+FRESULT f_rename (const TCHAR* path_old, const TCHAR* path_new);	/* Rename/Move a file or directory */
+FRESULT f_stat (const TCHAR* path, FILINFO* fno);					/* Get file status */
+FRESULT f_chmod (const TCHAR* path, BYTE attr, BYTE mask);			/* Change attribute of a file/dir */
+FRESULT f_utime (const TCHAR* path, const FILINFO* fno);			/* Change timestamp of a file/dir */
+FRESULT f_chdir (const TCHAR* path);								/* Change current directory */
+FRESULT f_chdrive (const TCHAR* path);								/* Change current drive */
+FRESULT f_getcwd (TCHAR* buff, UINT len);							/* Get current directory */
+FRESULT f_getfree (const TCHAR* path, DWORD* nclst, FATFS** fatfs);	/* Get number of free clusters on the drive */
+FRESULT f_getlabel (const TCHAR* path, TCHAR* label, DWORD* vsn);	/* Get volume label */
+FRESULT f_setlabel (const TCHAR* label);							/* Set volume label */
+FRESULT f_forward (FIL* fp, UINT(*func)(const BYTE*,UINT), UINT btf, UINT* bf);	/* Forward data to the stream */
+FRESULT f_expand (FIL* fp, FSIZE_t szf, BYTE opt);					/* Allocate a contiguous block to the file */
+FRESULT f_mount (FATFS* fs, const TCHAR* path, BYTE opt);			/* Mount/Unmount a logical drive */
+FRESULT f_mkfs (const TCHAR* path, BYTE opt, DWORD au, void* work, UINT len);	/* Create a FAT volume */
+FRESULT f_fdisk (BYTE pdrv, const DWORD* szt, void* work);			/* Divide a physical drive into some partitions */
+int f_putc (TCHAR c, FIL* fp);										/* Put a character to the file */
+int f_puts (const TCHAR* str, FIL* cp);								/* Put a string to the file */
+int f_printf (FIL* fp, const TCHAR* str, ...);						/* Put a formatted string to the file */
+TCHAR* f_gets (TCHAR* buff, int len, FIL* fp);						/* Get a string from the file */
+
+#define f_eof(fp) ((int)((fp)->fptr == (fp)->obj.objsize))
+#define f_error(fp) ((fp)->err)
+#define f_tell(fp) ((fp)->fptr)
+#define f_size(fp) ((fp)->obj.objsize)
+#define f_rewind(fp) f_lseek((fp), 0)
+#define f_rewinddir(dp) f_readdir((dp), 0)
+
+#ifndef EOF
+#define EOF (-1)
+#endif
+
+
+
+
+/*--------------------------------------------------------------*/
+/* Additional user defined functions                            */
+
+/* RTC function */
+#if !_FS_READONLY && !_FS_NORTC
+DWORD get_fattime (void);
+#endif
+
+/* Unicode support functions */
+#if _USE_LFN != 0						/* Unicode - OEM code conversion */
+WCHAR ff_convert (WCHAR chr, UINT dir);	/* OEM-Unicode bidirectional conversion */
+WCHAR ff_wtoupper (WCHAR chr);			/* Unicode upper-case conversion */
+#if _USE_LFN == 3						/* Memory functions */
+void* ff_memalloc (UINT msize);			/* Allocate memory block */
+void ff_memfree (void* mblock);			/* Free memory block */
+#endif
+#endif
+
+/* Sync functions */
+#if _FS_REENTRANT
+int ff_cre_syncobj (BYTE vol, _SYNC_t* sobj);	/* Create a sync object */
+int ff_req_grant (_SYNC_t sobj);				/* Lock sync object */
+void ff_rel_grant (_SYNC_t sobj);				/* Unlock sync object */
+int ff_del_syncobj (_SYNC_t sobj);				/* Delete a sync object */
+#endif
+
+
+
+
+/*--------------------------------------------------------------*/
+/* Flags and offset address                                     */
+
+
+/* File access mode and open method flags (3rd argument of f_open) */
+#define	FA_READ				0x01
+#define	FA_WRITE			0x02
+#define	FA_OPEN_EXISTING	0x00
+#define	FA_CREATE_NEW		0x04
+#define	FA_CREATE_ALWAYS	0x08
+#define	FA_OPEN_ALWAYS		0x10
+#define	FA_OPEN_APPEND		0x30
+
+/* Fast seek controls (2nd argument of f_lseek) */
+#define CREATE_LINKMAP	((FSIZE_t)0 - 1)
+
+/* Format options (2nd argument of f_mkfs) */
+#define FM_FAT		0x01
+#define FM_FAT32	0x02
+#define FM_EXFAT	0x04
+#define FM_ANY		0x07
+#define FM_SFD		0x08
+
+/* Filesystem type (FATFS.fs_type) */
+#define FS_FAT12	1
+#define FS_FAT16	2
+#define FS_FAT32	3
+#define FS_EXFAT	4
+
+/* File attribute bits for directory entry (FILINFO.fattrib) */
+#define	AM_RDO	0x01	/* Read only */
+#define	AM_HID	0x02	/* Hidden */
+#define	AM_SYS	0x04	/* System */
+#define AM_DIR	0x10	/* Directory */
+#define AM_ARC	0x20	/* Archive */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* _FATFS */
diff --git a/crazyflie-firmware-src/src/lib/FatFS/history.txt b/crazyflie-firmware-src/src/lib/FatFS/history.txt
new file mode 100644
index 0000000000000000000000000000000000000000..b00f58c018e2ff461bc0eb2f2183cfde3f58ccbd
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/history.txt
@@ -0,0 +1,180 @@
+----------------------------------------------------------------------------
+  Revision history of FatFs module
+----------------------------------------------------------------------------
+
+R0.00 (February 26, 2006)
+  Prototype.
+
+
+R0.01 (April 29, 2006)
+  First stable version.
+
+
+R0.02 (June 01, 2006)
+  Added FAT12 support.
+  Removed unbuffered mode.
+  Fixed a problem on small (<32M) partition.
+
+
+R0.02a (June 10, 2006)
+  Added a configuration option (_FS_MINIMUM).
+
+
+R0.03 (September 22, 2006)
+  Added f_rename().
+  Changed option _FS_MINIMUM to _FS_MINIMIZE.
+
+
+R0.03a (December 11, 2006)
+  Improved cluster scan algorithm to write files fast.
+  Fixed f_mkdir() creates incorrect directory on FAT32.
+
+
+R0.04 (February 04, 2007)
+  Added f_mkfs().
+  Supported multiple drive system.
+  Changed some interfaces for multiple drive system.
+  Changed f_mountdrv() to f_mount().
+
+
+R0.04a (April 01, 2007)
+  Supported multiple partitions on a physical drive.
+  Added a capability of extending file size to f_lseek().
+  Added minimization level 3.
+  Fixed an endian sensitive code in f_mkfs().
+
+
+R0.04b (May 05, 2007)
+  Added a configuration option _USE_NTFLAG.
+  Added FSINFO support.
+  Fixed DBCS name can result FR_INVALID_NAME.
+  Fixed short seek (<= csize) collapses the file object.
+
+
+R0.05 (August 25, 2007)
+  Changed arguments of f_read(), f_write() and f_mkfs().
+  Fixed f_mkfs() on FAT32 creates incorrect FSINFO.
+  Fixed f_mkdir() on FAT32 creates incorrect directory.
+
+
+R0.05a (February 03, 2008)
+  Added f_truncate() and f_utime().
+  Fixed off by one error at FAT sub-type determination.
+  Fixed btr in f_read() can be mistruncated.
+  Fixed cached sector is not flushed when create and close without write.
+
+
+R0.06 (April 01, 2008)
+  Added fputc(), fputs(), fprintf() and fgets().
+  Improved performance of f_lseek() on moving to the same or following cluster.
+
+
+R0.07 (April 01, 2009)
+  Merged Tiny-FatFs as a configuration option. (_FS_TINY)
+  Added long file name feature. (_USE_LFN)
+  Added multiple code page feature. (_CODE_PAGE)
+  Added re-entrancy for multitask operation. (_FS_REENTRANT)
+  Added auto cluster size selection to f_mkfs().
+  Added rewind option to f_readdir().
+  Changed result code of critical errors.
+  Renamed string functions to avoid name collision.
+
+
+R0.07a (April 14, 2009)
+  Septemberarated out OS dependent code on reentrant cfg.
+  Added multiple sector size feature.
+
+
+R0.07c (June 21, 2009)
+  Fixed f_unlink() can return FR_OK on error.
+  Fixed wrong cache control in f_lseek().
+  Added relative path feature.
+  Added f_chdir() and f_chdrive().
+  Added proper case conversion to extended character.
+
+
+R0.07e (November 03, 2009)
+  Septemberarated out configuration options from ff.h to ffconf.h.
+  Fixed f_unlink() fails to remove a sub-directory on _FS_RPATH.
+  Fixed name matching error on the 13 character boundary.
+  Added a configuration option, _LFN_UNICODE.
+  Changed f_readdir() to return the SFN with always upper case on non-LFN cfg.
+
+
+R0.08 (May 15, 2010)
+  Added a memory configuration option. (_USE_LFN = 3)
+  Added file lock feature. (_FS_SHARE)
+  Added fast seek feature. (_USE_FASTSEEK)
+  Changed some types on the API, XCHAR->TCHAR.
+  Changed .fname in the FILINFO structure on Unicode cfg.
+  String functions support UTF-8 encoding files on Unicode cfg.
+
+
+R0.08a (August 16, 2010)
+  Added f_getcwd(). (_FS_RPATH = 2)
+  Added sector erase feature. (_USE_ERASE)
+  Moved file lock semaphore table from fs object to the bss.
+  Fixed f_mkfs() creates wrong FAT32 volume.
+
+
+R0.08b (January 15, 2011)
+  Fast seek feature is also applied to f_read() and f_write().
+  f_lseek() reports required table size on creating CLMP.
+  Extended format syntax of f_printf().
+  Ignores duplicated directory separators in given path name.
+
+
+R0.09 (September 06, 2011)
+  f_mkfs() supports multiple partition to complete the multiple partition feature.
+  Added f_fdisk().
+
+
+R0.09a (August 27, 2012)
+  Changed f_open() and f_opendir() reject null object pointer to avoid crash.
+  Changed option name _FS_SHARE to _FS_LOCK.
+  Fixed assertion failure due to OS/2 EA on FAT12/16 volume.
+
+
+R0.09b (January 24, 2013)
+  Added f_setlabel() and f_getlabel().
+
+
+R0.10 (October 02, 2013)
+  Added selection of character encoding on the file. (_STRF_ENCODE)
+  Added f_closedir().
+  Added forced full FAT scan for f_getfree(). (_FS_NOFSINFO)
+  Added forced mount feature with changes of f_mount().
+  Improved behavior of volume auto detection.
+  Improved write throughput of f_puts() and f_printf().
+  Changed argument of f_chdrive(), f_mkfs(), disk_read() and disk_write().
+  Fixed f_write() can be truncated when the file size is close to 4GB.
+  Fixed f_open(), f_mkdir() and f_setlabel() can return incorrect error code.
+
+
+R0.10a (January 15, 2014)
+  Added arbitrary strings as drive number in the path name. (_STR_VOLUME_ID)
+  Added a configuration option of minimum sector size. (_MIN_SS)
+  2nd argument of f_rename() can have a drive number and it will be ignored.
+  Fixed f_mount() with forced mount fails when drive number is >= 1. (appeared at R0.10)
+  Fixed f_close() invalidates the file object without volume lock.
+  Fixed f_closedir() returns but the volume lock is left acquired. (appeared at R0.10)
+  Fixed creation of an entry with LFN fails on too many SFN collisions. (appeared at R0.07)
+
+
+R0.10b (May 19, 2014)
+  Fixed a hard error in the disk I/O layer can collapse the directory entry.
+  Fixed LFN entry is not deleted on delete/rename an object with lossy converted SFN. (appeared at R0.07)
+
+
+R0.10c (November 09, 2014)
+  Added a configuration option for the platforms without RTC. (_FS_NORTC)
+  Changed option name _USE_ERASE to _USE_TRIM.
+  Fixed volume label created by Mac OS X cannot be retrieved with f_getlabel(). (appeared at R0.09b)
+  Fixed a potential problem of FAT access that can appear on disk error.
+  Fixed null pointer dereference on attempting to delete the root direcotry. (appeared at R0.08)
+
+
+R0.11 (February 09, 2015)
+  Added f_findfirst(), f_findnext() and f_findclose(). (_USE_FIND)
+  Fixed f_unlink() does not remove cluster chain of the file. (appeared at R0.10c)
+  Fixed _FS_NORTC option does not work properly. (appeared at R0.10c)
diff --git a/crazyflie-firmware-src/src/lib/FatFS/integer.h b/crazyflie-firmware-src/src/lib/FatFS/integer.h
new file mode 100644
index 0000000000000000000000000000000000000000..4660ed6244fe2e625a1ebe4c5e26a27c2731c91e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/integer.h
@@ -0,0 +1,38 @@
+/*-------------------------------------------*/
+/* Integer type definitions for FatFs module */
+/*-------------------------------------------*/
+
+#ifndef _FF_INTEGER
+#define _FF_INTEGER
+
+#ifdef _WIN32	/* FatFs development platform */
+
+#include <windows.h>
+#include <tchar.h>
+typedef unsigned __int64 QWORD;
+
+
+#else			/* Embedded platform */
+
+/* These types MUST be 16-bit or 32-bit */
+typedef int				INT;
+typedef unsigned int	UINT;
+
+/* This type MUST be 8-bit */
+typedef unsigned char	BYTE;
+
+/* These types MUST be 16-bit */
+typedef short			SHORT;
+typedef unsigned short	WORD;
+typedef unsigned short	WCHAR;
+
+/* These types MUST be 32-bit */
+typedef long			LONG;
+typedef unsigned long	DWORD;
+
+/* This type MUST be 64-bit (Remove this for C89 compatibility) */
+typedef unsigned long long QWORD;
+
+#endif
+
+#endif
diff --git a/crazyflie-firmware-src/src/lib/FatFS/syscall.c b/crazyflie-firmware-src/src/lib/FatFS/syscall.c
new file mode 100644
index 0000000000000000000000000000000000000000..02d1306298ae9f85f885a758ffc65f2f812a0f5d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/syscall.c
@@ -0,0 +1,155 @@
+/*------------------------------------------------------------------------*/
+/* Sample code of OS dependent controls for FatFs                         */
+/* (C)ChaN, 2014                                                          */
+/*------------------------------------------------------------------------*/
+
+
+#include "ff.h"
+#include <stdint.h>
+
+#if _FS_REENTRANT
+/*------------------------------------------------------------------------*/
+/* Create a Synchronization Object                                        */
+/*------------------------------------------------------------------------*/
+/* This function is called in f_mount() function to create a new
+/  synchronization object, such as semaphore and mutex. When a 0 is returned,
+/  the f_mount() function fails with FR_INT_ERR.
+*/
+
+int ff_cre_syncobj (	/* 1:Function succeeded, 0:Could not create the sync object */
+	BYTE vol,			/* Corresponding volume (logical drive number) */
+	_SYNC_t *sobj		/* Pointer to return the created sync object */
+)
+{
+	int ret;
+
+
+	*sobj = CreateMutex(NULL, FALSE, NULL);		/* Win32 */
+	ret = (int)(*sobj != INVALID_HANDLE_VALUE);
+
+//	*sobj = SyncObjects[vol];			/* uITRON (give a static sync object) */
+//	ret = 1;							/* The initial value of the semaphore must be 1. */
+
+//	*sobj = OSMutexCreate(0, &err);		/* uC/OS-II */
+//	ret = (int)(err == OS_NO_ERR);
+
+//	*sobj = xSemaphoreCreateMutex();	/* FreeRTOS */
+//	ret = (int)(*sobj != NULL);
+
+	return ret;
+}
+
+
+
+/*------------------------------------------------------------------------*/
+/* Delete a Synchronization Object                                        */
+/*------------------------------------------------------------------------*/
+/* This function is called in f_mount() function to delete a synchronization
+/  object that created with ff_cre_syncobj() function. When a 0 is returned,
+/  the f_mount() function fails with FR_INT_ERR.
+*/
+
+int ff_del_syncobj (	/* 1:Function succeeded, 0:Could not delete due to any error */
+	_SYNC_t sobj		/* Sync object tied to the logical drive to be deleted */
+)
+{
+	int ret;
+
+
+	ret = CloseHandle(sobj);	/* Win32 */
+
+//	ret = 1;					/* uITRON (nothing to do) */
+
+//	OSMutexDel(sobj, OS_DEL_ALWAYS, &err);	/* uC/OS-II */
+//	ret = (int)(err == OS_NO_ERR);
+
+//  vSemaphoreDelete(sobj);		/* FreeRTOS */
+//	ret = 1;
+
+	return ret;
+}
+
+
+
+/*------------------------------------------------------------------------*/
+/* Request Grant to Access the Volume                                     */
+/*------------------------------------------------------------------------*/
+/* This function is called on entering file functions to lock the volume.
+/  When a 0 is returned, the file function fails with FR_TIMEOUT.
+*/
+
+int ff_req_grant (	/* 1:Got a grant to access the volume, 0:Could not get a grant */
+	_SYNC_t sobj	/* Sync object to wait */
+)
+{
+	int ret;
+
+	ret = (int)(WaitForSingleObject(sobj, _FS_TIMEOUT) == WAIT_OBJECT_0);	/* Win32 */
+
+//	ret = (int)(wai_sem(sobj) == E_OK);			/* uITRON */
+
+//	OSMutexPend(sobj, _FS_TIMEOUT, &err));		/* uC/OS-II */
+//	ret = (int)(err == OS_NO_ERR);
+
+//	ret = (int)(xSemaphoreTake(sobj, _FS_TIMEOUT) == pdTRUE);	/* FreeRTOS */
+
+	return ret;
+}
+
+
+
+/*------------------------------------------------------------------------*/
+/* Release Grant to Access the Volume                                     */
+/*------------------------------------------------------------------------*/
+/* This function is called on leaving file functions to unlock the volume.
+*/
+
+void ff_rel_grant (
+	_SYNC_t sobj	/* Sync object to be signaled */
+)
+{
+	ReleaseMutex(sobj);		/* Win32 */
+
+//	sig_sem(sobj);			/* uITRON */
+
+//	OSMutexPost(sobj);		/* uC/OS-II */
+
+//	xSemaphoreGive(sobj);	/* FreeRTOS */
+}
+
+#endif
+
+
+
+
+#if _USE_LFN == 3	/* LFN with a working buffer on the heap */
+/*------------------------------------------------------------------------*/
+/* Allocate a memory block                                                */
+/*------------------------------------------------------------------------*/
+/* If a NULL is returned, the file function fails with FR_NOT_ENOUGH_CORE.
+*/
+
+void* ff_memalloc (	/* Returns pointer to the allocated memory block */
+	UINT msize		/* Number of bytes to allocate */
+)
+{
+  extern void *pvPortMalloc( UINT xSize );
+
+	return pvPortMalloc(msize);	/* Allocate a new memory block with POSIX API */
+}
+
+
+/*------------------------------------------------------------------------*/
+/* Free a memory block                                                    */
+/*------------------------------------------------------------------------*/
+
+void ff_memfree (
+	void* mblock	/* Pointer to the memory block to free */
+)
+{
+  extern void vPortFree( void *pv );
+
+  vPortFree(mblock);	/* Discard the memory block with POSIX API */
+}
+
+#endif
diff --git a/crazyflie-firmware-src/src/lib/FatFS/unicode.c b/crazyflie-firmware-src/src/lib/FatFS/unicode.c
new file mode 100644
index 0000000000000000000000000000000000000000..135a2a6dabac9b166fb54469db371d0d3a06f736
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FatFS/unicode.c
@@ -0,0 +1,17 @@
+#include "ff.h"
+
+#if _USE_LFN != 0
+
+#if   _CODE_PAGE == 932	/* Japanese Shift_JIS */
+#include "cc932.c"
+#elif _CODE_PAGE == 936	/* Simplified Chinese GBK */
+#include "cc936.c"
+#elif _CODE_PAGE == 949	/* Korean */
+#include "cc949.c"
+#elif _CODE_PAGE == 950	/* Traditional Chinese Big5 */
+#include "cc950.c"
+#else					/* Single Byte Character-Set */
+#include "ccsbcs.c"
+#endif
+
+#endif
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/croutine.c b/crazyflie-firmware-src/src/lib/FreeRTOS/croutine.c
new file mode 100644
index 0000000000000000000000000000000000000000..4d6d4d7e25a81d87fb9ace7573b1eb9b0fdba38f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/croutine.c
@@ -0,0 +1,395 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "croutine.h"
+
+/* Remove the whole file is co-routines are not being used. */
+#if( configUSE_CO_ROUTINES != 0 )
+
+/*
+ * Some kernel aware debuggers require data to be viewed to be global, rather
+ * than file scope.
+ */
+#ifdef portREMOVE_STATIC_QUALIFIER
+	#define static
+#endif
+
+
+/* Lists for ready and blocked co-routines. --------------------*/
+static List_t pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ];	/*< Prioritised ready co-routines. */
+static List_t xDelayedCoRoutineList1;									/*< Delayed co-routines. */
+static List_t xDelayedCoRoutineList2;									/*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */
+static List_t * pxDelayedCoRoutineList;									/*< Points to the delayed co-routine list currently being used. */
+static List_t * pxOverflowDelayedCoRoutineList;							/*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */
+static List_t xPendingReadyCoRoutineList;								/*< Holds co-routines that have been readied by an external event.  They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */
+
+/* Other file private variables. --------------------------------*/
+CRCB_t * pxCurrentCoRoutine = NULL;
+static UBaseType_t uxTopCoRoutineReadyPriority = 0;
+static TickType_t xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0;
+
+/* The initial state of the co-routine when it is created. */
+#define corINITIAL_STATE	( 0 )
+
+/*
+ * Place the co-routine represented by pxCRCB into the appropriate ready queue
+ * for the priority.  It is inserted at the end of the list.
+ *
+ * This macro accesses the co-routine ready lists and therefore must not be
+ * used from within an ISR.
+ */
+#define prvAddCoRoutineToReadyQueue( pxCRCB )																		\
+{																													\
+	if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority )															\
+	{																												\
+		uxTopCoRoutineReadyPriority = pxCRCB->uxPriority;															\
+	}																												\
+	vListInsertEnd( ( List_t * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) );	\
+}
+
+/*
+ * Utility to ready all the lists used by the scheduler.  This is called
+ * automatically upon the creation of the first co-routine.
+ */
+static void prvInitialiseCoRoutineLists( void );
+
+/*
+ * Co-routines that are readied by an interrupt cannot be placed directly into
+ * the ready lists (there is no mutual exclusion).  Instead they are placed in
+ * in the pending ready list in order that they can later be moved to the ready
+ * list by the co-routine scheduler.
+ */
+static void prvCheckPendingReadyList( void );
+
+/*
+ * Macro that looks at the list of co-routines that are currently delayed to
+ * see if any require waking.
+ *
+ * Co-routines are stored in the queue in the order of their wake time -
+ * meaning once one co-routine has been found whose timer has not expired
+ * we need not look any further down the list.
+ */
+static void prvCheckDelayedList( void );
+
+/*-----------------------------------------------------------*/
+
+BaseType_t xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, UBaseType_t uxPriority, UBaseType_t uxIndex )
+{
+BaseType_t xReturn;
+CRCB_t *pxCoRoutine;
+
+	/* Allocate the memory that will store the co-routine control block. */
+	pxCoRoutine = ( CRCB_t * ) pvPortMalloc( sizeof( CRCB_t ) );
+	if( pxCoRoutine )
+	{
+		/* If pxCurrentCoRoutine is NULL then this is the first co-routine to
+		be created and the co-routine data structures need initialising. */
+		if( pxCurrentCoRoutine == NULL )
+		{
+			pxCurrentCoRoutine = pxCoRoutine;
+			prvInitialiseCoRoutineLists();
+		}
+
+		/* Check the priority is within limits. */
+		if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES )
+		{
+			uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1;
+		}
+
+		/* Fill out the co-routine control block from the function parameters. */
+		pxCoRoutine->uxState = corINITIAL_STATE;
+		pxCoRoutine->uxPriority = uxPriority;
+		pxCoRoutine->uxIndex = uxIndex;
+		pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode;
+
+		/* Initialise all the other co-routine control block parameters. */
+		vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) );
+		vListInitialiseItem( &( pxCoRoutine->xEventListItem ) );
+
+		/* Set the co-routine control block as a link back from the ListItem_t.
+		This is so we can get back to the containing CRCB from a generic item
+		in a list. */
+		listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine );
+		listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine );
+
+		/* Event lists are always in priority order. */
+		listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), ( ( TickType_t ) configMAX_CO_ROUTINE_PRIORITIES - ( TickType_t ) uxPriority ) );
+
+		/* Now the co-routine has been initialised it can be added to the ready
+		list at the correct priority. */
+		prvAddCoRoutineToReadyQueue( pxCoRoutine );
+
+		xReturn = pdPASS;
+	}
+	else
+	{
+		xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY;
+	}
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vCoRoutineAddToDelayedList( TickType_t xTicksToDelay, List_t *pxEventList )
+{
+TickType_t xTimeToWake;
+
+	/* Calculate the time to wake - this may overflow but this is
+	not a problem. */
+	xTimeToWake = xCoRoutineTickCount + xTicksToDelay;
+
+	/* We must remove ourselves from the ready list before adding
+	ourselves to the blocked list as the same list item is used for
+	both lists. */
+	( void ) uxListRemove( ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) );
+
+	/* The list item will be inserted in wake time order. */
+	listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake );
+
+	if( xTimeToWake < xCoRoutineTickCount )
+	{
+		/* Wake time has overflowed.  Place this item in the
+		overflow list. */
+		vListInsert( ( List_t * ) pxOverflowDelayedCoRoutineList, ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) );
+	}
+	else
+	{
+		/* The wake time has not overflowed, so we can use the
+		current block list. */
+		vListInsert( ( List_t * ) pxDelayedCoRoutineList, ( ListItem_t * ) &( pxCurrentCoRoutine->xGenericListItem ) );
+	}
+
+	if( pxEventList )
+	{
+		/* Also add the co-routine to an event list.  If this is done then the
+		function must be called with interrupts disabled. */
+		vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) );
+	}
+}
+/*-----------------------------------------------------------*/
+
+static void prvCheckPendingReadyList( void )
+{
+	/* Are there any co-routines waiting to get moved to the ready list?  These
+	are co-routines that have been readied by an ISR.  The ISR cannot access
+	the	ready lists itself. */
+	while( listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) == pdFALSE )
+	{
+		CRCB_t *pxUnblockedCRCB;
+
+		/* The pending ready list can be accessed by an ISR. */
+		portDISABLE_INTERRUPTS();
+		{
+			pxUnblockedCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) );
+			( void ) uxListRemove( &( pxUnblockedCRCB->xEventListItem ) );
+		}
+		portENABLE_INTERRUPTS();
+
+		( void ) uxListRemove( &( pxUnblockedCRCB->xGenericListItem ) );
+		prvAddCoRoutineToReadyQueue( pxUnblockedCRCB );
+	}
+}
+/*-----------------------------------------------------------*/
+
+static void prvCheckDelayedList( void )
+{
+CRCB_t *pxCRCB;
+
+	xPassedTicks = xTaskGetTickCount() - xLastTickCount;
+	while( xPassedTicks )
+	{
+		xCoRoutineTickCount++;
+		xPassedTicks--;
+
+		/* If the tick count has overflowed we need to swap the ready lists. */
+		if( xCoRoutineTickCount == 0 )
+		{
+			List_t * pxTemp;
+
+			/* Tick count has overflowed so we need to swap the delay lists.  If there are
+			any items in pxDelayedCoRoutineList here then there is an error! */
+			pxTemp = pxDelayedCoRoutineList;
+			pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList;
+			pxOverflowDelayedCoRoutineList = pxTemp;
+		}
+
+		/* See if this tick has made a timeout expire. */
+		while( listLIST_IS_EMPTY( pxDelayedCoRoutineList ) == pdFALSE )
+		{
+			pxCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList );
+
+			if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) )
+			{
+				/* Timeout not yet expired. */
+				break;
+			}
+
+			portDISABLE_INTERRUPTS();
+			{
+				/* The event could have occurred just before this critical
+				section.  If this is the case then the generic list item will
+				have been moved to the pending ready list and the following
+				line is still valid.  Also the pvContainer parameter will have
+				been set to NULL so the following lines are also valid. */
+				( void ) uxListRemove( &( pxCRCB->xGenericListItem ) );
+
+				/* Is the co-routine waiting on an event also? */
+				if( pxCRCB->xEventListItem.pvContainer )
+				{
+					( void ) uxListRemove( &( pxCRCB->xEventListItem ) );
+				}
+			}
+			portENABLE_INTERRUPTS();
+
+			prvAddCoRoutineToReadyQueue( pxCRCB );
+		}
+	}
+
+	xLastTickCount = xCoRoutineTickCount;
+}
+/*-----------------------------------------------------------*/
+
+void vCoRoutineSchedule( void )
+{
+	/* See if any co-routines readied by events need moving to the ready lists. */
+	prvCheckPendingReadyList();
+
+	/* See if any delayed co-routines have timed out. */
+	prvCheckDelayedList();
+
+	/* Find the highest priority queue that contains ready co-routines. */
+	while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) )
+	{
+		if( uxTopCoRoutineReadyPriority == 0 )
+		{
+			/* No more co-routines to check. */
+			return;
+		}
+		--uxTopCoRoutineReadyPriority;
+	}
+
+	/* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines
+	 of the	same priority get an equal share of the processor time. */
+	listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) );
+
+	/* Call the co-routine. */
+	( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex );
+
+	return;
+}
+/*-----------------------------------------------------------*/
+
+static void prvInitialiseCoRoutineLists( void )
+{
+UBaseType_t uxPriority;
+
+	for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ )
+	{
+		vListInitialise( ( List_t * ) &( pxReadyCoRoutineLists[ uxPriority ] ) );
+	}
+
+	vListInitialise( ( List_t * ) &xDelayedCoRoutineList1 );
+	vListInitialise( ( List_t * ) &xDelayedCoRoutineList2 );
+	vListInitialise( ( List_t * ) &xPendingReadyCoRoutineList );
+
+	/* Start with pxDelayedCoRoutineList using list1 and the
+	pxOverflowDelayedCoRoutineList using list2. */
+	pxDelayedCoRoutineList = &xDelayedCoRoutineList1;
+	pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xCoRoutineRemoveFromEventList( const List_t *pxEventList )
+{
+CRCB_t *pxUnblockedCRCB;
+BaseType_t xReturn;
+
+	/* This function is called from within an interrupt.  It can only access
+	event lists and the pending ready list.  This function assumes that a
+	check has already been made to ensure pxEventList is not empty. */
+	pxUnblockedCRCB = ( CRCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList );
+	( void ) uxListRemove( &( pxUnblockedCRCB->xEventListItem ) );
+	vListInsertEnd( ( List_t * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) );
+
+	if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority )
+	{
+		xReturn = pdTRUE;
+	}
+	else
+	{
+		xReturn = pdFALSE;
+	}
+
+	return xReturn;
+}
+
+#endif /* configUSE_CO_ROUTINES == 0 */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/event_groups.c b/crazyflie-firmware-src/src/lib/FreeRTOS/event_groups.c
new file mode 100644
index 0000000000000000000000000000000000000000..625548c56c78b594a09f5c2899b9a328edbca57c
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/event_groups.c
@@ -0,0 +1,683 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/* Standard includes. */
+#include <stdlib.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+/* FreeRTOS includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "timers.h"
+#include "event_groups.h"
+
+/* Lint e961 and e750 are suppressed as a MISRA exception justified because the
+MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined for the
+header files above, but not in this file, in order to generate the correct
+privileged Vs unprivileged linkage and placement. */
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750. */
+
+#if ( INCLUDE_xEventGroupSetBitFromISR == 1 ) && ( configUSE_TIMERS == 0 )
+	#error configUSE_TIMERS must be set to 1 to make the xEventGroupSetBitFromISR() function available.
+#endif
+
+#if ( INCLUDE_xEventGroupSetBitFromISR == 1 ) && ( INCLUDE_xTimerPendFunctionCall == 0 )
+	#error INCLUDE_xTimerPendFunctionCall must also be set to one to make the xEventGroupSetBitFromISR() function available.
+#endif
+
+/* The following bit fields convey control information in a task's event list
+item value.  It is important they don't clash with the
+taskEVENT_LIST_ITEM_VALUE_IN_USE definition. */
+#if configUSE_16_BIT_TICKS == 1
+	#define eventCLEAR_EVENTS_ON_EXIT_BIT	0x0100U
+	#define eventUNBLOCKED_DUE_TO_BIT_SET	0x0200U
+	#define eventWAIT_FOR_ALL_BITS			0x0400U
+	#define eventEVENT_BITS_CONTROL_BYTES	0xff00U
+#else
+	#define eventCLEAR_EVENTS_ON_EXIT_BIT	0x01000000UL
+	#define eventUNBLOCKED_DUE_TO_BIT_SET	0x02000000UL
+	#define eventWAIT_FOR_ALL_BITS			0x04000000UL
+	#define eventEVENT_BITS_CONTROL_BYTES	0xff000000UL
+#endif
+
+typedef struct xEventGroupDefinition
+{
+	EventBits_t uxEventBits;
+	List_t xTasksWaitingForBits;		/*< List of tasks waiting for a bit to be set. */
+
+	#if( configUSE_TRACE_FACILITY == 1 )
+		UBaseType_t uxEventGroupNumber;
+	#endif
+
+} EventGroup_t;
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Test the bits set in uxCurrentEventBits to see if the wait condition is met.
+ * The wait condition is defined by xWaitForAllBits.  If xWaitForAllBits is
+ * pdTRUE then the wait condition is met if all the bits set in uxBitsToWaitFor
+ * are also set in uxCurrentEventBits.  If xWaitForAllBits is pdFALSE then the
+ * wait condition is met if any of the bits set in uxBitsToWait for are also set
+ * in uxCurrentEventBits.
+ */
+static BaseType_t prvTestWaitCondition( const EventBits_t uxCurrentEventBits, const EventBits_t uxBitsToWaitFor, const BaseType_t xWaitForAllBits );
+
+/*-----------------------------------------------------------*/
+
+EventGroupHandle_t xEventGroupCreate( void )
+{
+EventGroup_t *pxEventBits;
+
+	pxEventBits = ( EventGroup_t * ) pvPortMalloc( sizeof( EventGroup_t ) );
+	if( pxEventBits != NULL )
+	{
+		pxEventBits->uxEventBits = 0;
+		vListInitialise( &( pxEventBits->xTasksWaitingForBits ) );
+		traceEVENT_GROUP_CREATE( pxEventBits );
+	}
+	else
+	{
+		traceEVENT_GROUP_CREATE_FAILED();
+	}
+
+	return ( EventGroupHandle_t ) pxEventBits;
+}
+/*-----------------------------------------------------------*/
+
+EventBits_t xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait )
+{
+EventBits_t uxOriginalBitValue, uxReturn;
+EventGroup_t *pxEventBits = ( EventGroup_t * ) xEventGroup;
+BaseType_t xAlreadyYielded;
+BaseType_t xTimeoutOccurred = pdFALSE;
+
+	configASSERT( ( uxBitsToWaitFor & eventEVENT_BITS_CONTROL_BYTES ) == 0 );
+	configASSERT( uxBitsToWaitFor != 0 );
+	#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) )
+	{
+		configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) );
+	}
+	#endif
+
+	vTaskSuspendAll();
+	{
+		uxOriginalBitValue = pxEventBits->uxEventBits;
+
+		( void ) xEventGroupSetBits( xEventGroup, uxBitsToSet );
+
+		if( ( ( uxOriginalBitValue | uxBitsToSet ) & uxBitsToWaitFor ) == uxBitsToWaitFor )
+		{
+			/* All the rendezvous bits are now set - no need to block. */
+			uxReturn = ( uxOriginalBitValue | uxBitsToSet );
+
+			/* Rendezvous always clear the bits.  They will have been cleared
+			already unless this is the only task in the rendezvous. */
+			pxEventBits->uxEventBits &= ~uxBitsToWaitFor;
+
+			xTicksToWait = 0;
+		}
+		else
+		{
+			if( xTicksToWait != ( TickType_t ) 0 )
+			{
+				traceEVENT_GROUP_SYNC_BLOCK( xEventGroup, uxBitsToSet, uxBitsToWaitFor );
+
+				/* Store the bits that the calling task is waiting for in the
+				task's event list item so the kernel knows when a match is
+				found.  Then enter the blocked state. */
+				vTaskPlaceOnUnorderedEventList( &( pxEventBits->xTasksWaitingForBits ), ( uxBitsToWaitFor | eventCLEAR_EVENTS_ON_EXIT_BIT | eventWAIT_FOR_ALL_BITS ), xTicksToWait );
+
+				/* This assignment is obsolete as uxReturn will get set after
+				the task unblocks, but some compilers mistakenly generate a
+				warning about uxReturn being returned without being set if the
+				assignment is omitted. */
+				uxReturn = 0;
+			}
+			else
+			{
+				/* The rendezvous bits were not set, but no block time was
+				specified - just return the current event bit value. */
+				uxReturn = pxEventBits->uxEventBits;
+			}
+		}
+	}
+	xAlreadyYielded = xTaskResumeAll();
+
+	if( xTicksToWait != ( TickType_t ) 0 )
+	{
+		if( xAlreadyYielded == pdFALSE )
+		{
+			portYIELD_WITHIN_API();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		/* The task blocked to wait for its required bits to be set - at this
+		point either the required bits were set or the block time expired.  If
+		the required bits were set they will have been stored in the task's
+		event list item, and they should now be retrieved then cleared. */
+		uxReturn = uxTaskResetEventItemValue();
+
+		if( ( uxReturn & eventUNBLOCKED_DUE_TO_BIT_SET ) == ( EventBits_t ) 0 )
+		{
+			/* The task timed out, just return the current event bit value. */
+			taskENTER_CRITICAL();
+			{
+				uxReturn = pxEventBits->uxEventBits;
+
+				/* Although the task got here because it timed out before the
+				bits it was waiting for were set, it is possible that since it
+				unblocked another task has set the bits.  If this is the case
+				then it needs to clear the bits before exiting. */
+				if( ( uxReturn & uxBitsToWaitFor ) == uxBitsToWaitFor )
+				{
+					pxEventBits->uxEventBits &= ~uxBitsToWaitFor;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			taskEXIT_CRITICAL();
+
+			xTimeoutOccurred = pdTRUE;
+		}
+		else
+		{
+			/* The task unblocked because the bits were set. */
+		}
+
+		/* Control bits might be set as the task had blocked should not be
+		returned. */
+		uxReturn &= ~eventEVENT_BITS_CONTROL_BYTES;
+	}
+
+	traceEVENT_GROUP_SYNC_END( xEventGroup, uxBitsToSet, uxBitsToWaitFor, xTimeoutOccurred );
+
+	return uxReturn;
+}
+/*-----------------------------------------------------------*/
+
+EventBits_t xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait )
+{
+EventGroup_t *pxEventBits = ( EventGroup_t * ) xEventGroup;
+EventBits_t uxReturn, uxControlBits = 0;
+BaseType_t xWaitConditionMet, xAlreadyYielded;
+BaseType_t xTimeoutOccurred = pdFALSE;
+
+	/* Check the user is not attempting to wait on the bits used by the kernel
+	itself, and that at least one bit is being requested. */
+	configASSERT( xEventGroup );
+	configASSERT( ( uxBitsToWaitFor & eventEVENT_BITS_CONTROL_BYTES ) == 0 );
+	configASSERT( uxBitsToWaitFor != 0 );
+	#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) )
+	{
+		configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) );
+	}
+	#endif
+
+	vTaskSuspendAll();
+	{
+		const EventBits_t uxCurrentEventBits = pxEventBits->uxEventBits;
+
+		/* Check to see if the wait condition is already met or not. */
+		xWaitConditionMet = prvTestWaitCondition( uxCurrentEventBits, uxBitsToWaitFor, xWaitForAllBits );
+
+		if( xWaitConditionMet != pdFALSE )
+		{
+			/* The wait condition has already been met so there is no need to
+			block. */
+			uxReturn = uxCurrentEventBits;
+			xTicksToWait = ( TickType_t ) 0;
+
+			/* Clear the wait bits if requested to do so. */
+			if( xClearOnExit != pdFALSE )
+			{
+				pxEventBits->uxEventBits &= ~uxBitsToWaitFor;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else if( xTicksToWait == ( TickType_t ) 0 )
+		{
+			/* The wait condition has not been met, but no block time was
+			specified, so just return the current value. */
+			uxReturn = uxCurrentEventBits;
+		}
+		else
+		{
+			/* The task is going to block to wait for its required bits to be
+			set.  uxControlBits are used to remember the specified behaviour of
+			this call to xEventGroupWaitBits() - for use when the event bits
+			unblock the task. */
+			if( xClearOnExit != pdFALSE )
+			{
+				uxControlBits |= eventCLEAR_EVENTS_ON_EXIT_BIT;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			if( xWaitForAllBits != pdFALSE )
+			{
+				uxControlBits |= eventWAIT_FOR_ALL_BITS;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			/* Store the bits that the calling task is waiting for in the
+			task's event list item so the kernel knows when a match is
+			found.  Then enter the blocked state. */
+			vTaskPlaceOnUnorderedEventList( &( pxEventBits->xTasksWaitingForBits ), ( uxBitsToWaitFor | uxControlBits ), xTicksToWait );
+
+			/* This is obsolete as it will get set after the task unblocks, but
+			some compilers mistakenly generate a warning about the variable
+			being returned without being set if it is not done. */
+			uxReturn = 0;
+
+			traceEVENT_GROUP_WAIT_BITS_BLOCK( xEventGroup, uxBitsToWaitFor );
+		}
+	}
+	xAlreadyYielded = xTaskResumeAll();
+
+	if( xTicksToWait != ( TickType_t ) 0 )
+	{
+		if( xAlreadyYielded == pdFALSE )
+		{
+			portYIELD_WITHIN_API();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		/* The task blocked to wait for its required bits to be set - at this
+		point either the required bits were set or the block time expired.  If
+		the required bits were set they will have been stored in the task's
+		event list item, and they should now be retrieved then cleared. */
+		uxReturn = uxTaskResetEventItemValue();
+
+		if( ( uxReturn & eventUNBLOCKED_DUE_TO_BIT_SET ) == ( EventBits_t ) 0 )
+		{
+			taskENTER_CRITICAL();
+			{
+				/* The task timed out, just return the current event bit value. */
+				uxReturn = pxEventBits->uxEventBits;
+
+				/* It is possible that the event bits were updated between this
+				task leaving the Blocked state and running again. */
+				if( prvTestWaitCondition( uxReturn, uxBitsToWaitFor, xWaitForAllBits ) != pdFALSE )
+				{
+					if( xClearOnExit != pdFALSE )
+					{
+						pxEventBits->uxEventBits &= ~uxBitsToWaitFor;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			taskEXIT_CRITICAL();
+
+			/* Prevent compiler warnings when trace macros are not used. */
+			xTimeoutOccurred = pdFALSE;
+		}
+		else
+		{
+			/* The task unblocked because the bits were set. */
+		}
+
+		/* The task blocked so control bits may have been set. */
+		uxReturn &= ~eventEVENT_BITS_CONTROL_BYTES;
+	}
+	traceEVENT_GROUP_WAIT_BITS_END( xEventGroup, uxBitsToWaitFor, xTimeoutOccurred );
+
+	return uxReturn;
+}
+/*-----------------------------------------------------------*/
+
+EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear )
+{
+EventGroup_t *pxEventBits = ( EventGroup_t * ) xEventGroup;
+EventBits_t uxReturn;
+
+	/* Check the user is not attempting to clear the bits used by the kernel
+	itself. */
+	configASSERT( xEventGroup );
+	configASSERT( ( uxBitsToClear & eventEVENT_BITS_CONTROL_BYTES ) == 0 );
+
+	taskENTER_CRITICAL();
+	{
+		traceEVENT_GROUP_CLEAR_BITS( xEventGroup, uxBitsToClear );
+
+		/* The value returned is the event group value prior to the bits being
+		cleared. */
+		uxReturn = pxEventBits->uxEventBits;
+
+		/* Clear the bits. */
+		pxEventBits->uxEventBits &= ~uxBitsToClear;
+	}
+	taskEXIT_CRITICAL();
+
+	return uxReturn;
+}
+/*-----------------------------------------------------------*/
+
+#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 1 ) )
+
+	BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear )
+	{
+		BaseType_t xReturn;
+
+		traceEVENT_GROUP_CLEAR_BITS_FROM_ISR( xEventGroup, uxBitsToClear );
+		xReturn = xTimerPendFunctionCallFromISR( vEventGroupClearBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToClear, NULL );
+
+		return xReturn;
+	}
+
+#endif
+/*-----------------------------------------------------------*/
+
+EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup )
+{
+UBaseType_t uxSavedInterruptStatus;
+EventGroup_t *pxEventBits = ( EventGroup_t * ) xEventGroup;
+EventBits_t uxReturn;
+
+	uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		uxReturn = pxEventBits->uxEventBits;
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+	return uxReturn;
+}
+/*-----------------------------------------------------------*/
+
+EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet )
+{
+ListItem_t *pxListItem, *pxNext;
+ListItem_t const *pxListEnd;
+List_t *pxList;
+EventBits_t uxBitsToClear = 0, uxBitsWaitedFor, uxControlBits;
+EventGroup_t *pxEventBits = ( EventGroup_t * ) xEventGroup;
+BaseType_t xMatchFound = pdFALSE;
+
+	/* Check the user is not attempting to set the bits used by the kernel
+	itself. */
+	configASSERT( xEventGroup );
+	configASSERT( ( uxBitsToSet & eventEVENT_BITS_CONTROL_BYTES ) == 0 );
+
+	pxList = &( pxEventBits->xTasksWaitingForBits );
+	pxListEnd = listGET_END_MARKER( pxList ); /*lint !e826 !e740 The mini list structure is used as the list end to save RAM.  This is checked and valid. */
+	vTaskSuspendAll();
+	{
+		traceEVENT_GROUP_SET_BITS( xEventGroup, uxBitsToSet );
+
+		pxListItem = listGET_HEAD_ENTRY( pxList );
+
+		/* Set the bits. */
+		pxEventBits->uxEventBits |= uxBitsToSet;
+
+		/* See if the new bit value should unblock any tasks. */
+		while( pxListItem != pxListEnd )
+		{
+			pxNext = listGET_NEXT( pxListItem );
+			uxBitsWaitedFor = listGET_LIST_ITEM_VALUE( pxListItem );
+			xMatchFound = pdFALSE;
+
+			/* Split the bits waited for from the control bits. */
+			uxControlBits = uxBitsWaitedFor & eventEVENT_BITS_CONTROL_BYTES;
+			uxBitsWaitedFor &= ~eventEVENT_BITS_CONTROL_BYTES;
+
+			if( ( uxControlBits & eventWAIT_FOR_ALL_BITS ) == ( EventBits_t ) 0 )
+			{
+				/* Just looking for single bit being set. */
+				if( ( uxBitsWaitedFor & pxEventBits->uxEventBits ) != ( EventBits_t ) 0 )
+				{
+					xMatchFound = pdTRUE;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else if( ( uxBitsWaitedFor & pxEventBits->uxEventBits ) == uxBitsWaitedFor )
+			{
+				/* All bits are set. */
+				xMatchFound = pdTRUE;
+			}
+			else
+			{
+				/* Need all bits to be set, but not all the bits were set. */
+			}
+
+			if( xMatchFound != pdFALSE )
+			{
+				/* The bits match.  Should the bits be cleared on exit? */
+				if( ( uxControlBits & eventCLEAR_EVENTS_ON_EXIT_BIT ) != ( EventBits_t ) 0 )
+				{
+					uxBitsToClear |= uxBitsWaitedFor;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				/* Store the actual event flag value in the task's event list
+				item before removing the task from the event list.  The
+				eventUNBLOCKED_DUE_TO_BIT_SET bit is set so the task knows
+				that is was unblocked due to its required bits matching, rather
+				than because it timed out. */
+				( void ) xTaskRemoveFromUnorderedEventList( pxListItem, pxEventBits->uxEventBits | eventUNBLOCKED_DUE_TO_BIT_SET );
+			}
+
+			/* Move onto the next list item.  Note pxListItem->pxNext is not
+			used here as the list item may have been removed from the event list
+			and inserted into the ready/pending reading list. */
+			pxListItem = pxNext;
+		}
+
+		/* Clear any bits that matched when the eventCLEAR_EVENTS_ON_EXIT_BIT
+		bit was set in the control word. */
+		pxEventBits->uxEventBits &= ~uxBitsToClear;
+	}
+	( void ) xTaskResumeAll();
+
+	return pxEventBits->uxEventBits;
+}
+/*-----------------------------------------------------------*/
+
+void vEventGroupDelete( EventGroupHandle_t xEventGroup )
+{
+EventGroup_t *pxEventBits = ( EventGroup_t * ) xEventGroup;
+const List_t *pxTasksWaitingForBits = &( pxEventBits->xTasksWaitingForBits );
+
+	vTaskSuspendAll();
+	{
+		traceEVENT_GROUP_DELETE( xEventGroup );
+
+		while( listCURRENT_LIST_LENGTH( pxTasksWaitingForBits ) > ( UBaseType_t ) 0 )
+		{
+			/* Unblock the task, returning 0 as the event list is being deleted
+			and	cannot therefore have any bits set. */
+			configASSERT( pxTasksWaitingForBits->xListEnd.pxNext != ( ListItem_t * ) &( pxTasksWaitingForBits->xListEnd ) );
+			( void ) xTaskRemoveFromUnorderedEventList( pxTasksWaitingForBits->xListEnd.pxNext, eventUNBLOCKED_DUE_TO_BIT_SET );
+		}
+
+		vPortFree( pxEventBits );
+	}
+	( void ) xTaskResumeAll();
+}
+/*-----------------------------------------------------------*/
+
+/* For internal use only - execute a 'set bits' command that was pended from
+an interrupt. */
+void vEventGroupSetBitsCallback( void *pvEventGroup, const uint32_t ulBitsToSet )
+{
+	( void ) xEventGroupSetBits( pvEventGroup, ( EventBits_t ) ulBitsToSet );
+}
+/*-----------------------------------------------------------*/
+
+/* For internal use only - execute a 'clear bits' command that was pended from
+an interrupt. */
+void vEventGroupClearBitsCallback( void *pvEventGroup, const uint32_t ulBitsToClear )
+{
+	( void ) xEventGroupClearBits( pvEventGroup, ( EventBits_t ) ulBitsToClear );
+}
+/*-----------------------------------------------------------*/
+
+static BaseType_t prvTestWaitCondition( const EventBits_t uxCurrentEventBits, const EventBits_t uxBitsToWaitFor, const BaseType_t xWaitForAllBits )
+{
+BaseType_t xWaitConditionMet = pdFALSE;
+
+	if( xWaitForAllBits == pdFALSE )
+	{
+		/* Task only has to wait for one bit within uxBitsToWaitFor to be
+		set.  Is one already set? */
+		if( ( uxCurrentEventBits & uxBitsToWaitFor ) != ( EventBits_t ) 0 )
+		{
+			xWaitConditionMet = pdTRUE;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	else
+	{
+		/* Task has to wait for all the bits in uxBitsToWaitFor to be set.
+		Are they set already? */
+		if( ( uxCurrentEventBits & uxBitsToWaitFor ) == uxBitsToWaitFor )
+		{
+			xWaitConditionMet = pdTRUE;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+	return xWaitConditionMet;
+}
+/*-----------------------------------------------------------*/
+
+#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 1 ) )
+
+	BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken )
+	{
+	BaseType_t xReturn;
+
+		traceEVENT_GROUP_SET_BITS_FROM_ISR( xEventGroup, uxBitsToSet );
+		xReturn = xTimerPendFunctionCallFromISR( vEventGroupSetBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToSet, pxHigherPriorityTaskWoken );
+
+		return xReturn;
+	}
+
+#endif
+/*-----------------------------------------------------------*/
+
+#if (configUSE_TRACE_FACILITY == 1)
+
+	UBaseType_t uxEventGroupGetNumber( void* xEventGroup )
+	{
+	UBaseType_t xReturn;
+	EventGroup_t *pxEventBits = ( EventGroup_t * ) xEventGroup;
+
+		if( xEventGroup == NULL )
+		{
+			xReturn = 0;
+		}
+		else
+		{
+			xReturn = pxEventBits->uxEventGroupNumber;
+		}
+
+		return xReturn;
+	}
+
+#endif
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/FreeRTOS.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/FreeRTOS.h
new file mode 100644
index 0000000000000000000000000000000000000000..7d34ec63bb51796ff02f130e26c23ccd0f291e3d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/FreeRTOS.h
@@ -0,0 +1,835 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef INC_FREERTOS_H
+#define INC_FREERTOS_H
+
+/*
+ * Include the generic headers required for the FreeRTOS port being used.
+ */
+#include <stddef.h>
+
+/*
+ * If stdint.h cannot be located then:
+ *   + If using GCC ensure the -nostdint options is *not* being used.
+ *   + Ensure the project's include path includes the directory in which your
+ *     compiler stores stdint.h.
+ *   + Set any compiler options necessary for it to support C99, as technically
+ *     stdint.h is only mandatory with C99 (FreeRTOS does not require C99 in any
+ *     other way).
+ *   + The FreeRTOS download includes a simple stdint.h definition that can be
+ *     used in cases where none is provided by the compiler.  The files only
+ *     contains the typedefs required to build FreeRTOS.  Read the instructions
+ *     in FreeRTOS/source/stdint.readme for more information.
+ */
+#include <stdint.h> /* READ COMMENT ABOVE. */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Application specific configuration options. */
+#include "FreeRTOSConfig.h"
+
+/* Basic FreeRTOS definitions. */
+#include "projdefs.h"
+
+/* Definitions specific to the port being used. */
+#include "portable.h"
+
+/*
+ * Check all the required application specific macros have been defined.
+ * These macros are application specific and (as downloaded) are defined
+ * within FreeRTOSConfig.h.
+ */
+
+#ifndef configMINIMAL_STACK_SIZE
+	#error Missing definition:  configMINIMAL_STACK_SIZE must be defined in FreeRTOSConfig.h.  configMINIMAL_STACK_SIZE defines the size (in words) of the stack allocated to the idle task.  Refer to the demo project provided for your port for a suitable value.
+#endif
+
+#ifndef configMAX_PRIORITIES
+	#error Missing definition:  configMAX_PRIORITIES must be defined in FreeRTOSConfig.h.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef configUSE_PREEMPTION
+	#error Missing definition:  configUSE_PREEMPTION must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef configUSE_IDLE_HOOK
+	#error Missing definition:  configUSE_IDLE_HOOK must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef configUSE_TICK_HOOK
+	#error Missing definition:  configUSE_TICK_HOOK must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef INCLUDE_vTaskPrioritySet
+	#error Missing definition:  INCLUDE_vTaskPrioritySet must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef INCLUDE_uxTaskPriorityGet
+	#error Missing definition:  INCLUDE_uxTaskPriorityGet must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef INCLUDE_vTaskDelete
+	#error Missing definition:  INCLUDE_vTaskDelete must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef INCLUDE_vTaskSuspend
+	#error Missing definition:  INCLUDE_vTaskSuspend must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef INCLUDE_vTaskDelayUntil
+	#error Missing definition:  INCLUDE_vTaskDelayUntil must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef INCLUDE_vTaskDelay
+	#error Missing definition:  INCLUDE_vTaskDelay must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef configUSE_16_BIT_TICKS
+	#error Missing definition:  configUSE_16_BIT_TICKS must be defined in FreeRTOSConfig.h as either 1 or 0.  See the Configuration section of the FreeRTOS API documentation for details.
+#endif
+
+#ifndef configMAX_PRIORITIES
+	#error configMAX_PRIORITIES must be defined to be greater than or equal to 1.
+#endif
+
+#ifndef configUSE_CO_ROUTINES
+	#define configUSE_CO_ROUTINES 0
+#endif
+
+#if configUSE_CO_ROUTINES != 0
+	#ifndef configMAX_CO_ROUTINE_PRIORITIES
+		#error configMAX_CO_ROUTINE_PRIORITIES must be greater than or equal to 1.
+	#endif
+#endif
+
+#ifndef INCLUDE_xTaskGetIdleTaskHandle
+	#define INCLUDE_xTaskGetIdleTaskHandle 0
+#endif
+
+#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle
+	#define INCLUDE_xTimerGetTimerDaemonTaskHandle 0
+#endif
+
+#ifndef INCLUDE_xQueueGetMutexHolder
+	#define INCLUDE_xQueueGetMutexHolder 0
+#endif
+
+#ifndef INCLUDE_xSemaphoreGetMutexHolder
+	#define INCLUDE_xSemaphoreGetMutexHolder INCLUDE_xQueueGetMutexHolder
+#endif
+
+#ifndef INCLUDE_pcTaskGetTaskName
+	#define INCLUDE_pcTaskGetTaskName 0
+#endif
+
+#ifndef configUSE_APPLICATION_TASK_TAG
+	#define configUSE_APPLICATION_TASK_TAG 0
+#endif
+
+#ifndef configNUM_THREAD_LOCAL_STORAGE_POINTERS
+	#define configNUM_THREAD_LOCAL_STORAGE_POINTERS 0
+#endif
+
+#ifndef INCLUDE_uxTaskGetStackHighWaterMark
+	#define INCLUDE_uxTaskGetStackHighWaterMark 0
+#endif
+
+#ifndef INCLUDE_eTaskGetState
+	#define INCLUDE_eTaskGetState 0
+#endif
+
+#ifndef configUSE_RECURSIVE_MUTEXES
+	#define configUSE_RECURSIVE_MUTEXES 0
+#endif
+
+#ifndef configUSE_MUTEXES
+	#define configUSE_MUTEXES 0
+#endif
+
+#ifndef configUSE_TIMERS
+	#define configUSE_TIMERS 0
+#endif
+
+#ifndef configUSE_COUNTING_SEMAPHORES
+	#define configUSE_COUNTING_SEMAPHORES 0
+#endif
+
+#ifndef configUSE_ALTERNATIVE_API
+	#define configUSE_ALTERNATIVE_API 0
+#endif
+
+#ifndef portCRITICAL_NESTING_IN_TCB
+	#define portCRITICAL_NESTING_IN_TCB 0
+#endif
+
+#ifndef configMAX_TASK_NAME_LEN
+	#define configMAX_TASK_NAME_LEN 16
+#endif
+
+#ifndef configIDLE_SHOULD_YIELD
+	#define configIDLE_SHOULD_YIELD		1
+#endif
+
+#if configMAX_TASK_NAME_LEN < 1
+	#error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h
+#endif
+
+#ifndef INCLUDE_xTaskResumeFromISR
+	#define INCLUDE_xTaskResumeFromISR 1
+#endif
+
+#ifndef INCLUDE_xEventGroupSetBitFromISR
+	#define INCLUDE_xEventGroupSetBitFromISR 0
+#endif
+
+#ifndef INCLUDE_xTimerPendFunctionCall
+	#define INCLUDE_xTimerPendFunctionCall 0
+#endif
+
+#ifndef configASSERT
+	#define configASSERT( x )
+	#define configASSERT_DEFINED 0
+#else
+	#define configASSERT_DEFINED 1
+#endif
+
+/* The timers module relies on xTaskGetSchedulerState(). */
+#if configUSE_TIMERS == 1
+
+	#ifndef configTIMER_TASK_PRIORITY
+		#error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined.
+	#endif /* configTIMER_TASK_PRIORITY */
+
+	#ifndef configTIMER_QUEUE_LENGTH
+		#error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined.
+	#endif /* configTIMER_QUEUE_LENGTH */
+
+	#ifndef configTIMER_TASK_STACK_DEPTH
+		#error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined.
+	#endif /* configTIMER_TASK_STACK_DEPTH */
+
+#endif /* configUSE_TIMERS */
+
+#ifndef INCLUDE_xTaskGetSchedulerState
+	#define INCLUDE_xTaskGetSchedulerState 0
+#endif
+
+#ifndef INCLUDE_xTaskGetCurrentTaskHandle
+	#define INCLUDE_xTaskGetCurrentTaskHandle 0
+#endif
+
+
+#ifndef portSET_INTERRUPT_MASK_FROM_ISR
+	#define portSET_INTERRUPT_MASK_FROM_ISR() 0
+#endif
+
+#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR
+	#define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue
+#endif
+
+#ifndef portCLEAN_UP_TCB
+	#define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB
+#endif
+
+#ifndef portPRE_TASK_DELETE_HOOK
+	#define portPRE_TASK_DELETE_HOOK( pvTaskToDelete, pxYieldPending )
+#endif
+
+#ifndef portSETUP_TCB
+	#define portSETUP_TCB( pxTCB ) ( void ) pxTCB
+#endif
+
+#ifndef configQUEUE_REGISTRY_SIZE
+	#define configQUEUE_REGISTRY_SIZE 0U
+#endif
+
+#if ( configQUEUE_REGISTRY_SIZE < 1 )
+	#define vQueueAddToRegistry( xQueue, pcName )
+	#define vQueueUnregisterQueue( xQueue )
+#endif
+
+#ifndef portPOINTER_SIZE_TYPE
+	#define portPOINTER_SIZE_TYPE uint32_t
+#endif
+
+/* Remove any unused trace macros. */
+#ifndef traceSTART
+	/* Used to perform any necessary initialisation - for example, open a file
+	into which trace is to be written. */
+	#define traceSTART()
+#endif
+
+#ifndef traceEND
+	/* Use to close a trace, for example close a file into which trace has been
+	written. */
+	#define traceEND()
+#endif
+
+#ifndef traceTASK_SWITCHED_IN
+	/* Called after a task has been selected to run.  pxCurrentTCB holds a pointer
+	to the task control block of the selected task. */
+	#define traceTASK_SWITCHED_IN()
+#endif
+
+#ifndef traceINCREASE_TICK_COUNT
+	/* Called before stepping the tick count after waking from tickless idle
+	sleep. */
+	#define traceINCREASE_TICK_COUNT( x )
+#endif
+
+#ifndef traceLOW_POWER_IDLE_BEGIN
+	/* Called immediately before entering tickless idle. */
+	#define traceLOW_POWER_IDLE_BEGIN()
+#endif
+
+#ifndef	traceLOW_POWER_IDLE_END
+	/* Called when returning to the Idle task after a tickless idle. */
+	#define traceLOW_POWER_IDLE_END()
+#endif
+
+#ifndef traceTASK_SWITCHED_OUT
+	/* Called before a task has been selected to run.  pxCurrentTCB holds a pointer
+	to the task control block of the task being switched out. */
+	#define traceTASK_SWITCHED_OUT()
+#endif
+
+#ifndef traceTASK_PRIORITY_INHERIT
+	/* Called when a task attempts to take a mutex that is already held by a
+	lower priority task.  pxTCBOfMutexHolder is a pointer to the TCB of the task
+	that holds the mutex.  uxInheritedPriority is the priority the mutex holder
+	will inherit (the priority of the task that is attempting to obtain the
+	muted. */
+	#define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority )
+#endif
+
+#ifndef traceTASK_PRIORITY_DISINHERIT
+	/* Called when a task releases a mutex, the holding of which had resulted in
+	the task inheriting the priority of a higher priority task.
+	pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the
+	mutex.  uxOriginalPriority is the task's configured (base) priority. */
+	#define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority )
+#endif
+
+#ifndef traceBLOCKING_ON_QUEUE_RECEIVE
+	/* Task is about to block because it cannot read from a
+	queue/mutex/semaphore.  pxQueue is a pointer to the queue/mutex/semaphore
+	upon which the read was attempted.  pxCurrentTCB points to the TCB of the
+	task that attempted the read. */
+	#define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue )
+#endif
+
+#ifndef traceBLOCKING_ON_QUEUE_SEND
+	/* Task is about to block because it cannot write to a
+	queue/mutex/semaphore.  pxQueue is a pointer to the queue/mutex/semaphore
+	upon which the write was attempted.  pxCurrentTCB points to the TCB of the
+	task that attempted the write. */
+	#define traceBLOCKING_ON_QUEUE_SEND( pxQueue )
+#endif
+
+#ifndef configCHECK_FOR_STACK_OVERFLOW
+	#define configCHECK_FOR_STACK_OVERFLOW 0
+#endif
+
+/* The following event macros are embedded in the kernel API calls. */
+
+#ifndef traceMOVED_TASK_TO_READY_STATE
+	#define traceMOVED_TASK_TO_READY_STATE( pxTCB )
+#endif
+
+#ifndef traceQUEUE_CREATE
+	#define traceQUEUE_CREATE( pxNewQueue )
+#endif
+
+#ifndef traceQUEUE_CREATE_FAILED
+	#define traceQUEUE_CREATE_FAILED( ucQueueType )
+#endif
+
+#ifndef traceCREATE_MUTEX
+	#define traceCREATE_MUTEX( pxNewQueue )
+#endif
+
+#ifndef traceCREATE_MUTEX_FAILED
+	#define traceCREATE_MUTEX_FAILED()
+#endif
+
+#ifndef traceGIVE_MUTEX_RECURSIVE
+	#define traceGIVE_MUTEX_RECURSIVE( pxMutex )
+#endif
+
+#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED
+	#define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex )
+#endif
+
+#ifndef traceTAKE_MUTEX_RECURSIVE
+	#define traceTAKE_MUTEX_RECURSIVE( pxMutex )
+#endif
+
+#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED
+	#define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex )
+#endif
+
+#ifndef traceCREATE_COUNTING_SEMAPHORE
+	#define traceCREATE_COUNTING_SEMAPHORE()
+#endif
+
+#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED
+	#define traceCREATE_COUNTING_SEMAPHORE_FAILED()
+#endif
+
+#ifndef traceQUEUE_SEND
+	#define traceQUEUE_SEND( pxQueue )
+#endif
+
+#ifndef traceQUEUE_SEND_FAILED
+	#define traceQUEUE_SEND_FAILED( pxQueue )
+#endif
+
+#ifndef traceQUEUE_RECEIVE
+	#define traceQUEUE_RECEIVE( pxQueue )
+#endif
+
+#ifndef traceQUEUE_PEEK
+	#define traceQUEUE_PEEK( pxQueue )
+#endif
+
+#ifndef traceQUEUE_PEEK_FROM_ISR
+	#define traceQUEUE_PEEK_FROM_ISR( pxQueue )
+#endif
+
+#ifndef traceQUEUE_RECEIVE_FAILED
+	#define traceQUEUE_RECEIVE_FAILED( pxQueue )
+#endif
+
+#ifndef traceQUEUE_SEND_FROM_ISR
+	#define traceQUEUE_SEND_FROM_ISR( pxQueue )
+#endif
+
+#ifndef traceQUEUE_SEND_FROM_ISR_FAILED
+	#define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue )
+#endif
+
+#ifndef traceQUEUE_RECEIVE_FROM_ISR
+	#define traceQUEUE_RECEIVE_FROM_ISR( pxQueue )
+#endif
+
+#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED
+	#define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue )
+#endif
+
+#ifndef traceQUEUE_PEEK_FROM_ISR_FAILED
+	#define traceQUEUE_PEEK_FROM_ISR_FAILED( pxQueue )
+#endif
+
+#ifndef traceQUEUE_DELETE
+	#define traceQUEUE_DELETE( pxQueue )
+#endif
+
+#ifndef traceTASK_CREATE
+	#define traceTASK_CREATE( pxNewTCB )
+#endif
+
+#ifndef traceTASK_CREATE_FAILED
+	#define traceTASK_CREATE_FAILED()
+#endif
+
+#ifndef traceTASK_DELETE
+	#define traceTASK_DELETE( pxTaskToDelete )
+#endif
+
+#ifndef traceTASK_DELAY_UNTIL
+	#define traceTASK_DELAY_UNTIL()
+#endif
+
+#ifndef traceTASK_DELAY
+	#define traceTASK_DELAY()
+#endif
+
+#ifndef traceTASK_PRIORITY_SET
+	#define traceTASK_PRIORITY_SET( pxTask, uxNewPriority )
+#endif
+
+#ifndef traceTASK_SUSPEND
+	#define traceTASK_SUSPEND( pxTaskToSuspend )
+#endif
+
+#ifndef traceTASK_RESUME
+	#define traceTASK_RESUME( pxTaskToResume )
+#endif
+
+#ifndef traceTASK_RESUME_FROM_ISR
+	#define traceTASK_RESUME_FROM_ISR( pxTaskToResume )
+#endif
+
+#ifndef traceTASK_INCREMENT_TICK
+	#define traceTASK_INCREMENT_TICK( xTickCount )
+#endif
+
+#ifndef traceTIMER_CREATE
+	#define traceTIMER_CREATE( pxNewTimer )
+#endif
+
+#ifndef traceTIMER_CREATE_FAILED
+	#define traceTIMER_CREATE_FAILED()
+#endif
+
+#ifndef traceTIMER_COMMAND_SEND
+	#define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn )
+#endif
+
+#ifndef traceTIMER_EXPIRED
+	#define traceTIMER_EXPIRED( pxTimer )
+#endif
+
+#ifndef traceTIMER_COMMAND_RECEIVED
+	#define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue )
+#endif
+
+#ifndef traceMALLOC
+    #define traceMALLOC( pvAddress, uiSize )
+#endif
+
+#ifndef traceFREE
+    #define traceFREE( pvAddress, uiSize )
+#endif
+
+#ifndef traceEVENT_GROUP_CREATE
+	#define traceEVENT_GROUP_CREATE( xEventGroup )
+#endif
+
+#ifndef traceEVENT_GROUP_CREATE_FAILED
+	#define traceEVENT_GROUP_CREATE_FAILED()
+#endif
+
+#ifndef traceEVENT_GROUP_SYNC_BLOCK
+	#define traceEVENT_GROUP_SYNC_BLOCK( xEventGroup, uxBitsToSet, uxBitsToWaitFor )
+#endif
+
+#ifndef traceEVENT_GROUP_SYNC_END
+	#define traceEVENT_GROUP_SYNC_END( xEventGroup, uxBitsToSet, uxBitsToWaitFor, xTimeoutOccurred ) ( void ) xTimeoutOccurred
+#endif
+
+#ifndef traceEVENT_GROUP_WAIT_BITS_BLOCK
+	#define traceEVENT_GROUP_WAIT_BITS_BLOCK( xEventGroup, uxBitsToWaitFor )
+#endif
+
+#ifndef traceEVENT_GROUP_WAIT_BITS_END
+	#define traceEVENT_GROUP_WAIT_BITS_END( xEventGroup, uxBitsToWaitFor, xTimeoutOccurred ) ( void ) xTimeoutOccurred
+#endif
+
+#ifndef traceEVENT_GROUP_CLEAR_BITS
+	#define traceEVENT_GROUP_CLEAR_BITS( xEventGroup, uxBitsToClear )
+#endif
+
+#ifndef traceEVENT_GROUP_CLEAR_BITS_FROM_ISR
+	#define traceEVENT_GROUP_CLEAR_BITS_FROM_ISR( xEventGroup, uxBitsToClear )
+#endif
+
+#ifndef traceEVENT_GROUP_SET_BITS
+	#define traceEVENT_GROUP_SET_BITS( xEventGroup, uxBitsToSet )
+#endif
+
+#ifndef traceEVENT_GROUP_SET_BITS_FROM_ISR
+	#define traceEVENT_GROUP_SET_BITS_FROM_ISR( xEventGroup, uxBitsToSet )
+#endif
+
+#ifndef traceEVENT_GROUP_DELETE
+	#define traceEVENT_GROUP_DELETE( xEventGroup )
+#endif
+
+#ifndef tracePEND_FUNC_CALL
+	#define tracePEND_FUNC_CALL(xFunctionToPend, pvParameter1, ulParameter2, ret)
+#endif
+
+#ifndef tracePEND_FUNC_CALL_FROM_ISR
+	#define tracePEND_FUNC_CALL_FROM_ISR(xFunctionToPend, pvParameter1, ulParameter2, ret)
+#endif
+
+#ifndef traceQUEUE_REGISTRY_ADD
+	#define traceQUEUE_REGISTRY_ADD(xQueue, pcQueueName)
+#endif
+
+#ifndef traceTASK_NOTIFY_TAKE_BLOCK
+	#define traceTASK_NOTIFY_TAKE_BLOCK()
+#endif
+
+#ifndef traceTASK_NOTIFY_TAKE
+	#define traceTASK_NOTIFY_TAKE()
+#endif
+
+#ifndef traceTASK_NOTIFY_WAIT_BLOCK
+	#define traceTASK_NOTIFY_WAIT_BLOCK()
+#endif
+
+#ifndef traceTASK_NOTIFY_WAIT
+	#define traceTASK_NOTIFY_WAIT()
+#endif
+
+#ifndef traceTASK_NOTIFY
+	#define traceTASK_NOTIFY()
+#endif
+
+#ifndef traceTASK_NOTIFY_FROM_ISR
+	#define traceTASK_NOTIFY_FROM_ISR()
+#endif
+
+#ifndef traceTASK_NOTIFY_GIVE_FROM_ISR
+	#define traceTASK_NOTIFY_GIVE_FROM_ISR()
+#endif
+
+#ifndef configGENERATE_RUN_TIME_STATS
+	#define configGENERATE_RUN_TIME_STATS 0
+#endif
+
+#if ( configGENERATE_RUN_TIME_STATS == 1 )
+
+	#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS
+		#error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined.  portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base.
+	#endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */
+
+	#ifndef portGET_RUN_TIME_COUNTER_VALUE
+		#ifndef portALT_GET_RUN_TIME_COUNTER_VALUE
+			#error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined.  See the examples provided and the FreeRTOS web site for more information.
+		#endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */
+	#endif /* portGET_RUN_TIME_COUNTER_VALUE */
+
+#endif /* configGENERATE_RUN_TIME_STATS */
+
+#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS
+	#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()
+#endif
+
+#ifndef configUSE_MALLOC_FAILED_HOOK
+	#define configUSE_MALLOC_FAILED_HOOK 0
+#endif
+
+#ifndef portPRIVILEGE_BIT
+	#define portPRIVILEGE_BIT ( ( UBaseType_t ) 0x00 )
+#endif
+
+#ifndef portYIELD_WITHIN_API
+	#define portYIELD_WITHIN_API portYIELD
+#endif
+
+#ifndef pvPortMallocAligned
+	#define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) )
+#endif
+
+#ifndef vPortFreeAligned
+	#define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree )
+#endif
+
+#ifndef portSUPPRESS_TICKS_AND_SLEEP
+	#define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime )
+#endif
+
+#ifndef configEXPECTED_IDLE_TIME_BEFORE_SLEEP
+	#define configEXPECTED_IDLE_TIME_BEFORE_SLEEP 2
+#endif
+
+#if configEXPECTED_IDLE_TIME_BEFORE_SLEEP < 2
+	#error configEXPECTED_IDLE_TIME_BEFORE_SLEEP must not be less than 2
+#endif
+
+#ifndef configUSE_TICKLESS_IDLE
+	#define configUSE_TICKLESS_IDLE 0
+#endif
+
+#ifndef configPRE_SLEEP_PROCESSING
+	#define configPRE_SLEEP_PROCESSING( x )
+#endif
+
+#ifndef configPOST_SLEEP_PROCESSING
+	#define configPOST_SLEEP_PROCESSING( x )
+#endif
+
+#ifndef configUSE_QUEUE_SETS
+	#define configUSE_QUEUE_SETS 0
+#endif
+
+#ifndef portTASK_USES_FLOATING_POINT
+	#define portTASK_USES_FLOATING_POINT()
+#endif
+
+#ifndef configUSE_TIME_SLICING
+	#define configUSE_TIME_SLICING 1
+#endif
+
+#ifndef configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS
+	#define configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS 0
+#endif
+
+#ifndef configUSE_NEWLIB_REENTRANT
+	#define configUSE_NEWLIB_REENTRANT 0
+#endif
+
+#ifndef configUSE_STATS_FORMATTING_FUNCTIONS
+	#define configUSE_STATS_FORMATTING_FUNCTIONS 0
+#endif
+
+#ifndef portASSERT_IF_INTERRUPT_PRIORITY_INVALID
+	#define portASSERT_IF_INTERRUPT_PRIORITY_INVALID()
+#endif
+
+#ifndef configUSE_TRACE_FACILITY
+	#define configUSE_TRACE_FACILITY 0
+#endif
+
+#ifndef mtCOVERAGE_TEST_MARKER
+	#define mtCOVERAGE_TEST_MARKER()
+#endif
+
+#ifndef mtCOVERAGE_TEST_DELAY
+	#define mtCOVERAGE_TEST_DELAY()
+#endif
+
+#ifndef portASSERT_IF_IN_ISR
+	#define portASSERT_IF_IN_ISR()
+#endif
+
+#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION
+	#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0
+#endif
+
+#ifndef configAPPLICATION_ALLOCATED_HEAP
+	#define configAPPLICATION_ALLOCATED_HEAP 0
+#endif
+
+#ifndef configUSE_TASK_NOTIFICATIONS
+	#define configUSE_TASK_NOTIFICATIONS 1
+#endif
+
+#ifndef portTICK_TYPE_IS_ATOMIC
+	#define portTICK_TYPE_IS_ATOMIC 0
+#endif
+
+#if( portTICK_TYPE_IS_ATOMIC == 0 )
+	/* Either variables of tick type cannot be read atomically, or
+	portTICK_TYPE_IS_ATOMIC was not set - map the critical sections used when
+	the tick count is returned to the standard critical section macros. */
+	#define portTICK_TYPE_ENTER_CRITICAL() portENTER_CRITICAL()
+	#define portTICK_TYPE_EXIT_CRITICAL() portEXIT_CRITICAL()
+	#define portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR() portSET_INTERRUPT_MASK_FROM_ISR()
+	#define portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( x ) portCLEAR_INTERRUPT_MASK_FROM_ISR( ( x ) )
+#else
+	/* The tick type can be read atomically, so critical sections used when the
+	tick count is returned can be defined away. */
+	#define portTICK_TYPE_ENTER_CRITICAL()
+	#define portTICK_TYPE_EXIT_CRITICAL()
+	#define portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR() 0
+	#define portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( x ) ( void ) x
+#endif
+
+/* Definitions to allow backward compatibility with FreeRTOS versions prior to
+V8 if desired. */
+#ifndef configENABLE_BACKWARD_COMPATIBILITY
+	#define configENABLE_BACKWARD_COMPATIBILITY 1
+#endif
+
+#if configENABLE_BACKWARD_COMPATIBILITY == 1
+	#define eTaskStateGet eTaskGetState
+	#define portTickType TickType_t
+	#define xTaskHandle TaskHandle_t
+	#define xQueueHandle QueueHandle_t
+	#define xSemaphoreHandle SemaphoreHandle_t
+	#define xQueueSetHandle QueueSetHandle_t
+	#define xQueueSetMemberHandle QueueSetMemberHandle_t
+	#define xTimeOutType TimeOut_t
+	#define xMemoryRegion MemoryRegion_t
+	#define xTaskParameters TaskParameters_t
+	#define xTaskStatusType	TaskStatus_t
+	#define xTimerHandle TimerHandle_t
+	#define xCoRoutineHandle CoRoutineHandle_t
+	#define pdTASK_HOOK_CODE TaskHookFunction_t
+	#define portTICK_RATE_MS portTICK_PERIOD_MS
+
+	/* Backward compatibility within the scheduler code only - these definitions
+	are not really required but are included for completeness. */
+	#define tmrTIMER_CALLBACK TimerCallbackFunction_t
+	#define pdTASK_CODE TaskFunction_t
+	#define xListItem ListItem_t
+	#define xList List_t
+#endif /* configENABLE_BACKWARD_COMPATIBILITY */
+
+/* Set configUSE_TASK_FPU_SUPPORT to 0 to omit floating point support even
+if floating point hardware is otherwise supported by the FreeRTOS port in use.
+This constant is not supported by all FreeRTOS ports that include floating 
+point support. */
+#ifndef configUSE_TASK_FPU_SUPPORT
+	#define configUSE_TASK_FPU_SUPPORT 1
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* INC_FREERTOS_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/StackMacros.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/StackMacros.h
new file mode 100644
index 0000000000000000000000000000000000000000..1359090c321f3f7497d5edc97542bc0dd516356f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/StackMacros.h
@@ -0,0 +1,171 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef STACK_MACROS_H
+#define STACK_MACROS_H
+
+/*
+ * Call the stack overflow hook function if the stack of the task being swapped
+ * out is currently overflowed, or looks like it might have overflowed in the
+ * past.
+ *
+ * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check
+ * the current stack state only - comparing the current top of stack value to
+ * the stack limit.  Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1
+ * will also cause the last few stack bytes to be checked to ensure the value
+ * to which the bytes were set when the task was created have not been
+ * overwritten.  Note this second test does not guarantee that an overflowed
+ * stack will always be recognised.
+ */
+
+/*-----------------------------------------------------------*/
+
+#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) )
+
+	/* Only the current stack state is to be checked. */
+	#define taskCHECK_FOR_STACK_OVERFLOW()																\
+	{																									\
+		/* Is the currently saved stack pointer within the stack limit? */								\
+		if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack )										\
+		{																								\
+			vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName );	\
+		}																								\
+	}
+
+#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */
+/*-----------------------------------------------------------*/
+
+#if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) )
+
+	/* Only the current stack state is to be checked. */
+	#define taskCHECK_FOR_STACK_OVERFLOW()																\
+	{																									\
+																										\
+		/* Is the currently saved stack pointer within the stack limit? */								\
+		if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack )									\
+		{																								\
+			vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName );	\
+		}																								\
+	}
+
+#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */
+/*-----------------------------------------------------------*/
+
+#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) )
+
+	#define taskCHECK_FOR_STACK_OVERFLOW()																\
+	{																									\
+		const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack;							\
+		const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5;											\
+																										\
+		if( ( pulStack[ 0 ] != ulCheckValue ) ||												\
+			( pulStack[ 1 ] != ulCheckValue ) ||												\
+			( pulStack[ 2 ] != ulCheckValue ) ||												\
+			( pulStack[ 3 ] != ulCheckValue ) )												\
+		{																								\
+			vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName );	\
+		}																								\
+	}
+
+#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */
+/*-----------------------------------------------------------*/
+
+#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) )
+
+	#define taskCHECK_FOR_STACK_OVERFLOW()																								\
+	{																																	\
+	int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack;																		\
+	static const uint8_t ucExpectedStackBytes[] = {	tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE,		\
+													tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE,		\
+													tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE,		\
+													tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE,		\
+													tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE };	\
+																																		\
+																																		\
+		pcEndOfStack -= sizeof( ucExpectedStackBytes );																					\
+																																		\
+		/* Has the extremity of the task stack ever been written over? */																\
+		if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 )					\
+		{																																\
+			vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName );									\
+		}																																\
+	}
+
+#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */
+/*-----------------------------------------------------------*/
+
+/* Remove stack overflow macro if not being used. */
+#ifndef taskCHECK_FOR_STACK_OVERFLOW
+	#define taskCHECK_FOR_STACK_OVERFLOW()
+#endif
+
+
+
+#endif /* STACK_MACROS_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/croutine.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/croutine.h
new file mode 100644
index 0000000000000000000000000000000000000000..dc655ae20c83666f2b45c475850acce797c31712
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/croutine.h
@@ -0,0 +1,762 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef CO_ROUTINE_H
+#define CO_ROUTINE_H
+
+#ifndef INC_FREERTOS_H
+	#error "include FreeRTOS.h must appear in source files before include croutine.h"
+#endif
+
+#include "list.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Used to hide the implementation of the co-routine control block.  The
+control block structure however has to be included in the header due to
+the macro implementation of the co-routine functionality. */
+typedef void * CoRoutineHandle_t;
+
+/* Defines the prototype to which co-routine functions must conform. */
+typedef void (*crCOROUTINE_CODE)( CoRoutineHandle_t, UBaseType_t );
+
+typedef struct corCoRoutineControlBlock
+{
+	crCOROUTINE_CODE 	pxCoRoutineFunction;
+	ListItem_t			xGenericListItem;	/*< List item used to place the CRCB in ready and blocked queues. */
+	ListItem_t			xEventListItem;		/*< List item used to place the CRCB in event lists. */
+	UBaseType_t 		uxPriority;			/*< The priority of the co-routine in relation to other co-routines. */
+	UBaseType_t 		uxIndex;			/*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */
+	uint16_t 			uxState;			/*< Used internally by the co-routine implementation. */
+} CRCB_t; /* Co-routine control block.  Note must be identical in size down to uxPriority with TCB_t. */
+
+/**
+ * croutine. h
+ *<pre>
+ BaseType_t xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 UBaseType_t uxPriority,
+                                 UBaseType_t uxIndex
+                               );</pre>
+ *
+ * Create a new co-routine and add it to the list of co-routines that are
+ * ready to run.
+ *
+ * @param pxCoRoutineCode Pointer to the co-routine function.  Co-routine
+ * functions require special syntax - see the co-routine section of the WEB
+ * documentation for more information.
+ *
+ * @param uxPriority The priority with respect to other co-routines at which
+ *  the co-routine will run.
+ *
+ * @param uxIndex Used to distinguish between different co-routines that
+ * execute the same function.  See the example below and the co-routine section
+ * of the WEB documentation for further information.
+ *
+ * @return pdPASS if the co-routine was successfully created and added to a ready
+ * list, otherwise an error code defined with ProjDefs.h.
+ *
+ * Example usage:
+   <pre>
+ // Co-routine to be created.
+ void vFlashCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const TickType_t uxFlashRates[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how int32_t to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ uint8_t ucParameterToPass;
+ TaskHandle_t xHandle;
+
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   </pre>
+ * \defgroup xCoRoutineCreate xCoRoutineCreate
+ * \ingroup Tasks
+ */
+BaseType_t xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, UBaseType_t uxPriority, UBaseType_t uxIndex );
+
+
+/**
+ * croutine. h
+ *<pre>
+ void vCoRoutineSchedule( void );</pre>
+ *
+ * Run a co-routine.
+ *
+ * vCoRoutineSchedule() executes the highest priority co-routine that is able
+ * to run.  The co-routine will execute until it either blocks, yields or is
+ * preempted by a task.  Co-routines execute cooperatively so one
+ * co-routine cannot be preempted by another, but can be preempted by a task.
+ *
+ * If an application comprises of both tasks and co-routines then
+ * vCoRoutineSchedule should be called from the idle task (in an idle task
+ * hook).
+ *
+ * Example usage:
+   <pre>
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ </pre>
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule
+ * \ingroup Tasks
+ */
+void vCoRoutineSchedule( void );
+
+/**
+ * croutine. h
+ * <pre>
+ crSTART( CoRoutineHandle_t xHandle );</pre>
+ *
+ * This macro MUST always be called at the start of a co-routine function.
+ *
+ * Example usage:
+   <pre>
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static int32_t ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }</pre>
+ * \defgroup crSTART crSTART
+ * \ingroup Tasks
+ */
+#define crSTART( pxCRCB ) switch( ( ( CRCB_t * )( pxCRCB ) )->uxState ) { case 0:
+
+/**
+ * croutine. h
+ * <pre>
+ crEND();</pre>
+ *
+ * This macro MUST always be called at the end of a co-routine function.
+ *
+ * Example usage:
+   <pre>
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static int32_t ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }</pre>
+ * \defgroup crSTART crSTART
+ * \ingroup Tasks
+ */
+#define crEND() }
+
+/*
+ * These macros are intended for internal use by the co-routine implementation
+ * only.  The macros should not be used directly by application writers.
+ */
+#define crSET_STATE0( xHandle ) ( ( CRCB_t * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2):
+#define crSET_STATE1( xHandle ) ( ( CRCB_t * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1):
+
+/**
+ * croutine. h
+ *<pre>
+ crDELAY( CoRoutineHandle_t xHandle, TickType_t xTicksToDelay );</pre>
+ *
+ * Delay a co-routine for a fixed period of time.
+ *
+ * crDELAY can only be called from the co-routine function itself - not
+ * from within a function called by the co-routine function.  This is because
+ * co-routines do not maintain their own stack.
+ *
+ * @param xHandle The handle of the co-routine to delay.  This is the xHandle
+ * parameter of the co-routine function.
+ *
+ * @param xTickToDelay The number of ticks that the co-routine should delay
+ * for.  The actual amount of time this equates to is defined by
+ * configTICK_RATE_HZ (set in FreeRTOSConfig.h).  The constant portTICK_PERIOD_MS
+ * can be used to convert ticks to milliseconds.
+ *
+ * Example usage:
+   <pre>
+ // Co-routine to be created.
+ void vACoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_PERIOD_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }</pre>
+ * \defgroup crDELAY crDELAY
+ * \ingroup Tasks
+ */
+#define crDELAY( xHandle, xTicksToDelay )												\
+	if( ( xTicksToDelay ) > 0 )															\
+	{																					\
+		vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL );							\
+	}																					\
+	crSET_STATE0( ( xHandle ) );
+
+/**
+ * <pre>
+ crQUEUE_SEND(
+                  CoRoutineHandle_t xHandle,
+                  QueueHandle_t pxQueue,
+                  void *pvItemToQueue,
+                  TickType_t xTicksToWait,
+                  BaseType_t *pxResult
+             )</pre>
+ *
+ * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine
+ * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks.
+ *
+ * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas
+ * xQueueSend() and xQueueReceive() can only be used from tasks.
+ *
+ * crQUEUE_SEND can only be called from the co-routine function itself - not
+ * from within a function called by the co-routine function.  This is because
+ * co-routines do not maintain their own stack.
+ *
+ * See the co-routine section of the WEB documentation for information on
+ * passing data between tasks and co-routines and between ISR's and
+ * co-routines.
+ *
+ * @param xHandle The handle of the calling co-routine.  This is the xHandle
+ * parameter of the co-routine function.
+ *
+ * @param pxQueue The handle of the queue on which the data will be posted.
+ * The handle is obtained as the return value when the queue is created using
+ * the xQueueCreate() API function.
+ *
+ * @param pvItemToQueue A pointer to the data being posted onto the queue.
+ * The number of bytes of each queued item is specified when the queue is
+ * created.  This number of bytes is copied from pvItemToQueue into the queue
+ * itself.
+ *
+ * @param xTickToDelay The number of ticks that the co-routine should block
+ * to wait for space to become available on the queue, should space not be
+ * available immediately. The actual amount of time this equates to is defined
+ * by configTICK_RATE_HZ (set in FreeRTOSConfig.h).  The constant
+ * portTICK_PERIOD_MS can be used to convert ticks to milliseconds (see example
+ * below).
+ *
+ * @param pxResult The variable pointed to by pxResult will be set to pdPASS if
+ * data was successfully posted onto the queue, otherwise it will be set to an
+ * error defined within ProjDefs.h.
+ *
+ * Example usage:
+   <pre>
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static BaseType_t xNumberToPost = 0;
+ static BaseType_t xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }</pre>
+ * \defgroup crQUEUE_SEND crQUEUE_SEND
+ * \ingroup Tasks
+ */
+#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult )			\
+{																						\
+	*( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) );	\
+	if( *( pxResult ) == errQUEUE_BLOCKED )												\
+	{																					\
+		crSET_STATE0( ( xHandle ) );													\
+		*pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 );					\
+	}																					\
+	if( *pxResult == errQUEUE_YIELD )													\
+	{																					\
+		crSET_STATE1( ( xHandle ) );													\
+		*pxResult = pdPASS;																\
+	}																					\
+}
+
+/**
+ * croutine. h
+ * <pre>
+  crQUEUE_RECEIVE(
+                     CoRoutineHandle_t xHandle,
+                     QueueHandle_t pxQueue,
+                     void *pvBuffer,
+                     TickType_t xTicksToWait,
+                     BaseType_t *pxResult
+                 )</pre>
+ *
+ * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine
+ * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks.
+ *
+ * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas
+ * xQueueSend() and xQueueReceive() can only be used from tasks.
+ *
+ * crQUEUE_RECEIVE can only be called from the co-routine function itself - not
+ * from within a function called by the co-routine function.  This is because
+ * co-routines do not maintain their own stack.
+ *
+ * See the co-routine section of the WEB documentation for information on
+ * passing data between tasks and co-routines and between ISR's and
+ * co-routines.
+ *
+ * @param xHandle The handle of the calling co-routine.  This is the xHandle
+ * parameter of the co-routine function.
+ *
+ * @param pxQueue The handle of the queue from which the data will be received.
+ * The handle is obtained as the return value when the queue is created using
+ * the xQueueCreate() API function.
+ *
+ * @param pvBuffer The buffer into which the received item is to be copied.
+ * The number of bytes of each queued item is specified when the queue is
+ * created.  This number of bytes is copied into pvBuffer.
+ *
+ * @param xTickToDelay The number of ticks that the co-routine should block
+ * to wait for data to become available from the queue, should data not be
+ * available immediately. The actual amount of time this equates to is defined
+ * by configTICK_RATE_HZ (set in FreeRTOSConfig.h).  The constant
+ * portTICK_PERIOD_MS can be used to convert ticks to milliseconds (see the
+ * crQUEUE_SEND example).
+ *
+ * @param pxResult The variable pointed to by pxResult will be set to pdPASS if
+ * data was successfully retrieved from the queue, otherwise it will be set to
+ * an error code as defined within ProjDefs.h.
+ *
+ * Example usage:
+ <pre>
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static BaseType_t xResult;
+ static UBaseType_t uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }</pre>
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE
+ * \ingroup Tasks
+ */
+#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult )			\
+{																						\
+	*( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) );		\
+	if( *( pxResult ) == errQUEUE_BLOCKED ) 											\
+	{																					\
+		crSET_STATE0( ( xHandle ) );													\
+		*( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 );				\
+	}																					\
+	if( *( pxResult ) == errQUEUE_YIELD )												\
+	{																					\
+		crSET_STATE1( ( xHandle ) );													\
+		*( pxResult ) = pdPASS;															\
+	}																					\
+}
+
+/**
+ * croutine. h
+ * <pre>
+  crQUEUE_SEND_FROM_ISR(
+                            QueueHandle_t pxQueue,
+                            void *pvItemToQueue,
+                            BaseType_t xCoRoutinePreviouslyWoken
+                       )</pre>
+ *
+ * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the
+ * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR()
+ * functions used by tasks.
+ *
+ * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to
+ * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and
+ * xQueueReceiveFromISR() can only be used to pass data between a task and and
+ * ISR.
+ *
+ * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue
+ * that is being used from within a co-routine.
+ *
+ * See the co-routine section of the WEB documentation for information on
+ * passing data between tasks and co-routines and between ISR's and
+ * co-routines.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto
+ * the same queue multiple times from a single interrupt.  The first call
+ * should always pass in pdFALSE.  Subsequent calls should pass in
+ * the value returned from the previous call.
+ *
+ * @return pdTRUE if a co-routine was woken by posting onto the queue.  This is
+ * used by the ISR to determine if a context switch may be required following
+ * the ISR.
+ *
+ * Example usage:
+ <pre>
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ char cRxedChar;
+ BaseType_t xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ BaseType_t xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }</pre>
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR
+ * \ingroup Tasks
+ */
+#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) )
+
+
+/**
+ * croutine. h
+ * <pre>
+  crQUEUE_SEND_FROM_ISR(
+                            QueueHandle_t pxQueue,
+                            void *pvBuffer,
+                            BaseType_t * pxCoRoutineWoken
+                       )</pre>
+ *
+ * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the
+ * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR()
+ * functions used by tasks.
+ *
+ * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to
+ * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and
+ * xQueueReceiveFromISR() can only be used to pass data between a task and and
+ * ISR.
+ *
+ * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data
+ * from a queue that is being used from within a co-routine (a co-routine
+ * posted to the queue).
+ *
+ * See the co-routine section of the WEB documentation for information on
+ * passing data between tasks and co-routines and between ISR's and
+ * co-routines.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvBuffer A pointer to a buffer into which the received item will be
+ * placed.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from the queue into
+ * pvBuffer.
+ *
+ * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become
+ * available on the queue.  If crQUEUE_RECEIVE_FROM_ISR causes such a
+ * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise
+ * *pxCoRoutineWoken will remain unchanged.
+ *
+ * @return pdTRUE an item was successfully received from the queue, otherwise
+ * pdFALSE.
+ *
+ * Example usage:
+ <pre>
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( CoRoutineHandle_t xHandle, UBaseType_t uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ BaseType_t xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ BaseType_t xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }</pre>
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR
+ * \ingroup Tasks
+ */
+#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) )
+
+/*
+ * This function is intended for internal use by the co-routine macros only.
+ * The macro nature of the co-routine implementation requires that the
+ * prototype appears here.  The function should not be used by application
+ * writers.
+ *
+ * Removes the current co-routine from its ready list and places it in the
+ * appropriate delayed list.
+ */
+void vCoRoutineAddToDelayedList( TickType_t xTicksToDelay, List_t *pxEventList );
+
+/*
+ * This function is intended for internal use by the queue implementation only.
+ * The function should not be used by application writers.
+ *
+ * Removes the highest priority co-routine from the event list and places it in
+ * the pending ready list.
+ */
+BaseType_t xCoRoutineRemoveFromEventList( const List_t *pxEventList );
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* CO_ROUTINE_H */
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/deprecated_definitions.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/deprecated_definitions.h
new file mode 100644
index 0000000000000000000000000000000000000000..0fad862693692a2a00d134252d24245429a38933
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/deprecated_definitions.h
@@ -0,0 +1,321 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef DEPRECATED_DEFINITIONS_H
+#define DEPRECATED_DEFINITIONS_H
+
+
+/* Each FreeRTOS port has a unique portmacro.h header file.  Originally a
+pre-processor definition was used to ensure the pre-processor found the correct
+portmacro.h file for the port being used.  That scheme was deprecated in favour
+of setting the compiler's include path such that it found the correct
+portmacro.h file - removing the need for the constant and allowing the
+portmacro.h file to be located anywhere in relation to the port being used.  The
+definitions below remain in the code for backward compatibility only.  New
+projects should not use them. */
+
+#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT
+	#include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h"
+	typedef void ( __interrupt __far *pxISR )();
+#endif
+
+#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT
+	#include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h"
+	typedef void ( __interrupt __far *pxISR )();
+#endif
+
+#ifdef GCC_MEGA_AVR
+	#include "../portable/GCC/ATMega323/portmacro.h"
+#endif
+
+#ifdef IAR_MEGA_AVR
+	#include "../portable/IAR/ATMega323/portmacro.h"
+#endif
+
+#ifdef MPLAB_PIC24_PORT
+	#include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h"
+#endif
+
+#ifdef MPLAB_DSPIC_PORT
+	#include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h"
+#endif
+
+#ifdef MPLAB_PIC18F_PORT
+	#include "../../Source/portable/MPLAB/PIC18F/portmacro.h"
+#endif
+
+#ifdef MPLAB_PIC32MX_PORT
+	#include "../../Source/portable/MPLAB/PIC32MX/portmacro.h"
+#endif
+
+#ifdef _FEDPICC
+	#include "libFreeRTOS/Include/portmacro.h"
+#endif
+
+#ifdef SDCC_CYGNAL
+	#include "../../Source/portable/SDCC/Cygnal/portmacro.h"
+#endif
+
+#ifdef GCC_ARM7
+	#include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h"
+#endif
+
+#ifdef GCC_ARM7_ECLIPSE
+	#include "portmacro.h"
+#endif
+
+#ifdef ROWLEY_LPC23xx
+	#include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h"
+#endif
+
+#ifdef IAR_MSP430
+	#include "..\..\Source\portable\IAR\MSP430\portmacro.h"
+#endif
+
+#ifdef GCC_MSP430
+	#include "../../Source/portable/GCC/MSP430F449/portmacro.h"
+#endif
+
+#ifdef ROWLEY_MSP430
+	#include "../../Source/portable/Rowley/MSP430F449/portmacro.h"
+#endif
+
+#ifdef ARM7_LPC21xx_KEIL_RVDS
+	#include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h"
+#endif
+
+#ifdef SAM7_GCC
+	#include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h"
+#endif
+
+#ifdef SAM7_IAR
+	#include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h"
+#endif
+
+#ifdef SAM9XE_IAR
+	#include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h"
+#endif
+
+#ifdef LPC2000_IAR
+	#include "..\..\Source\portable\IAR\LPC2000\portmacro.h"
+#endif
+
+#ifdef STR71X_IAR
+	#include "..\..\Source\portable\IAR\STR71x\portmacro.h"
+#endif
+
+#ifdef STR75X_IAR
+	#include "..\..\Source\portable\IAR\STR75x\portmacro.h"
+#endif
+
+#ifdef STR75X_GCC
+	#include "..\..\Source\portable\GCC\STR75x\portmacro.h"
+#endif
+
+#ifdef STR91X_IAR
+	#include "..\..\Source\portable\IAR\STR91x\portmacro.h"
+#endif
+
+#ifdef GCC_H8S
+	#include "../../Source/portable/GCC/H8S2329/portmacro.h"
+#endif
+
+#ifdef GCC_AT91FR40008
+	#include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h"
+#endif
+
+#ifdef RVDS_ARMCM3_LM3S102
+	#include "../../Source/portable/RVDS/ARM_CM3/portmacro.h"
+#endif
+
+#ifdef GCC_ARMCM3_LM3S102
+	#include "../../Source/portable/GCC/ARM_CM3/portmacro.h"
+#endif
+
+#ifdef GCC_ARMCM3
+	#include "../../Source/portable/GCC/ARM_CM3/portmacro.h"
+#endif
+
+#ifdef IAR_ARM_CM3
+	#include "../../Source/portable/IAR/ARM_CM3/portmacro.h"
+#endif
+
+#ifdef IAR_ARMCM3_LM
+	#include "../../Source/portable/IAR/ARM_CM3/portmacro.h"
+#endif
+
+#ifdef HCS12_CODE_WARRIOR
+	#include "../../Source/portable/CodeWarrior/HCS12/portmacro.h"
+#endif
+
+#ifdef MICROBLAZE_GCC
+	#include "../../Source/portable/GCC/MicroBlaze/portmacro.h"
+#endif
+
+#ifdef TERN_EE
+	#include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h"
+#endif
+
+#ifdef GCC_HCS12
+	#include "../../Source/portable/GCC/HCS12/portmacro.h"
+#endif
+
+#ifdef GCC_MCF5235
+    #include "../../Source/portable/GCC/MCF5235/portmacro.h"
+#endif
+
+#ifdef COLDFIRE_V2_GCC
+	#include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h"
+#endif
+
+#ifdef COLDFIRE_V2_CODEWARRIOR
+	#include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h"
+#endif
+
+#ifdef GCC_PPC405
+	#include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h"
+#endif
+
+#ifdef GCC_PPC440
+	#include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h"
+#endif
+
+#ifdef _16FX_SOFTUNE
+	#include "..\..\Source\portable\Softune\MB96340\portmacro.h"
+#endif
+
+#ifdef BCC_INDUSTRIAL_PC_PORT
+	/* A short file name has to be used in place of the normal
+	FreeRTOSConfig.h when using the Borland compiler. */
+	#include "frconfig.h"
+	#include "..\portable\BCC\16BitDOS\PC\prtmacro.h"
+    typedef void ( __interrupt __far *pxISR )();
+#endif
+
+#ifdef BCC_FLASH_LITE_186_PORT
+	/* A short file name has to be used in place of the normal
+	FreeRTOSConfig.h when using the Borland compiler. */
+	#include "frconfig.h"
+	#include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h"
+    typedef void ( __interrupt __far *pxISR )();
+#endif
+
+#ifdef __GNUC__
+   #ifdef __AVR32_AVR32A__
+	   #include "portmacro.h"
+   #endif
+#endif
+
+#ifdef __ICCAVR32__
+   #ifdef __CORE__
+      #if __CORE__ == __AVR32A__
+	      #include "portmacro.h"
+      #endif
+   #endif
+#endif
+
+#ifdef __91467D
+	#include "portmacro.h"
+#endif
+
+#ifdef __96340
+	#include "portmacro.h"
+#endif
+
+
+#ifdef __IAR_V850ES_Fx3__
+	#include "../../Source/portable/IAR/V850ES/portmacro.h"
+#endif
+
+#ifdef __IAR_V850ES_Jx3__
+	#include "../../Source/portable/IAR/V850ES/portmacro.h"
+#endif
+
+#ifdef __IAR_V850ES_Jx3_L__
+	#include "../../Source/portable/IAR/V850ES/portmacro.h"
+#endif
+
+#ifdef __IAR_V850ES_Jx2__
+	#include "../../Source/portable/IAR/V850ES/portmacro.h"
+#endif
+
+#ifdef __IAR_V850ES_Hx2__
+	#include "../../Source/portable/IAR/V850ES/portmacro.h"
+#endif
+
+#ifdef __IAR_78K0R_Kx3__
+	#include "../../Source/portable/IAR/78K0R/portmacro.h"
+#endif
+
+#ifdef __IAR_78K0R_Kx3L__
+	#include "../../Source/portable/IAR/78K0R/portmacro.h"
+#endif
+
+#endif /* DEPRECATED_DEFINITIONS_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/event_groups.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/event_groups.h
new file mode 100644
index 0000000000000000000000000000000000000000..a381ed0726010521968e55fc974332b2c4156490
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/event_groups.h
@@ -0,0 +1,730 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef EVENT_GROUPS_H
+#define EVENT_GROUPS_H
+
+#ifndef INC_FREERTOS_H
+	#error "include FreeRTOS.h" must appear in source files before "include event_groups.h"
+#endif
+
+#include "timers.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * An event group is a collection of bits to which an application can assign a
+ * meaning.  For example, an application may create an event group to convey
+ * the status of various CAN bus related events in which bit 0 might mean "A CAN
+ * message has been received and is ready for processing", bit 1 might mean "The
+ * application has queued a message that is ready for sending onto the CAN
+ * network", and bit 2 might mean "It is time to send a SYNC message onto the
+ * CAN network" etc.  A task can then test the bit values to see which events
+ * are active, and optionally enter the Blocked state to wait for a specified
+ * bit or a group of specified bits to be active.  To continue the CAN bus
+ * example, a CAN controlling task can enter the Blocked state (and therefore
+ * not consume any processing time) until either bit 0, bit 1 or bit 2 are
+ * active, at which time the bit that was actually active would inform the task
+ * which action it had to take (process a received message, send a message, or
+ * send a SYNC).
+ *
+ * The event groups implementation contains intelligence to avoid race
+ * conditions that would otherwise occur were an application to use a simple
+ * variable for the same purpose.  This is particularly important with respect
+ * to when a bit within an event group is to be cleared, and when bits have to
+ * be set and then tested atomically - as is the case where event groups are
+ * used to create a synchronisation point between multiple tasks (a
+ * 'rendezvous').
+ *
+ * \defgroup EventGroup
+ */
+
+
+
+/**
+ * event_groups.h
+ *
+ * Type by which event groups are referenced.  For example, a call to
+ * xEventGroupCreate() returns an EventGroupHandle_t variable that can then
+ * be used as a parameter to other event group functions.
+ *
+ * \defgroup EventGroupHandle_t EventGroupHandle_t
+ * \ingroup EventGroup
+ */
+typedef void * EventGroupHandle_t;
+
+/* 
+ * The type that holds event bits always matches TickType_t - therefore the
+ * number of bits it holds is set by configUSE_16_BIT_TICKS (16 bits if set to 1,
+ * 32 bits if set to 0. 
+ *
+ * \defgroup EventBits_t EventBits_t
+ * \ingroup EventGroup
+ */
+typedef TickType_t EventBits_t;
+
+/**
+ * event_groups.h
+ *<pre>
+ EventGroupHandle_t xEventGroupCreate( void );
+ </pre>
+ *
+ * Create a new event group.  This function cannot be called from an interrupt.
+ *
+ * Although event groups are not related to ticks, for internal implementation
+ * reasons the number of bits available for use in an event group is dependent
+ * on the configUSE_16_BIT_TICKS setting in FreeRTOSConfig.h.  If
+ * configUSE_16_BIT_TICKS is 1 then each event group contains 8 usable bits (bit
+ * 0 to bit 7).  If configUSE_16_BIT_TICKS is set to 0 then each event group has
+ * 24 usable bits (bit 0 to bit 23).  The EventBits_t type is used to store
+ * event bits within an event group.
+ *
+ * @return If the event group was created then a handle to the event group is
+ * returned.  If there was insufficient FreeRTOS heap available to create the
+ * event group then NULL is returned.  See http://www.freertos.org/a00111.html
+ *
+ * Example usage:
+   <pre>
+	// Declare a variable to hold the created event group.
+	EventGroupHandle_t xCreatedEventGroup;
+
+	// Attempt to create the event group.
+	xCreatedEventGroup = xEventGroupCreate();
+
+	// Was the event group created successfully?
+	if( xCreatedEventGroup == NULL )
+	{
+		// The event group was not created because there was insufficient
+		// FreeRTOS heap available.
+	}
+	else
+	{
+		// The event group was created.
+	}
+   </pre>
+ * \defgroup xEventGroupCreate xEventGroupCreate
+ * \ingroup EventGroup
+ */
+EventGroupHandle_t xEventGroupCreate( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * event_groups.h
+ *<pre>
+	EventBits_t xEventGroupWaitBits( 	EventGroupHandle_t xEventGroup,
+										const EventBits_t uxBitsToWaitFor,
+										const BaseType_t xClearOnExit,
+										const BaseType_t xWaitForAllBits,
+										const TickType_t xTicksToWait );
+ </pre>
+ *
+ * [Potentially] block to wait for one or more bits to be set within a
+ * previously created event group.
+ *
+ * This function cannot be called from an interrupt.
+ *
+ * @param xEventGroup The event group in which the bits are being tested.  The
+ * event group must have previously been created using a call to
+ * xEventGroupCreate().
+ *
+ * @param uxBitsToWaitFor A bitwise value that indicates the bit or bits to test
+ * inside the event group.  For example, to wait for bit 0 and/or bit 2 set
+ * uxBitsToWaitFor to 0x05.  To wait for bits 0 and/or bit 1 and/or bit 2 set
+ * uxBitsToWaitFor to 0x07.  Etc.
+ *
+ * @param xClearOnExit If xClearOnExit is set to pdTRUE then any bits within
+ * uxBitsToWaitFor that are set within the event group will be cleared before
+ * xEventGroupWaitBits() returns if the wait condition was met (if the function
+ * returns for a reason other than a timeout).  If xClearOnExit is set to
+ * pdFALSE then the bits set in the event group are not altered when the call to
+ * xEventGroupWaitBits() returns.
+ *
+ * @param xWaitForAllBits If xWaitForAllBits is set to pdTRUE then
+ * xEventGroupWaitBits() will return when either all the bits in uxBitsToWaitFor
+ * are set or the specified block time expires.  If xWaitForAllBits is set to
+ * pdFALSE then xEventGroupWaitBits() will return when any one of the bits set
+ * in uxBitsToWaitFor is set or the specified block time expires.  The block
+ * time is specified by the xTicksToWait parameter.
+ *
+ * @param xTicksToWait The maximum amount of time (specified in 'ticks') to wait
+ * for one/all (depending on the xWaitForAllBits value) of the bits specified by
+ * uxBitsToWaitFor to become set.
+ *
+ * @return The value of the event group at the time either the bits being waited
+ * for became set, or the block time expired.  Test the return value to know
+ * which bits were set.  If xEventGroupWaitBits() returned because its timeout
+ * expired then not all the bits being waited for will be set.  If
+ * xEventGroupWaitBits() returned because the bits it was waiting for were set
+ * then the returned value is the event group value before any bits were
+ * automatically cleared in the case that xClearOnExit parameter was set to
+ * pdTRUE.
+ *
+ * Example usage:
+   <pre>
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+   const TickType_t xTicksToWait = 100 / portTICK_PERIOD_MS;
+
+		// Wait a maximum of 100ms for either bit 0 or bit 4 to be set within
+		// the event group.  Clear the bits before exiting.
+		uxBits = xEventGroupWaitBits(
+					xEventGroup,	// The event group being tested.
+					BIT_0 | BIT_4,	// The bits within the event group to wait for.
+					pdTRUE,			// BIT_0 and BIT_4 should be cleared before returning.
+					pdFALSE,		// Don't wait for both bits, either bit will do.
+					xTicksToWait );	// Wait a maximum of 100ms for either bit to be set.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// xEventGroupWaitBits() returned because both bits were set.
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// xEventGroupWaitBits() returned because just BIT_0 was set.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// xEventGroupWaitBits() returned because just BIT_4 was set.
+		}
+		else
+		{
+			// xEventGroupWaitBits() returned because xTicksToWait ticks passed
+			// without either BIT_0 or BIT_4 becoming set.
+		}
+   }
+   </pre>
+ * \defgroup xEventGroupWaitBits xEventGroupWaitBits
+ * \ingroup EventGroup
+ */
+EventBits_t xEventGroupWaitBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToWaitFor, const BaseType_t xClearOnExit, const BaseType_t xWaitForAllBits, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+/**
+ * event_groups.h
+ *<pre>
+	EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear );
+ </pre>
+ *
+ * Clear bits within an event group.  This function cannot be called from an
+ * interrupt.
+ *
+ * @param xEventGroup The event group in which the bits are to be cleared.
+ *
+ * @param uxBitsToClear A bitwise value that indicates the bit or bits to clear
+ * in the event group.  For example, to clear bit 3 only, set uxBitsToClear to
+ * 0x08.  To clear bit 3 and bit 0 set uxBitsToClear to 0x09.
+ *
+ * @return The value of the event group before the specified bits were cleared.
+ *
+ * Example usage:
+   <pre>
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+
+		// Clear bit 0 and bit 4 in xEventGroup.
+		uxBits = xEventGroupClearBits(
+								xEventGroup,	// The event group being updated.
+								BIT_0 | BIT_4 );// The bits being cleared.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// Both bit 0 and bit 4 were set before xEventGroupClearBits() was
+			// called.  Both will now be clear (not set).
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// Bit 0 was set before xEventGroupClearBits() was called.  It will
+			// now be clear.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// Bit 4 was set before xEventGroupClearBits() was called.  It will
+			// now be clear.
+		}
+		else
+		{
+			// Neither bit 0 nor bit 4 were set in the first place.
+		}
+   }
+   </pre>
+ * \defgroup xEventGroupClearBits xEventGroupClearBits
+ * \ingroup EventGroup
+ */
+EventBits_t xEventGroupClearBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToClear ) PRIVILEGED_FUNCTION;
+
+/**
+ * event_groups.h
+ *<pre>
+	BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet );
+ </pre>
+ *
+ * A version of xEventGroupClearBits() that can be called from an interrupt.
+ *
+ * Setting bits in an event group is not a deterministic operation because there
+ * are an unknown number of tasks that may be waiting for the bit or bits being
+ * set.  FreeRTOS does not allow nondeterministic operations to be performed
+ * while interrupts are disabled, so protects event groups that are accessed
+ * from tasks by suspending the scheduler rather than disabling interrupts.  As
+ * a result event groups cannot be accessed directly from an interrupt service
+ * routine.  Therefore xEventGroupClearBitsFromISR() sends a message to the 
+ * timer task to have the clear operation performed in the context of the timer 
+ * task.
+ *
+ * @param xEventGroup The event group in which the bits are to be cleared.
+ *
+ * @param uxBitsToClear A bitwise value that indicates the bit or bits to clear.
+ * For example, to clear bit 3 only, set uxBitsToClear to 0x08.  To clear bit 3
+ * and bit 0 set uxBitsToClear to 0x09.
+ *
+ * @return If the request to execute the function was posted successfully then 
+ * pdPASS is returned, otherwise pdFALSE is returned.  pdFALSE will be returned 
+ * if the timer service queue was full.
+ *
+ * Example usage:
+   <pre>
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   // An event group which it is assumed has already been created by a call to
+   // xEventGroupCreate().
+   EventGroupHandle_t xEventGroup;
+
+   void anInterruptHandler( void )
+   {
+		// Clear bit 0 and bit 4 in xEventGroup.
+		xResult = xEventGroupClearBitsFromISR(
+							xEventGroup,	 // The event group being updated.
+							BIT_0 | BIT_4 ); // The bits being set.
+
+		if( xResult == pdPASS )
+		{
+			// The message was posted successfully.
+		}
+  }
+   </pre>
+ * \defgroup xEventGroupSetBitsFromISR xEventGroupSetBitsFromISR
+ * \ingroup EventGroup
+ */
+#if( configUSE_TRACE_FACILITY == 1 )
+	BaseType_t xEventGroupClearBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) PRIVILEGED_FUNCTION;
+#else
+	#define xEventGroupClearBitsFromISR( xEventGroup, uxBitsToClear ) xTimerPendFunctionCallFromISR( vEventGroupClearBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToClear, NULL )
+#endif
+
+/**
+ * event_groups.h
+ *<pre>
+	EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet );
+ </pre>
+ *
+ * Set bits within an event group.
+ * This function cannot be called from an interrupt.  xEventGroupSetBitsFromISR()
+ * is a version that can be called from an interrupt.
+ *
+ * Setting bits in an event group will automatically unblock tasks that are
+ * blocked waiting for the bits.
+ *
+ * @param xEventGroup The event group in which the bits are to be set.
+ *
+ * @param uxBitsToSet A bitwise value that indicates the bit or bits to set.
+ * For example, to set bit 3 only, set uxBitsToSet to 0x08.  To set bit 3
+ * and bit 0 set uxBitsToSet to 0x09.
+ *
+ * @return The value of the event group at the time the call to
+ * xEventGroupSetBits() returns.  There are two reasons why the returned value
+ * might have the bits specified by the uxBitsToSet parameter cleared.  First,
+ * if setting a bit results in a task that was waiting for the bit leaving the
+ * blocked state then it is possible the bit will be cleared automatically
+ * (see the xClearBitOnExit parameter of xEventGroupWaitBits()).  Second, any
+ * unblocked (or otherwise Ready state) task that has a priority above that of
+ * the task that called xEventGroupSetBits() will execute and may change the
+ * event group value before the call to xEventGroupSetBits() returns.
+ *
+ * Example usage:
+   <pre>
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   void aFunction( EventGroupHandle_t xEventGroup )
+   {
+   EventBits_t uxBits;
+
+		// Set bit 0 and bit 4 in xEventGroup.
+		uxBits = xEventGroupSetBits(
+							xEventGroup,	// The event group being updated.
+							BIT_0 | BIT_4 );// The bits being set.
+
+		if( ( uxBits & ( BIT_0 | BIT_4 ) ) == ( BIT_0 | BIT_4 ) )
+		{
+			// Both bit 0 and bit 4 remained set when the function returned.
+		}
+		else if( ( uxBits & BIT_0 ) != 0 )
+		{
+			// Bit 0 remained set when the function returned, but bit 4 was
+			// cleared.  It might be that bit 4 was cleared automatically as a
+			// task that was waiting for bit 4 was removed from the Blocked
+			// state.
+		}
+		else if( ( uxBits & BIT_4 ) != 0 )
+		{
+			// Bit 4 remained set when the function returned, but bit 0 was
+			// cleared.  It might be that bit 0 was cleared automatically as a
+			// task that was waiting for bit 0 was removed from the Blocked
+			// state.
+		}
+		else
+		{
+			// Neither bit 0 nor bit 4 remained set.  It might be that a task
+			// was waiting for both of the bits to be set, and the bits were
+			// cleared as the task left the Blocked state.
+		}
+   }
+   </pre>
+ * \defgroup xEventGroupSetBits xEventGroupSetBits
+ * \ingroup EventGroup
+ */
+EventBits_t xEventGroupSetBits( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet ) PRIVILEGED_FUNCTION;
+
+/**
+ * event_groups.h
+ *<pre>
+	BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken );
+ </pre>
+ *
+ * A version of xEventGroupSetBits() that can be called from an interrupt.
+ *
+ * Setting bits in an event group is not a deterministic operation because there
+ * are an unknown number of tasks that may be waiting for the bit or bits being
+ * set.  FreeRTOS does not allow nondeterministic operations to be performed in
+ * interrupts or from critical sections.  Therefore xEventGroupSetBitFromISR()
+ * sends a message to the timer task to have the set operation performed in the
+ * context of the timer task - where a scheduler lock is used in place of a
+ * critical section.
+ *
+ * @param xEventGroup The event group in which the bits are to be set.
+ *
+ * @param uxBitsToSet A bitwise value that indicates the bit or bits to set.
+ * For example, to set bit 3 only, set uxBitsToSet to 0x08.  To set bit 3
+ * and bit 0 set uxBitsToSet to 0x09.
+ *
+ * @param pxHigherPriorityTaskWoken As mentioned above, calling this function
+ * will result in a message being sent to the timer daemon task.  If the
+ * priority of the timer daemon task is higher than the priority of the
+ * currently running task (the task the interrupt interrupted) then
+ * *pxHigherPriorityTaskWoken will be set to pdTRUE by
+ * xEventGroupSetBitsFromISR(), indicating that a context switch should be
+ * requested before the interrupt exits.  For that reason
+ * *pxHigherPriorityTaskWoken must be initialised to pdFALSE.  See the
+ * example code below.
+ *
+ * @return If the request to execute the function was posted successfully then 
+ * pdPASS is returned, otherwise pdFALSE is returned.  pdFALSE will be returned 
+ * if the timer service queue was full.
+ *
+ * Example usage:
+   <pre>
+   #define BIT_0	( 1 << 0 )
+   #define BIT_4	( 1 << 4 )
+
+   // An event group which it is assumed has already been created by a call to
+   // xEventGroupCreate().
+   EventGroupHandle_t xEventGroup;
+
+   void anInterruptHandler( void )
+   {
+   BaseType_t xHigherPriorityTaskWoken, xResult;
+
+		// xHigherPriorityTaskWoken must be initialised to pdFALSE.
+		xHigherPriorityTaskWoken = pdFALSE;
+
+		// Set bit 0 and bit 4 in xEventGroup.
+		xResult = xEventGroupSetBitsFromISR(
+							xEventGroup,	// The event group being updated.
+							BIT_0 | BIT_4   // The bits being set.
+							&xHigherPriorityTaskWoken );
+
+		// Was the message posted successfully?
+		if( xResult == pdPASS )
+		{
+			// If xHigherPriorityTaskWoken is now set to pdTRUE then a context
+			// switch should be requested.  The macro used is port specific and 
+			// will be either portYIELD_FROM_ISR() or portEND_SWITCHING_ISR() - 
+			// refer to the documentation page for the port being used.
+			portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+		}
+  }
+   </pre>
+ * \defgroup xEventGroupSetBitsFromISR xEventGroupSetBitsFromISR
+ * \ingroup EventGroup
+ */
+#if( configUSE_TRACE_FACILITY == 1 )
+	BaseType_t xEventGroupSetBitsFromISR( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+#else
+	#define xEventGroupSetBitsFromISR( xEventGroup, uxBitsToSet, pxHigherPriorityTaskWoken ) xTimerPendFunctionCallFromISR( vEventGroupSetBitsCallback, ( void * ) xEventGroup, ( uint32_t ) uxBitsToSet, pxHigherPriorityTaskWoken )
+#endif
+
+/**
+ * event_groups.h
+ *<pre>
+	EventBits_t xEventGroupSync(	EventGroupHandle_t xEventGroup,
+									const EventBits_t uxBitsToSet,
+									const EventBits_t uxBitsToWaitFor,
+									TickType_t xTicksToWait );
+ </pre>
+ *
+ * Atomically set bits within an event group, then wait for a combination of
+ * bits to be set within the same event group.  This functionality is typically
+ * used to synchronise multiple tasks, where each task has to wait for the other
+ * tasks to reach a synchronisation point before proceeding.
+ *
+ * This function cannot be used from an interrupt.
+ *
+ * The function will return before its block time expires if the bits specified
+ * by the uxBitsToWait parameter are set, or become set within that time.  In
+ * this case all the bits specified by uxBitsToWait will be automatically
+ * cleared before the function returns.
+ *
+ * @param xEventGroup The event group in which the bits are being tested.  The
+ * event group must have previously been created using a call to
+ * xEventGroupCreate().
+ *
+ * @param uxBitsToSet The bits to set in the event group before determining
+ * if, and possibly waiting for, all the bits specified by the uxBitsToWait
+ * parameter are set.
+ *
+ * @param uxBitsToWaitFor A bitwise value that indicates the bit or bits to test
+ * inside the event group.  For example, to wait for bit 0 and bit 2 set
+ * uxBitsToWaitFor to 0x05.  To wait for bits 0 and bit 1 and bit 2 set
+ * uxBitsToWaitFor to 0x07.  Etc.
+ *
+ * @param xTicksToWait The maximum amount of time (specified in 'ticks') to wait
+ * for all of the bits specified by uxBitsToWaitFor to become set.
+ *
+ * @return The value of the event group at the time either the bits being waited
+ * for became set, or the block time expired.  Test the return value to know
+ * which bits were set.  If xEventGroupSync() returned because its timeout
+ * expired then not all the bits being waited for will be set.  If
+ * xEventGroupSync() returned because all the bits it was waiting for were
+ * set then the returned value is the event group value before any bits were
+ * automatically cleared.
+ *
+ * Example usage:
+ <pre>
+ // Bits used by the three tasks.
+ #define TASK_0_BIT		( 1 << 0 )
+ #define TASK_1_BIT		( 1 << 1 )
+ #define TASK_2_BIT		( 1 << 2 )
+
+ #define ALL_SYNC_BITS ( TASK_0_BIT | TASK_1_BIT | TASK_2_BIT )
+
+ // Use an event group to synchronise three tasks.  It is assumed this event
+ // group has already been created elsewhere.
+ EventGroupHandle_t xEventBits;
+
+ void vTask0( void *pvParameters )
+ {
+ EventBits_t uxReturn;
+ TickType_t xTicksToWait = 100 / portTICK_PERIOD_MS;
+
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 0 in the event flag to note this task has reached the
+		// sync point.  The other two tasks will set the other two bits defined
+		// by ALL_SYNC_BITS.  All three tasks have reached the synchronisation
+		// point when all the ALL_SYNC_BITS are set.  Wait a maximum of 100ms
+		// for this to happen.
+		uxReturn = xEventGroupSync( xEventBits, TASK_0_BIT, ALL_SYNC_BITS, xTicksToWait );
+
+		if( ( uxReturn & ALL_SYNC_BITS ) == ALL_SYNC_BITS )
+		{
+			// All three tasks reached the synchronisation point before the call
+			// to xEventGroupSync() timed out.
+		}
+	}
+ }
+
+ void vTask1( void *pvParameters )
+ {
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 1 in the event flag to note this task has reached the
+		// synchronisation point.  The other two tasks will set the other two
+		// bits defined by ALL_SYNC_BITS.  All three tasks have reached the
+		// synchronisation point when all the ALL_SYNC_BITS are set.  Wait
+		// indefinitely for this to happen.
+		xEventGroupSync( xEventBits, TASK_1_BIT, ALL_SYNC_BITS, portMAX_DELAY );
+
+		// xEventGroupSync() was called with an indefinite block time, so
+		// this task will only reach here if the syncrhonisation was made by all
+		// three tasks, so there is no need to test the return value.
+	 }
+ }
+
+ void vTask2( void *pvParameters )
+ {
+	 for( ;; )
+	 {
+		// Perform task functionality here.
+
+		// Set bit 2 in the event flag to note this task has reached the
+		// synchronisation point.  The other two tasks will set the other two
+		// bits defined by ALL_SYNC_BITS.  All three tasks have reached the
+		// synchronisation point when all the ALL_SYNC_BITS are set.  Wait
+		// indefinitely for this to happen.
+		xEventGroupSync( xEventBits, TASK_2_BIT, ALL_SYNC_BITS, portMAX_DELAY );
+
+		// xEventGroupSync() was called with an indefinite block time, so
+		// this task will only reach here if the syncrhonisation was made by all
+		// three tasks, so there is no need to test the return value.
+	}
+ }
+
+ </pre>
+ * \defgroup xEventGroupSync xEventGroupSync
+ * \ingroup EventGroup
+ */
+EventBits_t xEventGroupSync( EventGroupHandle_t xEventGroup, const EventBits_t uxBitsToSet, const EventBits_t uxBitsToWaitFor, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+
+/**
+ * event_groups.h
+ *<pre>
+	EventBits_t xEventGroupGetBits( EventGroupHandle_t xEventGroup );
+ </pre>
+ *
+ * Returns the current value of the bits in an event group.  This function
+ * cannot be used from an interrupt.
+ *
+ * @param xEventGroup The event group being queried.
+ *
+ * @return The event group bits at the time xEventGroupGetBits() was called.
+ *
+ * \defgroup xEventGroupGetBits xEventGroupGetBits
+ * \ingroup EventGroup
+ */
+#define xEventGroupGetBits( xEventGroup ) xEventGroupClearBits( xEventGroup, 0 )
+
+/**
+ * event_groups.h
+ *<pre>
+	EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup );
+ </pre>
+ *
+ * A version of xEventGroupGetBits() that can be called from an ISR.
+ *
+ * @param xEventGroup The event group being queried.
+ *
+ * @return The event group bits at the time xEventGroupGetBitsFromISR() was called.
+ *
+ * \defgroup xEventGroupGetBitsFromISR xEventGroupGetBitsFromISR
+ * \ingroup EventGroup
+ */
+EventBits_t xEventGroupGetBitsFromISR( EventGroupHandle_t xEventGroup ) PRIVILEGED_FUNCTION;
+
+/**
+ * event_groups.h
+ *<pre>
+	void xEventGroupDelete( EventGroupHandle_t xEventGroup );
+ </pre>
+ *
+ * Delete an event group that was previously created by a call to
+ * xEventGroupCreate().  Tasks that are blocked on the event group will be
+ * unblocked and obtain 0 as the event group's value.
+ *
+ * @param xEventGroup The event group being deleted.
+ */
+void vEventGroupDelete( EventGroupHandle_t xEventGroup ) PRIVILEGED_FUNCTION;
+
+/* For internal use only. */
+void vEventGroupSetBitsCallback( void *pvEventGroup, const uint32_t ulBitsToSet ) PRIVILEGED_FUNCTION;
+void vEventGroupClearBitsCallback( void *pvEventGroup, const uint32_t ulBitsToClear ) PRIVILEGED_FUNCTION;
+
+#if (configUSE_TRACE_FACILITY == 1)
+	UBaseType_t uxEventGroupGetNumber( void* xEventGroup ) PRIVILEGED_FUNCTION;
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* EVENT_GROUPS_H */
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/list.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/list.h
new file mode 100644
index 0000000000000000000000000000000000000000..75d391d4ce4e4d281ea1a9eeacee36fb57fd31ed
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/list.h
@@ -0,0 +1,453 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/*
+ * This is the list implementation used by the scheduler.  While it is tailored
+ * heavily for the schedulers needs, it is also available for use by
+ * application code.
+ *
+ * list_ts can only store pointers to list_item_ts.  Each ListItem_t contains a
+ * numeric value (xItemValue).  Most of the time the lists are sorted in
+ * descending item value order.
+ *
+ * Lists are created already containing one list item.  The value of this
+ * item is the maximum possible that can be stored, it is therefore always at
+ * the end of the list and acts as a marker.  The list member pxHead always
+ * points to this marker - even though it is at the tail of the list.  This
+ * is because the tail contains a wrap back pointer to the true head of
+ * the list.
+ *
+ * In addition to it's value, each list item contains a pointer to the next
+ * item in the list (pxNext), a pointer to the list it is in (pxContainer)
+ * and a pointer to back to the object that contains it.  These later two
+ * pointers are included for efficiency of list manipulation.  There is
+ * effectively a two way link between the object containing the list item and
+ * the list item itself.
+ *
+ *
+ * \page ListIntroduction List Implementation
+ * \ingroup FreeRTOSIntro
+ */
+
+#ifndef INC_FREERTOS_H
+	#error FreeRTOS.h must be included before list.h
+#endif
+
+#ifndef LIST_H
+#define LIST_H
+
+/*
+ * The list structure members are modified from within interrupts, and therefore
+ * by rights should be declared volatile.  However, they are only modified in a
+ * functionally atomic way (within critical sections of with the scheduler
+ * suspended) and are either passed by reference into a function or indexed via
+ * a volatile variable.  Therefore, in all use cases tested so far, the volatile
+ * qualifier can be omitted in order to provide a moderate performance
+ * improvement without adversely affecting functional behaviour.  The assembly
+ * instructions generated by the IAR, ARM and GCC compilers when the respective
+ * compiler's options were set for maximum optimisation has been inspected and
+ * deemed to be as intended.  That said, as compiler technology advances, and
+ * especially if aggressive cross module optimisation is used (a use case that
+ * has not been exercised to any great extend) then it is feasible that the
+ * volatile qualifier will be needed for correct optimisation.  It is expected
+ * that a compiler removing essential code because, without the volatile
+ * qualifier on the list structure members and with aggressive cross module
+ * optimisation, the compiler deemed the code unnecessary will result in
+ * complete and obvious failure of the scheduler.  If this is ever experienced
+ * then the volatile qualifier can be inserted in the relevant places within the
+ * list structures by simply defining configLIST_VOLATILE to volatile in
+ * FreeRTOSConfig.h (as per the example at the bottom of this comment block).
+ * If configLIST_VOLATILE is not defined then the preprocessor directives below
+ * will simply #define configLIST_VOLATILE away completely.
+ *
+ * To use volatile list structure members then add the following line to
+ * FreeRTOSConfig.h (without the quotes):
+ * "#define configLIST_VOLATILE volatile"
+ */
+#ifndef configLIST_VOLATILE
+	#define configLIST_VOLATILE
+#endif /* configSUPPORT_CROSS_MODULE_OPTIMISATION */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Macros that can be used to place known values within the list structures,
+then check that the known values do not get corrupted during the execution of
+the application.   These may catch the list data structures being overwritten in
+memory.  They will not catch data errors caused by incorrect configuration or
+use of FreeRTOS.*/
+#if( configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES == 0 )
+	/* Define the macros to do nothing. */
+	#define listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE
+	#define listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE
+	#define listFIRST_LIST_INTEGRITY_CHECK_VALUE
+	#define listSECOND_LIST_INTEGRITY_CHECK_VALUE
+	#define listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem )
+	#define listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem )
+	#define listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList )
+	#define listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList )
+	#define listTEST_LIST_ITEM_INTEGRITY( pxItem )
+	#define listTEST_LIST_INTEGRITY( pxList )
+#else
+	/* Define macros that add new members into the list structures. */
+	#define listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE				TickType_t xListItemIntegrityValue1;
+	#define listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE				TickType_t xListItemIntegrityValue2;
+	#define listFIRST_LIST_INTEGRITY_CHECK_VALUE					TickType_t xListIntegrityValue1;
+	#define listSECOND_LIST_INTEGRITY_CHECK_VALUE					TickType_t xListIntegrityValue2;
+
+	/* Define macros that set the new structure members to known values. */
+	#define listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem )		( pxItem )->xListItemIntegrityValue1 = pdINTEGRITY_CHECK_VALUE
+	#define listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem )	( pxItem )->xListItemIntegrityValue2 = pdINTEGRITY_CHECK_VALUE
+	#define listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList )		( pxList )->xListIntegrityValue1 = pdINTEGRITY_CHECK_VALUE
+	#define listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList )		( pxList )->xListIntegrityValue2 = pdINTEGRITY_CHECK_VALUE
+
+	/* Define macros that will assert if one of the structure members does not
+	contain its expected value. */
+	#define listTEST_LIST_ITEM_INTEGRITY( pxItem )		configASSERT( ( ( pxItem )->xListItemIntegrityValue1 == pdINTEGRITY_CHECK_VALUE ) && ( ( pxItem )->xListItemIntegrityValue2 == pdINTEGRITY_CHECK_VALUE ) )
+	#define listTEST_LIST_INTEGRITY( pxList )			configASSERT( ( ( pxList )->xListIntegrityValue1 == pdINTEGRITY_CHECK_VALUE ) && ( ( pxList )->xListIntegrityValue2 == pdINTEGRITY_CHECK_VALUE ) )
+#endif /* configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES */
+
+
+/*
+ * Definition of the only type of object that a list can contain.
+ */
+struct xLIST_ITEM
+{
+	listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE			/*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
+	configLIST_VOLATILE TickType_t xItemValue;			/*< The value being listed.  In most cases this is used to sort the list in descending order. */
+	struct xLIST_ITEM * configLIST_VOLATILE pxNext;		/*< Pointer to the next ListItem_t in the list. */
+	struct xLIST_ITEM * configLIST_VOLATILE pxPrevious;	/*< Pointer to the previous ListItem_t in the list. */
+	void * pvOwner;										/*< Pointer to the object (normally a TCB) that contains the list item.  There is therefore a two way link between the object containing the list item and the list item itself. */
+	void * configLIST_VOLATILE pvContainer;				/*< Pointer to the list in which this list item is placed (if any). */
+	listSECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE			/*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
+};
+typedef struct xLIST_ITEM ListItem_t;					/* For some reason lint wants this as two separate definitions. */
+
+struct xMINI_LIST_ITEM
+{
+	listFIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE			/*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
+	configLIST_VOLATILE TickType_t xItemValue;
+	struct xLIST_ITEM * configLIST_VOLATILE pxNext;
+	struct xLIST_ITEM * configLIST_VOLATILE pxPrevious;
+};
+typedef struct xMINI_LIST_ITEM MiniListItem_t;
+
+/*
+ * Definition of the type of queue used by the scheduler.
+ */
+typedef struct xLIST
+{
+	listFIRST_LIST_INTEGRITY_CHECK_VALUE				/*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
+	configLIST_VOLATILE UBaseType_t uxNumberOfItems;
+	ListItem_t * configLIST_VOLATILE pxIndex;			/*< Used to walk through the list.  Points to the last item returned by a call to listGET_OWNER_OF_NEXT_ENTRY (). */
+	MiniListItem_t xListEnd;							/*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */
+	listSECOND_LIST_INTEGRITY_CHECK_VALUE				/*< Set to a known value if configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
+} List_t;
+
+/*
+ * Access macro to set the owner of a list item.  The owner of a list item
+ * is the object (usually a TCB) that contains the list item.
+ *
+ * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER
+ * \ingroup LinkedList
+ */
+#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner )		( ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) )
+
+/*
+ * Access macro to get the owner of a list item.  The owner of a list item
+ * is the object (usually a TCB) that contains the list item.
+ *
+ * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER
+ * \ingroup LinkedList
+ */
+#define listGET_LIST_ITEM_OWNER( pxListItem )	( ( pxListItem )->pvOwner )
+
+/*
+ * Access macro to set the value of the list item.  In most cases the value is
+ * used to sort the list in descending order.
+ *
+ * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE
+ * \ingroup LinkedList
+ */
+#define listSET_LIST_ITEM_VALUE( pxListItem, xValue )	( ( pxListItem )->xItemValue = ( xValue ) )
+
+/*
+ * Access macro to retrieve the value of the list item.  The value can
+ * represent anything - for example the priority of a task, or the time at
+ * which a task should be unblocked.
+ *
+ * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE
+ * \ingroup LinkedList
+ */
+#define listGET_LIST_ITEM_VALUE( pxListItem )	( ( pxListItem )->xItemValue )
+
+/*
+ * Access macro to retrieve the value of the list item at the head of a given
+ * list.
+ *
+ * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE
+ * \ingroup LinkedList
+ */
+#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList )	( ( ( pxList )->xListEnd ).pxNext->xItemValue )
+
+/*
+ * Return the list item at the head of the list.
+ *
+ * \page listGET_HEAD_ENTRY listGET_HEAD_ENTRY
+ * \ingroup LinkedList
+ */
+#define listGET_HEAD_ENTRY( pxList )	( ( ( pxList )->xListEnd ).pxNext )
+
+/*
+ * Return the list item at the head of the list.
+ *
+ * \page listGET_NEXT listGET_NEXT
+ * \ingroup LinkedList
+ */
+#define listGET_NEXT( pxListItem )	( ( pxListItem )->pxNext )
+
+/*
+ * Return the list item that marks the end of the list
+ *
+ * \page listGET_END_MARKER listGET_END_MARKER
+ * \ingroup LinkedList
+ */
+#define listGET_END_MARKER( pxList )	( ( ListItem_t const * ) ( &( ( pxList )->xListEnd ) ) )
+
+/*
+ * Access macro to determine if a list contains any items.  The macro will
+ * only have the value true if the list is empty.
+ *
+ * \page listLIST_IS_EMPTY listLIST_IS_EMPTY
+ * \ingroup LinkedList
+ */
+#define listLIST_IS_EMPTY( pxList )	( ( BaseType_t ) ( ( pxList )->uxNumberOfItems == ( UBaseType_t ) 0 ) )
+
+/*
+ * Access macro to return the number of items in the list.
+ */
+#define listCURRENT_LIST_LENGTH( pxList )	( ( pxList )->uxNumberOfItems )
+
+/*
+ * Access function to obtain the owner of the next entry in a list.
+ *
+ * The list member pxIndex is used to walk through a list.  Calling
+ * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list
+ * and returns that entry's pxOwner parameter.  Using multiple calls to this
+ * function it is therefore possible to move through every item contained in
+ * a list.
+ *
+ * The pxOwner parameter of a list item is a pointer to the object that owns
+ * the list item.  In the scheduler this is normally a task control block.
+ * The pxOwner parameter effectively creates a two way link between the list
+ * item and its owner.
+ *
+ * @param pxTCB pxTCB is set to the address of the owner of the next list item.
+ * @param pxList The list from which the next item owner is to be returned.
+ *
+ * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY
+ * \ingroup LinkedList
+ */
+#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList )										\
+{																							\
+List_t * const pxConstList = ( pxList );													\
+	/* Increment the index to the next item and return the item, ensuring */				\
+	/* we don't return the marker used at the end of the list.  */							\
+	( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext;							\
+	if( ( void * ) ( pxConstList )->pxIndex == ( void * ) &( ( pxConstList )->xListEnd ) )	\
+	{																						\
+		( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext;						\
+	}																						\
+	( pxTCB ) = ( pxConstList )->pxIndex->pvOwner;											\
+}
+
+
+/*
+ * Access function to obtain the owner of the first entry in a list.  Lists
+ * are normally sorted in ascending item value order.
+ *
+ * This function returns the pxOwner member of the first item in the list.
+ * The pxOwner parameter of a list item is a pointer to the object that owns
+ * the list item.  In the scheduler this is normally a task control block.
+ * The pxOwner parameter effectively creates a two way link between the list
+ * item and its owner.
+ *
+ * @param pxList The list from which the owner of the head item is to be
+ * returned.
+ *
+ * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY
+ * \ingroup LinkedList
+ */
+#define listGET_OWNER_OF_HEAD_ENTRY( pxList )  ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner )
+
+/*
+ * Check to see if a list item is within a list.  The list item maintains a
+ * "container" pointer that points to the list it is in.  All this macro does
+ * is check to see if the container and the list match.
+ *
+ * @param pxList The list we want to know if the list item is within.
+ * @param pxListItem The list item we want to know if is in the list.
+ * @return pdTRUE if the list item is in the list, otherwise pdFALSE.
+ */
+#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( BaseType_t ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) )
+
+/*
+ * Return the list a list item is contained within (referenced from).
+ *
+ * @param pxListItem The list item being queried.
+ * @return A pointer to the List_t object that references the pxListItem
+ */
+#define listLIST_ITEM_CONTAINER( pxListItem ) ( ( pxListItem )->pvContainer )
+
+/*
+ * This provides a crude means of knowing if a list has been initialised, as
+ * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise()
+ * function.
+ */
+#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY )
+
+/*
+ * Must be called before a list is used!  This initialises all the members
+ * of the list structure and inserts the xListEnd item into the list as a
+ * marker to the back of the list.
+ *
+ * @param pxList Pointer to the list being initialised.
+ *
+ * \page vListInitialise vListInitialise
+ * \ingroup LinkedList
+ */
+void vListInitialise( List_t * const pxList ) PRIVILEGED_FUNCTION;
+
+/*
+ * Must be called before a list item is used.  This sets the list container to
+ * null so the item does not think that it is already contained in a list.
+ *
+ * @param pxItem Pointer to the list item being initialised.
+ *
+ * \page vListInitialiseItem vListInitialiseItem
+ * \ingroup LinkedList
+ */
+void vListInitialiseItem( ListItem_t * const pxItem ) PRIVILEGED_FUNCTION;
+
+/*
+ * Insert a list item into a list.  The item will be inserted into the list in
+ * a position determined by its item value (descending item value order).
+ *
+ * @param pxList The list into which the item is to be inserted.
+ *
+ * @param pxNewListItem The item that is to be placed in the list.
+ *
+ * \page vListInsert vListInsert
+ * \ingroup LinkedList
+ */
+void vListInsert( List_t * const pxList, ListItem_t * const pxNewListItem ) PRIVILEGED_FUNCTION;
+
+/*
+ * Insert a list item into a list.  The item will be inserted in a position
+ * such that it will be the last item within the list returned by multiple
+ * calls to listGET_OWNER_OF_NEXT_ENTRY.
+ *
+ * The list member pvIndex is used to walk through a list.  Calling
+ * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list.
+ * Placing an item in a list using vListInsertEnd effectively places the item
+ * in the list position pointed to by pvIndex.  This means that every other
+ * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before
+ * the pvIndex parameter again points to the item being inserted.
+ *
+ * @param pxList The list into which the item is to be inserted.
+ *
+ * @param pxNewListItem The list item to be inserted into the list.
+ *
+ * \page vListInsertEnd vListInsertEnd
+ * \ingroup LinkedList
+ */
+void vListInsertEnd( List_t * const pxList, ListItem_t * const pxNewListItem ) PRIVILEGED_FUNCTION;
+
+/*
+ * Remove an item from a list.  The list item has a pointer to the list that
+ * it is in, so only the list item need be passed into the function.
+ *
+ * @param uxListRemove The item to be removed.  The item will remove itself from
+ * the list pointed to by it's pxContainer parameter.
+ *
+ * @return The number of items that remain in the list after the list item has
+ * been removed.
+ *
+ * \page uxListRemove uxListRemove
+ * \ingroup LinkedList
+ */
+UBaseType_t uxListRemove( ListItem_t * const pxItemToRemove ) PRIVILEGED_FUNCTION;
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/mpu_wrappers.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/mpu_wrappers.h
new file mode 100644
index 0000000000000000000000000000000000000000..5b2ad474d848a7d690dc14dacb2edbe61b9d66c6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/mpu_wrappers.h
@@ -0,0 +1,177 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef MPU_WRAPPERS_H
+#define MPU_WRAPPERS_H
+
+/* This file redefines API functions to be called through a wrapper macro, but
+only for ports that are using the MPU. */
+#ifdef portUSING_MPU_WRAPPERS
+
+	/* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is
+	included from queue.c or task.c to prevent it from having an effect within
+	those files. */
+	#ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+		#define xTaskGenericCreate				MPU_xTaskGenericCreate
+		#define vTaskAllocateMPURegions			MPU_vTaskAllocateMPURegions
+		#define vTaskDelete						MPU_vTaskDelete
+		#define vTaskDelayUntil					MPU_vTaskDelayUntil
+		#define vTaskDelay						MPU_vTaskDelay
+		#define uxTaskPriorityGet				MPU_uxTaskPriorityGet
+		#define vTaskPrioritySet				MPU_vTaskPrioritySet
+		#define eTaskGetState					MPU_eTaskGetState
+		#define vTaskSuspend					MPU_vTaskSuspend
+		#define vTaskResume						MPU_vTaskResume
+		#define vTaskSuspendAll					MPU_vTaskSuspendAll
+		#define xTaskResumeAll					MPU_xTaskResumeAll
+		#define xTaskGetTickCount				MPU_xTaskGetTickCount
+		#define uxTaskGetNumberOfTasks			MPU_uxTaskGetNumberOfTasks
+		#define vTaskList						MPU_vTaskList
+		#define vTaskGetRunTimeStats			MPU_vTaskGetRunTimeStats
+		#define vTaskSetApplicationTaskTag		MPU_vTaskSetApplicationTaskTag
+		#define xTaskGetApplicationTaskTag		MPU_xTaskGetApplicationTaskTag
+		#define xTaskCallApplicationTaskHook	MPU_xTaskCallApplicationTaskHook
+		#define uxTaskGetStackHighWaterMark		MPU_uxTaskGetStackHighWaterMark
+		#define xTaskGetCurrentTaskHandle		MPU_xTaskGetCurrentTaskHandle
+		#define xTaskGetSchedulerState			MPU_xTaskGetSchedulerState
+		#define xTaskGetIdleTaskHandle			MPU_xTaskGetIdleTaskHandle
+		#define uxTaskGetSystemState			MPU_uxTaskGetSystemState
+		#define xTaskGenericNotify				MPU_xTaskGenericNotify
+		#define xTaskNotifyWait					MPU_xTaskNotifyWait
+		#define ulTaskNotifyTake				MPU_ulTaskNotifyTake
+
+		#define xQueueGenericCreate				MPU_xQueueGenericCreate
+		#define xQueueCreateMutex				MPU_xQueueCreateMutex
+		#define xQueueGiveMutexRecursive		MPU_xQueueGiveMutexRecursive
+		#define xQueueTakeMutexRecursive		MPU_xQueueTakeMutexRecursive
+		#define xQueueCreateCountingSemaphore	MPU_xQueueCreateCountingSemaphore
+		#define xQueueGenericSend				MPU_xQueueGenericSend
+		#define xQueueAltGenericSend			MPU_xQueueAltGenericSend
+		#define xQueueAltGenericReceive			MPU_xQueueAltGenericReceive
+		#define xQueueGenericReceive			MPU_xQueueGenericReceive
+		#define uxQueueMessagesWaiting			MPU_uxQueueMessagesWaiting
+		#define vQueueDelete					MPU_vQueueDelete
+		#define xQueueGenericReset				MPU_xQueueGenericReset
+		#define xQueueCreateSet					MPU_xQueueCreateSet
+		#define xQueueSelectFromSet				MPU_xQueueSelectFromSet
+		#define xQueueAddToSet					MPU_xQueueAddToSet
+		#define xQueueRemoveFromSet				MPU_xQueueRemoveFromSet
+		#define xQueueGetMutexHolder			MPU_xQueueGetMutexHolder
+		#define xQueueGetMutexHolder			MPU_xQueueGetMutexHolder
+
+		#define pvPortMalloc					MPU_pvPortMalloc
+		#define vPortFree						MPU_vPortFree
+		#define xPortGetFreeHeapSize			MPU_xPortGetFreeHeapSize
+		#define vPortInitialiseBlocks			MPU_vPortInitialiseBlocks
+		#define xPortGetMinimumEverFreeHeapSize	MPU_xPortGetMinimumEverFreeHeapSize
+
+		#if configQUEUE_REGISTRY_SIZE > 0
+			#define vQueueAddToRegistry				MPU_vQueueAddToRegistry
+			#define vQueueUnregisterQueue			MPU_vQueueUnregisterQueue
+		#endif
+
+		#define xTimerCreate					MPU_xTimerCreate
+		#define pvTimerGetTimerID				MPU_pvTimerGetTimerID
+		#define vTimerSetTimerID				MPU_vTimerSetTimerID
+		#define xTimerIsTimerActive				MPU_xTimerIsTimerActive
+		#define xTimerGetTimerDaemonTaskHandle	MPU_xTimerGetTimerDaemonTaskHandle
+		#define xTimerPendFunctionCall			MPU_xTimerPendFunctionCall
+		#define pcTimerGetTimerName				MPU_pcTimerGetTimerName
+		#define xTimerGenericCommand			MPU_xTimerGenericCommand
+
+		#define xEventGroupCreate				MPU_xEventGroupCreate
+		#define xEventGroupWaitBits				MPU_xEventGroupWaitBits
+		#define xEventGroupClearBits			MPU_xEventGroupClearBits
+		#define xEventGroupSetBits				MPU_xEventGroupSetBits
+		#define xEventGroupSync					MPU_xEventGroupSync
+		#define vEventGroupDelete				MPU_vEventGroupDelete
+
+		/* Remove the privileged function macro. */
+		#define PRIVILEGED_FUNCTION
+
+	#else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */
+
+		/* Ensure API functions go in the privileged execution section. */
+		#define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions")))
+		#define PRIVILEGED_DATA __attribute__((section("privileged_data")))
+
+	#endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */
+
+#else /* portUSING_MPU_WRAPPERS */
+
+	#define PRIVILEGED_FUNCTION
+	#define PRIVILEGED_DATA
+	#define portUSING_MPU_WRAPPERS 0
+
+#endif /* portUSING_MPU_WRAPPERS */
+
+
+#endif /* MPU_WRAPPERS_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/portable.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/portable.h
new file mode 100644
index 0000000000000000000000000000000000000000..cd6a9344c4d2b7ea59069ca8eef52bc3c14d5db6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/portable.h
@@ -0,0 +1,207 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/*-----------------------------------------------------------
+ * Portable layer API.  Each function must be defined for each port.
+ *----------------------------------------------------------*/
+
+#ifndef PORTABLE_H
+#define PORTABLE_H
+
+/* Each FreeRTOS port has a unique portmacro.h header file.  Originally a
+pre-processor definition was used to ensure the pre-processor found the correct
+portmacro.h file for the port being used.  That scheme was deprecated in favour
+of setting the compiler's include path such that it found the correct
+portmacro.h file - removing the need for the constant and allowing the
+portmacro.h file to be located anywhere in relation to the port being used.
+Purely for reasons of backward compatibility the old method is still valid, but
+to make it clear that new projects should not use it, support for the port
+specific constants has been moved into the deprecated_definitions.h header
+file. */
+#include "deprecated_definitions.h"
+
+/* If portENTER_CRITICAL is not defined then including deprecated_definitions.h
+did not result in a portmacro.h header file being included - and it should be
+included here.  In this case the path to the correct portmacro.h header file
+must be set in the compiler's include path. */
+#ifndef portENTER_CRITICAL
+	#include "portmacro.h"
+#endif
+
+#if portBYTE_ALIGNMENT == 32
+	#define portBYTE_ALIGNMENT_MASK ( 0x001f )
+#endif
+
+#if portBYTE_ALIGNMENT == 16
+	#define portBYTE_ALIGNMENT_MASK ( 0x000f )
+#endif
+
+#if portBYTE_ALIGNMENT == 8
+	#define portBYTE_ALIGNMENT_MASK ( 0x0007 )
+#endif
+
+#if portBYTE_ALIGNMENT == 4
+	#define portBYTE_ALIGNMENT_MASK	( 0x0003 )
+#endif
+
+#if portBYTE_ALIGNMENT == 2
+	#define portBYTE_ALIGNMENT_MASK	( 0x0001 )
+#endif
+
+#if portBYTE_ALIGNMENT == 1
+	#define portBYTE_ALIGNMENT_MASK	( 0x0000 )
+#endif
+
+#ifndef portBYTE_ALIGNMENT_MASK
+	#error "Invalid portBYTE_ALIGNMENT definition"
+#endif
+
+#ifndef portNUM_CONFIGURABLE_REGIONS
+	#define portNUM_CONFIGURABLE_REGIONS 1
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include "mpu_wrappers.h"
+
+/*
+ * Setup the stack of a new task so it is ready to be placed under the
+ * scheduler control.  The registers have to be placed on the stack in
+ * the order that the port expects to find them.
+ *
+ */
+#if( portUSING_MPU_WRAPPERS == 1 )
+	StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters, BaseType_t xRunPrivileged ) PRIVILEGED_FUNCTION;
+#else
+	StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters ) PRIVILEGED_FUNCTION;
+#endif
+
+/* Used by heap_5.c. */
+typedef struct HeapRegion
+{
+	uint8_t *pucStartAddress;
+	size_t xSizeInBytes;
+} HeapRegion_t;
+
+/*
+ * Used to define multiple heap regions for use by heap_5.c.  This function
+ * must be called before any calls to pvPortMalloc() - not creating a task,
+ * queue, semaphore, mutex, software timer, event group, etc. will result in
+ * pvPortMalloc being called.
+ *
+ * pxHeapRegions passes in an array of HeapRegion_t structures - each of which
+ * defines a region of memory that can be used as the heap.  The array is
+ * terminated by a HeapRegions_t structure that has a size of 0.  The region
+ * with the lowest start address must appear first in the array.
+ */
+void vPortDefineHeapRegions( const HeapRegion_t * const pxHeapRegions ) PRIVILEGED_FUNCTION;
+
+
+/*
+ * Map to the memory management routines required for the port.
+ */
+void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION;
+void vPortFree( void *pv ) PRIVILEGED_FUNCTION;
+void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION;
+size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION;
+size_t xPortGetMinimumEverFreeHeapSize( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Setup the hardware ready for the scheduler to take control.  This generally
+ * sets up a tick interrupt and sets timers for the correct tick frequency.
+ */
+BaseType_t xPortStartScheduler( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so
+ * the hardware is left in its original condition after the scheduler stops
+ * executing.
+ */
+void vPortEndScheduler( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * The structures and methods of manipulating the MPU are contained within the
+ * port layer.
+ *
+ * Fills the xMPUSettings structure with the memory region information
+ * contained in xRegions.
+ */
+#if( portUSING_MPU_WRAPPERS == 1 )
+	struct xMEMORY_REGION;
+	void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, StackType_t *pxBottomOfStack, uint16_t usStackDepth ) PRIVILEGED_FUNCTION;
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PORTABLE_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/projdefs.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/projdefs.h
new file mode 100644
index 0000000000000000000000000000000000000000..956264b953a110f90c92e44c09e979aa33e5f58f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/projdefs.h
@@ -0,0 +1,156 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef PROJDEFS_H
+#define PROJDEFS_H
+
+/*
+ * Defines the prototype to which task functions must conform.  Defined in this
+ * file to ensure the type is known before portable.h is included.
+ */
+typedef void (*TaskFunction_t)( void * );
+
+/* Converts a time in milliseconds to a time in ticks. */
+#define pdMS_TO_TICKS( xTimeInMs ) ( ( TickType_t ) ( ( ( TickType_t ) ( xTimeInMs ) * ( TickType_t ) configTICK_RATE_HZ ) / ( TickType_t ) 1000 ) )
+
+#define pdFALSE			( ( BaseType_t ) 0 )
+#define pdTRUE			( ( BaseType_t ) 1 )
+
+#define pdPASS			( pdTRUE )
+#define pdFAIL			( pdFALSE )
+#define errQUEUE_EMPTY	( ( BaseType_t ) 0 )
+#define errQUEUE_FULL	( ( BaseType_t ) 0 )
+
+/* FreeRTOS error definitions. */
+#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY	( -1 )
+#define errQUEUE_BLOCKED						( -4 )
+#define errQUEUE_YIELD							( -5 )
+
+/* Macros used for basic data corruption checks. */
+#ifndef configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES
+	#define configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES 0
+#endif
+
+#if( configUSE_16_BIT_TICKS == 1 )
+	#define pdINTEGRITY_CHECK_VALUE 0x5a5a
+#else
+	#define pdINTEGRITY_CHECK_VALUE 0x5a5a5a5aUL
+#endif
+
+/* The following errno values are used by FreeRTOS+ components, not FreeRTOS
+itself. */
+#define pdFREERTOS_ERRNO_NONE			0	/* No errors */
+#define	pdFREERTOS_ERRNO_ENOENT			2	/* No such file or directory */
+#define	pdFREERTOS_ERRNO_EIO			5	/* I/O error */
+#define	pdFREERTOS_ERRNO_ENXIO			6	/* No such device or address */
+#define	pdFREERTOS_ERRNO_EBADF			9	/* Bad file number */
+#define	pdFREERTOS_ERRNO_EAGAIN			11	/* No more processes */
+#define	pdFREERTOS_ERRNO_EWOULDBLOCK	11	/* Operation would block */
+#define	pdFREERTOS_ERRNO_ENOMEM			12	/* Not enough memory */
+#define	pdFREERTOS_ERRNO_EACCES			13	/* Permission denied */
+#define	pdFREERTOS_ERRNO_EFAULT			14	/* Bad address */
+#define	pdFREERTOS_ERRNO_EBUSY			16	/* Mount device busy */
+#define	pdFREERTOS_ERRNO_EEXIST			17	/* File exists */
+#define	pdFREERTOS_ERRNO_EXDEV			18	/* Cross-device link */
+#define	pdFREERTOS_ERRNO_ENODEV			19	/* No such device */
+#define	pdFREERTOS_ERRNO_ENOTDIR		20	/* Not a directory */
+#define	pdFREERTOS_ERRNO_EISDIR			21	/* Is a directory */
+#define	pdFREERTOS_ERRNO_EINVAL			22	/* Invalid argument */
+#define	pdFREERTOS_ERRNO_ENOSPC			28	/* No space left on device */
+#define	pdFREERTOS_ERRNO_ESPIPE			29	/* Illegal seek */
+#define	pdFREERTOS_ERRNO_EROFS			30	/* Read only file system */
+#define	pdFREERTOS_ERRNO_EUNATCH		42	/* Protocol driver not attached */
+#define	pdFREERTOS_ERRNO_EBADE			50	/* Invalid exchange */
+#define	pdFREERTOS_ERRNO_EFTYPE			79	/* Inappropriate file type or format */
+#define	pdFREERTOS_ERRNO_ENMFILE		89	/* No more files */
+#define	pdFREERTOS_ERRNO_ENOTEMPTY		90	/* Directory not empty */
+#define	pdFREERTOS_ERRNO_ENAMETOOLONG 	91	/* File or path name too long */
+#define	pdFREERTOS_ERRNO_EOPNOTSUPP		95	/* Operation not supported on transport endpoint */
+#define	pdFREERTOS_ERRNO_ENOBUFS		105	/* No buffer space available */
+#define	pdFREERTOS_ERRNO_ENOPROTOOPT	109	/* Protocol not available */
+#define	pdFREERTOS_ERRNO_EADDRINUSE		112	/* Address already in use */
+#define	pdFREERTOS_ERRNO_ETIMEDOUT		116	/* Connection timed out */
+#define	pdFREERTOS_ERRNO_EINPROGRESS	119	/* Connection already in progress */
+#define	pdFREERTOS_ERRNO_EALREADY		120	/* Socket already connected */
+#define	pdFREERTOS_ERRNO_EADDRNOTAVAIL 	125	/* Address not available */
+#define	pdFREERTOS_ERRNO_EISCONN		127	/* Socket is already connected */
+#define	pdFREERTOS_ERRNO_ENOTCONN		128	/* Socket is not connected */
+#define	pdFREERTOS_ERRNO_ENOMEDIUM		135	/* No medium inserted */
+#define	pdFREERTOS_ERRNO_EILSEQ			138	/* An invalid UTF-16 sequence was encountered. */
+#define	pdFREERTOS_ERRNO_ECANCELED		140	/* Operation canceled. */
+
+/* The following endian values are used by FreeRTOS+ components, not FreeRTOS
+itself. */
+#define pdFREERTOS_LITTLE_ENDIAN	0
+#define pdFREERTOS_BIG_ENDIAN		1
+
+#endif /* PROJDEFS_H */
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/queue.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/queue.h
new file mode 100644
index 0000000000000000000000000000000000000000..2d7b5e90a70c06b879216f0381a0b1ed5f708cee
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/queue.h
@@ -0,0 +1,1691 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+#ifndef QUEUE_H
+#define QUEUE_H
+
+#ifndef INC_FREERTOS_H
+	#error "include FreeRTOS.h" must appear in source files before "include queue.h"
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/**
+ * Type by which queues are referenced.  For example, a call to xQueueCreate()
+ * returns an QueueHandle_t variable that can then be used as a parameter to
+ * xQueueSend(), xQueueReceive(), etc.
+ */
+typedef void * QueueHandle_t;
+
+/**
+ * Type by which queue sets are referenced.  For example, a call to
+ * xQueueCreateSet() returns an xQueueSet variable that can then be used as a
+ * parameter to xQueueSelectFromSet(), xQueueAddToSet(), etc.
+ */
+typedef void * QueueSetHandle_t;
+
+/**
+ * Queue sets can contain both queues and semaphores, so the
+ * QueueSetMemberHandle_t is defined as a type to be used where a parameter or
+ * return value can be either an QueueHandle_t or an SemaphoreHandle_t.
+ */
+typedef void * QueueSetMemberHandle_t;
+
+/* For internal use only. */
+#define	queueSEND_TO_BACK		( ( BaseType_t ) 0 )
+#define	queueSEND_TO_FRONT		( ( BaseType_t ) 1 )
+#define queueOVERWRITE			( ( BaseType_t ) 2 )
+
+/* For internal use only.  These definitions *must* match those in queue.c. */
+#define queueQUEUE_TYPE_BASE				( ( uint8_t ) 0U )
+#define queueQUEUE_TYPE_SET					( ( uint8_t ) 0U )
+#define queueQUEUE_TYPE_MUTEX 				( ( uint8_t ) 1U )
+#define queueQUEUE_TYPE_COUNTING_SEMAPHORE	( ( uint8_t ) 2U )
+#define queueQUEUE_TYPE_BINARY_SEMAPHORE	( ( uint8_t ) 3U )
+#define queueQUEUE_TYPE_RECURSIVE_MUTEX		( ( uint8_t ) 4U )
+
+/**
+ * queue. h
+ * <pre>
+ QueueHandle_t xQueueCreate(
+							  UBaseType_t uxQueueLength,
+							  UBaseType_t uxItemSize
+						  );
+ * </pre>
+ *
+ * Creates a new queue instance.  This allocates the storage required by the
+ * new queue and returns a handle for the queue.
+ *
+ * @param uxQueueLength The maximum number of items that the queue can contain.
+ *
+ * @param uxItemSize The number of bytes each item in the queue will require.
+ * Items are queued by copy, not by reference, so this is the number of bytes
+ * that will be copied for each posted item.  Each item on the queue must be
+ * the same size.
+ *
+ * @return If the queue is successfully create then a handle to the newly
+ * created queue is returned.  If the queue cannot be created then 0 is
+ * returned.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueCreate xQueueCreate
+ * \ingroup QueueManagement
+ */
+#define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( uxQueueLength, uxItemSize, queueQUEUE_TYPE_BASE )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueSendToToFront(
+								   QueueHandle_t	xQueue,
+								   const void		*pvItemToQueue,
+								   TickType_t		xTicksToWait
+							   );
+ * </pre>
+ *
+ * This is a macro that calls xQueueGenericSend().
+ *
+ * Post an item to the front of a queue.  The item is queued by copy, not by
+ * reference.  This function must not be called from an interrupt service
+ * routine.  See xQueueSendFromISR () for an alternative which may be used
+ * in an ISR.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param xTicksToWait The maximum amount of time the task should block
+ * waiting for space to become available on the queue, should it already
+ * be full.  The call will return immediately if this is set to 0 and the
+ * queue is full.  The time is defined in tick periods so the constant
+ * portTICK_PERIOD_MS should be used to convert to real time if this is required.
+ *
+ * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueSend xQueueSend
+ * \ingroup QueueManagement
+ */
+#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueSendToBack(
+								   QueueHandle_t	xQueue,
+								   const void		*pvItemToQueue,
+								   TickType_t		xTicksToWait
+							   );
+ * </pre>
+ *
+ * This is a macro that calls xQueueGenericSend().
+ *
+ * Post an item to the back of a queue.  The item is queued by copy, not by
+ * reference.  This function must not be called from an interrupt service
+ * routine.  See xQueueSendFromISR () for an alternative which may be used
+ * in an ISR.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param xTicksToWait The maximum amount of time the task should block
+ * waiting for space to become available on the queue, should it already
+ * be full.  The call will return immediately if this is set to 0 and the queue
+ * is full.  The  time is defined in tick periods so the constant
+ * portTICK_PERIOD_MS should be used to convert to real time if this is required.
+ *
+ * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueSend xQueueSend
+ * \ingroup QueueManagement
+ */
+#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueSend(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue,
+							  TickType_t xTicksToWait
+						 );
+ * </pre>
+ *
+ * This is a macro that calls xQueueGenericSend().  It is included for
+ * backward compatibility with versions of FreeRTOS.org that did not
+ * include the xQueueSendToFront() and xQueueSendToBack() macros.  It is
+ * equivalent to xQueueSendToBack().
+ *
+ * Post an item on a queue.  The item is queued by copy, not by reference.
+ * This function must not be called from an interrupt service routine.
+ * See xQueueSendFromISR () for an alternative which may be used in an ISR.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param xTicksToWait The maximum amount of time the task should block
+ * waiting for space to become available on the queue, should it already
+ * be full.  The call will return immediately if this is set to 0 and the
+ * queue is full.  The time is defined in tick periods so the constant
+ * portTICK_PERIOD_MS should be used to convert to real time if this is required.
+ *
+ * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueSend xQueueSend
+ * \ingroup QueueManagement
+ */
+#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueOverwrite(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue
+						 );
+ * </pre>
+ *
+ * Only for use with queues that have a length of one - so the queue is either
+ * empty or full.
+ *
+ * Post an item on a queue.  If the queue is already full then overwrite the
+ * value held in the queue.  The item is queued by copy, not by reference.
+ *
+ * This function must not be called from an interrupt service routine.
+ * See xQueueOverwriteFromISR () for an alternative which may be used in an ISR.
+ *
+ * @param xQueue The handle of the queue to which the data is being sent.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @return xQueueOverwrite() is a macro that calls xQueueGenericSend(), and
+ * therefore has the same return values as xQueueSendToFront().  However, pdPASS
+ * is the only value that can be returned because xQueueOverwrite() will write
+ * to the queue even when the queue is already full.
+ *
+ * Example usage:
+   <pre>
+
+ void vFunction( void *pvParameters )
+ {
+ QueueHandle_t xQueue;
+ uint32_t ulVarToSend, ulValReceived;
+
+	// Create a queue to hold one uint32_t value.  It is strongly
+	// recommended *not* to use xQueueOverwrite() on queues that can
+	// contain more than one value, and doing so will trigger an assertion
+	// if configASSERT() is defined.
+	xQueue = xQueueCreate( 1, sizeof( uint32_t ) );
+
+	// Write the value 10 to the queue using xQueueOverwrite().
+	ulVarToSend = 10;
+	xQueueOverwrite( xQueue, &ulVarToSend );
+
+	// Peeking the queue should now return 10, but leave the value 10 in
+	// the queue.  A block time of zero is used as it is known that the
+	// queue holds a value.
+	ulValReceived = 0;
+	xQueuePeek( xQueue, &ulValReceived, 0 );
+
+	if( ulValReceived != 10 )
+	{
+		// Error unless the item was removed by a different task.
+	}
+
+	// The queue is still full.  Use xQueueOverwrite() to overwrite the
+	// value held in the queue with 100.
+	ulVarToSend = 100;
+	xQueueOverwrite( xQueue, &ulVarToSend );
+
+	// This time read from the queue, leaving the queue empty once more.
+	// A block time of 0 is used again.
+	xQueueReceive( xQueue, &ulValReceived, 0 );
+
+	// The value read should be the last value written, even though the
+	// queue was already full when the value was written.
+	if( ulValReceived != 100 )
+	{
+		// Error!
+	}
+
+	// ...
+}
+ </pre>
+ * \defgroup xQueueOverwrite xQueueOverwrite
+ * \ingroup QueueManagement
+ */
+#define xQueueOverwrite( xQueue, pvItemToQueue ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), 0, queueOVERWRITE )
+
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueGenericSend(
+									QueueHandle_t xQueue,
+									const void * pvItemToQueue,
+									TickType_t xTicksToWait
+									BaseType_t xCopyPosition
+								);
+ * </pre>
+ *
+ * It is preferred that the macros xQueueSend(), xQueueSendToFront() and
+ * xQueueSendToBack() are used in place of calling this function directly.
+ *
+ * Post an item on a queue.  The item is queued by copy, not by reference.
+ * This function must not be called from an interrupt service routine.
+ * See xQueueSendFromISR () for an alternative which may be used in an ISR.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param xTicksToWait The maximum amount of time the task should block
+ * waiting for space to become available on the queue, should it already
+ * be full.  The call will return immediately if this is set to 0 and the
+ * queue is full.  The time is defined in tick periods so the constant
+ * portTICK_PERIOD_MS should be used to convert to real time if this is required.
+ *
+ * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the
+ * item at the back of the queue, or queueSEND_TO_FRONT to place the item
+ * at the front of the queue (for high priority messages).
+ *
+ * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ uint32_t ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ QueueHandle_t xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 uint32_t values.
+	xQueue1 = xQueueCreate( 10, sizeof( uint32_t ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an uint32_t.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( TickType_t ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( TickType_t ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueSend xQueueSend
+ * \ingroup QueueManagement
+ */
+BaseType_t xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION;
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueuePeek(
+							 QueueHandle_t xQueue,
+							 void *pvBuffer,
+							 TickType_t xTicksToWait
+						 );</pre>
+ *
+ * This is a macro that calls the xQueueGenericReceive() function.
+ *
+ * Receive an item from a queue without removing the item from the queue.
+ * The item is received by copy so a buffer of adequate size must be
+ * provided.  The number of bytes copied into the buffer was defined when
+ * the queue was created.
+ *
+ * Successfully received items remain on the queue so will be returned again
+ * by the next call, or a call to xQueueReceive().
+ *
+ * This macro must not be used in an interrupt service routine.  See
+ * xQueuePeekFromISR() for an alternative that can be called from an interrupt
+ * service routine.
+ *
+ * @param xQueue The handle to the queue from which the item is to be
+ * received.
+ *
+ * @param pvBuffer Pointer to the buffer into which the received item will
+ * be copied.
+ *
+ * @param xTicksToWait The maximum amount of time the task should block
+ * waiting for an item to receive should the queue be empty at the time
+ * of the call.	 The time is defined in tick periods so the constant
+ * portTICK_PERIOD_MS should be used to convert to real time if this is required.
+ * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue
+ * is empty.
+ *
+ * @return pdTRUE if an item was successfully received from the queue,
+ * otherwise pdFALSE.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ QueueHandle_t xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( TickType_t ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( TickType_t ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueReceive xQueueReceive
+ * \ingroup QueueManagement
+ */
+#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueuePeekFromISR(
+									QueueHandle_t xQueue,
+									void *pvBuffer,
+								);</pre>
+ *
+ * A version of xQueuePeek() that can be called from an interrupt service
+ * routine (ISR).
+ *
+ * Receive an item from a queue without removing the item from the queue.
+ * The item is received by copy so a buffer of adequate size must be
+ * provided.  The number of bytes copied into the buffer was defined when
+ * the queue was created.
+ *
+ * Successfully received items remain on the queue so will be returned again
+ * by the next call, or a call to xQueueReceive().
+ *
+ * @param xQueue The handle to the queue from which the item is to be
+ * received.
+ *
+ * @param pvBuffer Pointer to the buffer into which the received item will
+ * be copied.
+ *
+ * @return pdTRUE if an item was successfully received from the queue,
+ * otherwise pdFALSE.
+ *
+ * \defgroup xQueuePeekFromISR xQueuePeekFromISR
+ * \ingroup QueueManagement
+ */
+BaseType_t xQueuePeekFromISR( QueueHandle_t xQueue, void * const pvBuffer ) PRIVILEGED_FUNCTION;
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueReceive(
+								 QueueHandle_t xQueue,
+								 void *pvBuffer,
+								 TickType_t xTicksToWait
+							);</pre>
+ *
+ * This is a macro that calls the xQueueGenericReceive() function.
+ *
+ * Receive an item from a queue.  The item is received by copy so a buffer of
+ * adequate size must be provided.  The number of bytes copied into the buffer
+ * was defined when the queue was created.
+ *
+ * Successfully received items are removed from the queue.
+ *
+ * This function must not be used in an interrupt service routine.  See
+ * xQueueReceiveFromISR for an alternative that can.
+ *
+ * @param xQueue The handle to the queue from which the item is to be
+ * received.
+ *
+ * @param pvBuffer Pointer to the buffer into which the received item will
+ * be copied.
+ *
+ * @param xTicksToWait The maximum amount of time the task should block
+ * waiting for an item to receive should the queue be empty at the time
+ * of the call.	 xQueueReceive() will return immediately if xTicksToWait
+ * is zero and the queue is empty.  The time is defined in tick periods so the
+ * constant portTICK_PERIOD_MS should be used to convert to real time if this is
+ * required.
+ *
+ * @return pdTRUE if an item was successfully received from the queue,
+ * otherwise pdFALSE.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ QueueHandle_t xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( TickType_t ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( TickType_t ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueReceive xQueueReceive
+ * \ingroup QueueManagement
+ */
+#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE )
+
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueGenericReceive(
+									   QueueHandle_t	xQueue,
+									   void	*pvBuffer,
+									   TickType_t	xTicksToWait
+									   BaseType_t	xJustPeek
+									);</pre>
+ *
+ * It is preferred that the macro xQueueReceive() be used rather than calling
+ * this function directly.
+ *
+ * Receive an item from a queue.  The item is received by copy so a buffer of
+ * adequate size must be provided.  The number of bytes copied into the buffer
+ * was defined when the queue was created.
+ *
+ * This function must not be used in an interrupt service routine.  See
+ * xQueueReceiveFromISR for an alternative that can.
+ *
+ * @param xQueue The handle to the queue from which the item is to be
+ * received.
+ *
+ * @param pvBuffer Pointer to the buffer into which the received item will
+ * be copied.
+ *
+ * @param xTicksToWait The maximum amount of time the task should block
+ * waiting for an item to receive should the queue be empty at the time
+ * of the call.	 The time is defined in tick periods so the constant
+ * portTICK_PERIOD_MS should be used to convert to real time if this is required.
+ * xQueueGenericReceive() will return immediately if the queue is empty and
+ * xTicksToWait is 0.
+ *
+ * @param xJustPeek When set to true, the item received from the queue is not
+ * actually removed from the queue - meaning a subsequent call to
+ * xQueueReceive() will return the same item.  When set to false, the item
+ * being received from the queue is also removed from the queue.
+ *
+ * @return pdTRUE if an item was successfully received from the queue,
+ * otherwise pdFALSE.
+ *
+ * Example usage:
+   <pre>
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ QueueHandle_t xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( TickType_t ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( TickType_t ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ </pre>
+ * \defgroup xQueueReceive xQueueReceive
+ * \ingroup QueueManagement
+ */
+BaseType_t xQueueGenericReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait, const BaseType_t xJustPeek ) PRIVILEGED_FUNCTION;
+
+/**
+ * queue. h
+ * <pre>UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue );</pre>
+ *
+ * Return the number of messages stored in a queue.
+ *
+ * @param xQueue A handle to the queue being queried.
+ *
+ * @return The number of messages available in the queue.
+ *
+ * \defgroup uxQueueMessagesWaiting uxQueueMessagesWaiting
+ * \ingroup QueueManagement
+ */
+UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+
+/**
+ * queue. h
+ * <pre>UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue );</pre>
+ *
+ * Return the number of free spaces available in a queue.  This is equal to the
+ * number of items that can be sent to the queue before the queue becomes full
+ * if no items are removed.
+ *
+ * @param xQueue A handle to the queue being queried.
+ *
+ * @return The number of spaces available in the queue.
+ *
+ * \defgroup uxQueueMessagesWaiting uxQueueMessagesWaiting
+ * \ingroup QueueManagement
+ */
+UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+
+/**
+ * queue. h
+ * <pre>void vQueueDelete( QueueHandle_t xQueue );</pre>
+ *
+ * Delete a queue - freeing all the memory allocated for storing of items
+ * placed on the queue.
+ *
+ * @param xQueue A handle to the queue to be deleted.
+ *
+ * \defgroup vQueueDelete vQueueDelete
+ * \ingroup QueueManagement
+ */
+void vQueueDelete( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueSendToFrontFromISR(
+										 QueueHandle_t xQueue,
+										 const void *pvItemToQueue,
+										 BaseType_t *pxHigherPriorityTaskWoken
+									  );
+ </pre>
+ *
+ * This is a macro that calls xQueueGenericSendFromISR().
+ *
+ * Post an item to the front of a queue.  It is safe to use this macro from
+ * within an interrupt service routine.
+ *
+ * Items are queued by copy not reference so it is preferable to only
+ * queue small items, especially when called from an ISR.  In most cases
+ * it would be preferable to store a pointer to the item being queued.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task
+ * to unblock, and the unblocked task has a priority higher than the currently
+ * running task.  If xQueueSendToFromFromISR() sets this value to pdTRUE then
+ * a context switch should be requested before the interrupt is exited.
+ *
+ * @return pdTRUE if the data was successfully sent to the queue, otherwise
+ * errQUEUE_FULL.
+ *
+ * Example usage for buffered IO (where the ISR can obtain more than one value
+ * per call):
+   <pre>
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ </pre>
+ *
+ * \defgroup xQueueSendFromISR xQueueSendFromISR
+ * \ingroup QueueManagement
+ */
+#define xQueueSendToFrontFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT )
+
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueSendToBackFromISR(
+										 QueueHandle_t xQueue,
+										 const void *pvItemToQueue,
+										 BaseType_t *pxHigherPriorityTaskWoken
+									  );
+ </pre>
+ *
+ * This is a macro that calls xQueueGenericSendFromISR().
+ *
+ * Post an item to the back of a queue.  It is safe to use this macro from
+ * within an interrupt service routine.
+ *
+ * Items are queued by copy not reference so it is preferable to only
+ * queue small items, especially when called from an ISR.  In most cases
+ * it would be preferable to store a pointer to the item being queued.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task
+ * to unblock, and the unblocked task has a priority higher than the currently
+ * running task.  If xQueueSendToBackFromISR() sets this value to pdTRUE then
+ * a context switch should be requested before the interrupt is exited.
+ *
+ * @return pdTRUE if the data was successfully sent to the queue, otherwise
+ * errQUEUE_FULL.
+ *
+ * Example usage for buffered IO (where the ISR can obtain more than one value
+ * per call):
+   <pre>
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ </pre>
+ *
+ * \defgroup xQueueSendFromISR xQueueSendFromISR
+ * \ingroup QueueManagement
+ */
+#define xQueueSendToBackFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueOverwriteFromISR(
+							  QueueHandle_t xQueue,
+							  const void * pvItemToQueue,
+							  BaseType_t *pxHigherPriorityTaskWoken
+						 );
+ * </pre>
+ *
+ * A version of xQueueOverwrite() that can be used in an interrupt service
+ * routine (ISR).
+ *
+ * Only for use with queues that can hold a single item - so the queue is either
+ * empty or full.
+ *
+ * Post an item on a queue.  If the queue is already full then overwrite the
+ * value held in the queue.  The item is queued by copy, not by reference.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param pxHigherPriorityTaskWoken xQueueOverwriteFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task
+ * to unblock, and the unblocked task has a priority higher than the currently
+ * running task.  If xQueueOverwriteFromISR() sets this value to pdTRUE then
+ * a context switch should be requested before the interrupt is exited.
+ *
+ * @return xQueueOverwriteFromISR() is a macro that calls
+ * xQueueGenericSendFromISR(), and therefore has the same return values as
+ * xQueueSendToFrontFromISR().  However, pdPASS is the only value that can be
+ * returned because xQueueOverwriteFromISR() will write to the queue even when
+ * the queue is already full.
+ *
+ * Example usage:
+   <pre>
+
+ QueueHandle_t xQueue;
+
+ void vFunction( void *pvParameters )
+ {
+ 	// Create a queue to hold one uint32_t value.  It is strongly
+	// recommended *not* to use xQueueOverwriteFromISR() on queues that can
+	// contain more than one value, and doing so will trigger an assertion
+	// if configASSERT() is defined.
+	xQueue = xQueueCreate( 1, sizeof( uint32_t ) );
+}
+
+void vAnInterruptHandler( void )
+{
+// xHigherPriorityTaskWoken must be set to pdFALSE before it is used.
+BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+uint32_t ulVarToSend, ulValReceived;
+
+	// Write the value 10 to the queue using xQueueOverwriteFromISR().
+	ulVarToSend = 10;
+	xQueueOverwriteFromISR( xQueue, &ulVarToSend, &xHigherPriorityTaskWoken );
+
+	// The queue is full, but calling xQueueOverwriteFromISR() again will still
+	// pass because the value held in the queue will be overwritten with the
+	// new value.
+	ulVarToSend = 100;
+	xQueueOverwriteFromISR( xQueue, &ulVarToSend, &xHigherPriorityTaskWoken );
+
+	// Reading from the queue will now return 100.
+
+	// ...
+
+	if( xHigherPrioritytaskWoken == pdTRUE )
+	{
+		// Writing to the queue caused a task to unblock and the unblocked task
+		// has a priority higher than or equal to the priority of the currently
+		// executing task (the task this interrupt interrupted).  Perform a context
+		// switch so this interrupt returns directly to the unblocked task.
+		portYIELD_FROM_ISR(); // or portEND_SWITCHING_ISR() depending on the port.
+	}
+}
+ </pre>
+ * \defgroup xQueueOverwriteFromISR xQueueOverwriteFromISR
+ * \ingroup QueueManagement
+ */
+#define xQueueOverwriteFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueOVERWRITE )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueSendFromISR(
+									 QueueHandle_t xQueue,
+									 const void *pvItemToQueue,
+									 BaseType_t *pxHigherPriorityTaskWoken
+								);
+ </pre>
+ *
+ * This is a macro that calls xQueueGenericSendFromISR().  It is included
+ * for backward compatibility with versions of FreeRTOS.org that did not
+ * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR()
+ * macros.
+ *
+ * Post an item to the back of a queue.  It is safe to use this function from
+ * within an interrupt service routine.
+ *
+ * Items are queued by copy not reference so it is preferable to only
+ * queue small items, especially when called from an ISR.  In most cases
+ * it would be preferable to store a pointer to the item being queued.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task
+ * to unblock, and the unblocked task has a priority higher than the currently
+ * running task.  If xQueueSendFromISR() sets this value to pdTRUE then
+ * a context switch should be requested before the interrupt is exited.
+ *
+ * @return pdTRUE if the data was successfully sent to the queue, otherwise
+ * errQUEUE_FULL.
+ *
+ * Example usage for buffered IO (where the ISR can obtain more than one value
+ * per call):
+   <pre>
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		portYIELD_FROM_ISR ();
+	}
+ }
+ </pre>
+ *
+ * \defgroup xQueueSendFromISR xQueueSendFromISR
+ * \ingroup QueueManagement
+ */
+#define xQueueSendFromISR( xQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK )
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueGenericSendFromISR(
+										   QueueHandle_t		xQueue,
+										   const	void	*pvItemToQueue,
+										   BaseType_t	*pxHigherPriorityTaskWoken,
+										   BaseType_t	xCopyPosition
+									   );
+ </pre>
+ *
+ * It is preferred that the macros xQueueSendFromISR(),
+ * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place
+ * of calling this function directly.  xQueueGiveFromISR() is an
+ * equivalent for use by semaphores that don't actually copy any data.
+ *
+ * Post an item on a queue.  It is safe to use this function from within an
+ * interrupt service routine.
+ *
+ * Items are queued by copy not reference so it is preferable to only
+ * queue small items, especially when called from an ISR.  In most cases
+ * it would be preferable to store a pointer to the item being queued.
+ *
+ * @param xQueue The handle to the queue on which the item is to be posted.
+ *
+ * @param pvItemToQueue A pointer to the item that is to be placed on the
+ * queue.  The size of the items the queue will hold was defined when the
+ * queue was created, so this many bytes will be copied from pvItemToQueue
+ * into the queue storage area.
+ *
+ * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task
+ * to unblock, and the unblocked task has a priority higher than the currently
+ * running task.  If xQueueGenericSendFromISR() sets this value to pdTRUE then
+ * a context switch should be requested before the interrupt is exited.
+ *
+ * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the
+ * item at the back of the queue, or queueSEND_TO_FRONT to place the item
+ * at the front of the queue (for high priority messages).
+ *
+ * @return pdTRUE if the data was successfully sent to the queue, otherwise
+ * errQUEUE_FULL.
+ *
+ * Example usage for buffered IO (where the ISR can obtain more than one value
+ * per call):
+   <pre>
+ void vBufferISR( void )
+ {
+ char cIn;
+ BaseType_t xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ </pre>
+ *
+ * \defgroup xQueueSendFromISR xQueueSendFromISR
+ * \ingroup QueueManagement
+ */
+BaseType_t xQueueGenericSendFromISR( QueueHandle_t xQueue, const void * const pvItemToQueue, BaseType_t * const pxHigherPriorityTaskWoken, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION;
+BaseType_t xQueueGiveFromISR( QueueHandle_t xQueue, BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+
+/**
+ * queue. h
+ * <pre>
+ BaseType_t xQueueReceiveFromISR(
+									   QueueHandle_t	xQueue,
+									   void	*pvBuffer,
+									   BaseType_t *pxTaskWoken
+								   );
+ * </pre>
+ *
+ * Receive an item from a queue.  It is safe to use this function from within an
+ * interrupt service routine.
+ *
+ * @param xQueue The handle to the queue from which the item is to be
+ * received.
+ *
+ * @param pvBuffer Pointer to the buffer into which the received item will
+ * be copied.
+ *
+ * @param pxTaskWoken A task may be blocked waiting for space to become
+ * available on the queue.  If xQueueReceiveFromISR causes such a task to
+ * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will
+ * remain unchanged.
+ *
+ * @return pdTRUE if an item was successfully received from the queue,
+ * otherwise pdFALSE.
+ *
+ * Example usage:
+   <pre>
+
+ QueueHandle_t xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const TickType_t xTicksToWait = ( TickType_t )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xTicksToWait ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xTicksToWait );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ BaseType_t xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ </pre>
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR
+ * \ingroup QueueManagement
+ */
+BaseType_t xQueueReceiveFromISR( QueueHandle_t xQueue, void * const pvBuffer, BaseType_t * const pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+
+/*
+ * Utilities to query queues that are safe to use from an ISR.  These utilities
+ * should be used only from witin an ISR, or within a critical section.
+ */
+BaseType_t xQueueIsQueueEmptyFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+BaseType_t xQueueIsQueueFullFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+UBaseType_t uxQueueMessagesWaitingFromISR( const QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+
+
+/*
+ * xQueueAltGenericSend() is an alternative version of xQueueGenericSend().
+ * Likewise xQueueAltGenericReceive() is an alternative version of
+ * xQueueGenericReceive().
+ *
+ * The source code that implements the alternative (Alt) API is much
+ * simpler	because it executes everything from within a critical section.
+ * This is	the approach taken by many other RTOSes, but FreeRTOS.org has the
+ * preferred fully featured API too.  The fully featured API has more
+ * complex	code that takes longer to execute, but makes much less use of
+ * critical sections.  Therefore the alternative API sacrifices interrupt
+ * responsiveness to gain execution speed, whereas the fully featured API
+ * sacrifices execution speed to ensure better interrupt responsiveness.
+ */
+BaseType_t xQueueAltGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION;
+BaseType_t xQueueAltGenericReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait, BaseType_t xJustPeeking ) PRIVILEGED_FUNCTION;
+#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT )
+#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK )
+#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE )
+#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE )
+
+/*
+ * The functions defined above are for passing data to and from tasks.  The
+ * functions below are the equivalents for passing data to and from
+ * co-routines.
+ *
+ * These functions are called from the co-routine macro implementation and
+ * should not be called directly from application code.  Instead use the macro
+ * wrappers defined within croutine.h.
+ */
+BaseType_t xQueueCRSendFromISR( QueueHandle_t xQueue, const void *pvItemToQueue, BaseType_t xCoRoutinePreviouslyWoken );
+BaseType_t xQueueCRReceiveFromISR( QueueHandle_t xQueue, void *pvBuffer, BaseType_t *pxTaskWoken );
+BaseType_t xQueueCRSend( QueueHandle_t xQueue, const void *pvItemToQueue, TickType_t xTicksToWait );
+BaseType_t xQueueCRReceive( QueueHandle_t xQueue, void *pvBuffer, TickType_t xTicksToWait );
+
+/*
+ * For internal use only.  Use xSemaphoreCreateMutex(),
+ * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling
+ * these functions directly.
+ */
+QueueHandle_t xQueueCreateMutex( const uint8_t ucQueueType ) PRIVILEGED_FUNCTION;
+QueueHandle_t xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount ) PRIVILEGED_FUNCTION;
+void* xQueueGetMutexHolder( QueueHandle_t xSemaphore ) PRIVILEGED_FUNCTION;
+
+/*
+ * For internal use only.  Use xSemaphoreTakeMutexRecursive() or
+ * xSemaphoreGiveMutexRecursive() instead of calling these functions directly.
+ */
+BaseType_t xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+BaseType_t xQueueGiveMutexRecursive( QueueHandle_t pxMutex ) PRIVILEGED_FUNCTION;
+
+/*
+ * Reset a queue back to its original empty state.  The return value is now
+ * obsolete and is always set to pdPASS.
+ */
+#define xQueueReset( xQueue ) xQueueGenericReset( xQueue, pdFALSE )
+
+/*
+ * The registry is provided as a means for kernel aware debuggers to
+ * locate queues, semaphores and mutexes.  Call vQueueAddToRegistry() add
+ * a queue, semaphore or mutex handle to the registry if you want the handle
+ * to be available to a kernel aware debugger.  If you are not using a kernel
+ * aware debugger then this function can be ignored.
+ *
+ * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the
+ * registry can hold.  configQUEUE_REGISTRY_SIZE must be greater than 0
+ * within FreeRTOSConfig.h for the registry to be available.  Its value
+ * does not effect the number of queues, semaphores and mutexes that can be
+ * created - just the number that the registry can hold.
+ *
+ * @param xQueue The handle of the queue being added to the registry.  This
+ * is the handle returned by a call to xQueueCreate().  Semaphore and mutex
+ * handles can also be passed in here.
+ *
+ * @param pcName The name to be associated with the handle.  This is the
+ * name that the kernel aware debugger will display.  The queue registry only
+ * stores a pointer to the string - so the string must be persistent (global or
+ * preferably in ROM/Flash), not on the stack.
+ */
+#if configQUEUE_REGISTRY_SIZE > 0
+	void vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcName ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+#endif
+
+/*
+ * The registry is provided as a means for kernel aware debuggers to
+ * locate queues, semaphores and mutexes.  Call vQueueAddToRegistry() add
+ * a queue, semaphore or mutex handle to the registry if you want the handle
+ * to be available to a kernel aware debugger, and vQueueUnregisterQueue() to
+ * remove the queue, semaphore or mutex from the register.  If you are not using
+ * a kernel aware debugger then this function can be ignored.
+ *
+ * @param xQueue The handle of the queue being removed from the registry.
+ */
+#if configQUEUE_REGISTRY_SIZE > 0
+	void vQueueUnregisterQueue( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+#endif
+
+/*
+ * Generic version of the queue creation function, which is in turn called by
+ * any queue, semaphore or mutex creation function or macro.
+ */
+QueueHandle_t xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType ) PRIVILEGED_FUNCTION;
+
+/*
+ * Queue sets provide a mechanism to allow a task to block (pend) on a read
+ * operation from multiple queues or semaphores simultaneously.
+ *
+ * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this
+ * function.
+ *
+ * A queue set must be explicitly created using a call to xQueueCreateSet()
+ * before it can be used.  Once created, standard FreeRTOS queues and semaphores
+ * can be added to the set using calls to xQueueAddToSet().
+ * xQueueSelectFromSet() is then used to determine which, if any, of the queues
+ * or semaphores contained in the set is in a state where a queue read or
+ * semaphore take operation would be successful.
+ *
+ * Note 1:  See the documentation on http://wwwFreeRTOS.org/RTOS-queue-sets.html
+ * for reasons why queue sets are very rarely needed in practice as there are
+ * simpler methods of blocking on multiple objects.
+ *
+ * Note 2:  Blocking on a queue set that contains a mutex will not cause the
+ * mutex holder to inherit the priority of the blocked task.
+ *
+ * Note 3:  An additional 4 bytes of RAM is required for each space in a every
+ * queue added to a queue set.  Therefore counting semaphores that have a high
+ * maximum count value should not be added to a queue set.
+ *
+ * Note 4:  A receive (in the case of a queue) or take (in the case of a
+ * semaphore) operation must not be performed on a member of a queue set unless
+ * a call to xQueueSelectFromSet() has first returned a handle to that set member.
+ *
+ * @param uxEventQueueLength Queue sets store events that occur on
+ * the queues and semaphores contained in the set.  uxEventQueueLength specifies
+ * the maximum number of events that can be queued at once.  To be absolutely
+ * certain that events are not lost uxEventQueueLength should be set to the
+ * total sum of the length of the queues added to the set, where binary
+ * semaphores and mutexes have a length of 1, and counting semaphores have a
+ * length set by their maximum count value.  Examples:
+ *  + If a queue set is to hold a queue of length 5, another queue of length 12,
+ *    and a binary semaphore, then uxEventQueueLength should be set to
+ *    (5 + 12 + 1), or 18.
+ *  + If a queue set is to hold three binary semaphores then uxEventQueueLength
+ *    should be set to (1 + 1 + 1 ), or 3.
+ *  + If a queue set is to hold a counting semaphore that has a maximum count of
+ *    5, and a counting semaphore that has a maximum count of 3, then
+ *    uxEventQueueLength should be set to (5 + 3), or 8.
+ *
+ * @return If the queue set is created successfully then a handle to the created
+ * queue set is returned.  Otherwise NULL is returned.
+ */
+QueueSetHandle_t xQueueCreateSet( const UBaseType_t uxEventQueueLength ) PRIVILEGED_FUNCTION;
+
+/*
+ * Adds a queue or semaphore to a queue set that was previously created by a
+ * call to xQueueCreateSet().
+ *
+ * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this
+ * function.
+ *
+ * Note 1:  A receive (in the case of a queue) or take (in the case of a
+ * semaphore) operation must not be performed on a member of a queue set unless
+ * a call to xQueueSelectFromSet() has first returned a handle to that set member.
+ *
+ * @param xQueueOrSemaphore The handle of the queue or semaphore being added to
+ * the queue set (cast to an QueueSetMemberHandle_t type).
+ *
+ * @param xQueueSet The handle of the queue set to which the queue or semaphore
+ * is being added.
+ *
+ * @return If the queue or semaphore was successfully added to the queue set
+ * then pdPASS is returned.  If the queue could not be successfully added to the
+ * queue set because it is already a member of a different queue set then pdFAIL
+ * is returned.
+ */
+BaseType_t xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION;
+
+/*
+ * Removes a queue or semaphore from a queue set.  A queue or semaphore can only
+ * be removed from a set if the queue or semaphore is empty.
+ *
+ * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this
+ * function.
+ *
+ * @param xQueueOrSemaphore The handle of the queue or semaphore being removed
+ * from the queue set (cast to an QueueSetMemberHandle_t type).
+ *
+ * @param xQueueSet The handle of the queue set in which the queue or semaphore
+ * is included.
+ *
+ * @return If the queue or semaphore was successfully removed from the queue set
+ * then pdPASS is returned.  If the queue was not in the queue set, or the
+ * queue (or semaphore) was not empty, then pdFAIL is returned.
+ */
+BaseType_t xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION;
+
+/*
+ * xQueueSelectFromSet() selects from the members of a queue set a queue or
+ * semaphore that either contains data (in the case of a queue) or is available
+ * to take (in the case of a semaphore).  xQueueSelectFromSet() effectively
+ * allows a task to block (pend) on a read operation on all the queues and
+ * semaphores in a queue set simultaneously.
+ *
+ * See FreeRTOS/Source/Demo/Common/Minimal/QueueSet.c for an example using this
+ * function.
+ *
+ * Note 1:  See the documentation on http://wwwFreeRTOS.org/RTOS-queue-sets.html
+ * for reasons why queue sets are very rarely needed in practice as there are
+ * simpler methods of blocking on multiple objects.
+ *
+ * Note 2:  Blocking on a queue set that contains a mutex will not cause the
+ * mutex holder to inherit the priority of the blocked task.
+ *
+ * Note 3:  A receive (in the case of a queue) or take (in the case of a
+ * semaphore) operation must not be performed on a member of a queue set unless
+ * a call to xQueueSelectFromSet() has first returned a handle to that set member.
+ *
+ * @param xQueueSet The queue set on which the task will (potentially) block.
+ *
+ * @param xTicksToWait The maximum time, in ticks, that the calling task will
+ * remain in the Blocked state (with other tasks executing) to wait for a member
+ * of the queue set to be ready for a successful queue read or semaphore take
+ * operation.
+ *
+ * @return xQueueSelectFromSet() will return the handle of a queue (cast to
+ * a QueueSetMemberHandle_t type) contained in the queue set that contains data,
+ * or the handle of a semaphore (cast to a QueueSetMemberHandle_t type) contained
+ * in the queue set that is available, or NULL if no such queue or semaphore
+ * exists before before the specified block time expires.
+ */
+QueueSetMemberHandle_t xQueueSelectFromSet( QueueSetHandle_t xQueueSet, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+/*
+ * A version of xQueueSelectFromSet() that can be used from an ISR.
+ */
+QueueSetMemberHandle_t xQueueSelectFromSetFromISR( QueueSetHandle_t xQueueSet ) PRIVILEGED_FUNCTION;
+
+/* Not public API functions. */
+void vQueueWaitForMessageRestricted( QueueHandle_t xQueue, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) PRIVILEGED_FUNCTION;
+BaseType_t xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue ) PRIVILEGED_FUNCTION;
+void vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber ) PRIVILEGED_FUNCTION;
+UBaseType_t uxQueueGetQueueNumber( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+uint8_t ucQueueGetQueueType( QueueHandle_t xQueue ) PRIVILEGED_FUNCTION;
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* QUEUE_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/semphr.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/semphr.h
new file mode 100644
index 0000000000000000000000000000000000000000..ab00d09d76ce0debee162e1770de2c11b5031572
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/semphr.h
@@ -0,0 +1,844 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#ifndef SEMAPHORE_H
+#define SEMAPHORE_H
+
+#ifndef INC_FREERTOS_H
+	#error "include FreeRTOS.h" must appear in source files before "include semphr.h"
+#endif
+
+#include "queue.h"
+
+typedef QueueHandle_t SemaphoreHandle_t;
+
+#define semBINARY_SEMAPHORE_QUEUE_LENGTH	( ( uint8_t ) 1U )
+#define semSEMAPHORE_QUEUE_ITEM_LENGTH		( ( uint8_t ) 0U )
+#define semGIVE_BLOCK_TIME					( ( TickType_t ) 0U )
+
+
+/**
+ * semphr. h
+ * <pre>vSemaphoreCreateBinary( SemaphoreHandle_t xSemaphore )</pre>
+ *
+ * This old vSemaphoreCreateBinary() macro is now deprecated in favour of the
+ * xSemaphoreCreateBinary() function.  Note that binary semaphores created using
+ * the vSemaphoreCreateBinary() macro are created in a state such that the
+ * first call to 'take' the semaphore would pass, whereas binary semaphores
+ * created using xSemaphoreCreateBinary() are created in a state such that the
+ * the semaphore must first be 'given' before it can be 'taken'.
+ *
+ * <i>Macro</i> that implements a semaphore by using the existing queue mechanism.
+ * The queue length is 1 as this is a binary semaphore.  The data size is 0
+ * as we don't want to actually store any data - we just want to know if the
+ * queue is empty or full.
+ *
+ * This type of semaphore can be used for pure synchronisation between tasks or
+ * between an interrupt and a task.  The semaphore need not be given back once
+ * obtained, so one task/interrupt can continuously 'give' the semaphore while
+ * another continuously 'takes' the semaphore.  For this reason this type of
+ * semaphore does not use a priority inheritance mechanism.  For an alternative
+ * that does use priority inheritance see xSemaphoreCreateMutex().
+ *
+ * @param xSemaphore Handle to the created semaphore.  Should be of type SemaphoreHandle_t.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ </pre>
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary
+ * \ingroup Semaphores
+ */
+#define vSemaphoreCreateBinary( xSemaphore )																							\
+	{																																	\
+		( xSemaphore ) = xQueueGenericCreate( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE );	\
+		if( ( xSemaphore ) != NULL )																									\
+		{																																\
+			( void ) xSemaphoreGive( ( xSemaphore ) );																					\
+		}																																\
+	}
+
+/**
+ * semphr. h
+ * <pre>SemaphoreHandle_t xSemaphoreCreateBinary( void )</pre>
+ *
+ * The old vSemaphoreCreateBinary() macro is now deprecated in favour of this
+ * xSemaphoreCreateBinary() function.  Note that binary semaphores created using
+ * the vSemaphoreCreateBinary() macro are created in a state such that the
+ * first call to 'take' the semaphore would pass, whereas binary semaphores
+ * created using xSemaphoreCreateBinary() are created in a state such that the
+ * the semaphore must first be 'given' before it can be 'taken'.
+ *
+ * Function that creates a semaphore by using the existing queue mechanism.
+ * The queue length is 1 as this is a binary semaphore.  The data size is 0
+ * as nothing is actually stored - all that is important is whether the queue is
+ * empty or full (the binary semaphore is available or not).
+ *
+ * This type of semaphore can be used for pure synchronisation between tasks or
+ * between an interrupt and a task.  The semaphore need not be given back once
+ * obtained, so one task/interrupt can continuously 'give' the semaphore while
+ * another continuously 'takes' the semaphore.  For this reason this type of
+ * semaphore does not use a priority inheritance mechanism.  For an alternative
+ * that does use priority inheritance see xSemaphoreCreateMutex().
+ *
+ * @return Handle to the created semaphore.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateBinary();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ </pre>
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary
+ * \ingroup Semaphores
+ */
+#define xSemaphoreCreateBinary() xQueueGenericCreate( ( UBaseType_t ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE )
+
+/**
+ * semphr. h
+ * <pre>xSemaphoreTake(
+ *                   SemaphoreHandle_t xSemaphore,
+ *                   TickType_t xBlockTime
+ *               )</pre>
+ *
+ * <i>Macro</i> to obtain a semaphore.  The semaphore must have previously been
+ * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or
+ * xSemaphoreCreateCounting().
+ *
+ * @param xSemaphore A handle to the semaphore being taken - obtained when
+ * the semaphore was created.
+ *
+ * @param xBlockTime The time in ticks to wait for the semaphore to become
+ * available.  The macro portTICK_PERIOD_MS can be used to convert this to a
+ * real time.  A block time of zero can be used to poll the semaphore.  A block
+ * time of portMAX_DELAY can be used to block indefinitely (provided
+ * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h).
+ *
+ * @return pdTRUE if the semaphore was obtained.  pdFALSE
+ * if xBlockTime expired without the semaphore becoming available.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTake( xSemaphore, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ </pre>
+ * \defgroup xSemaphoreTake xSemaphoreTake
+ * \ingroup Semaphores
+ */
+#define xSemaphoreTake( xSemaphore, xBlockTime )		xQueueGenericReceive( ( QueueHandle_t ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE )
+
+/**
+ * semphr. h
+ * xSemaphoreTakeRecursive(
+ *                          SemaphoreHandle_t xMutex,
+ *                          TickType_t xBlockTime
+ *                        )
+ *
+ * <i>Macro</i> to recursively obtain, or 'take', a mutex type semaphore.
+ * The mutex must have previously been created using a call to
+ * xSemaphoreCreateRecursiveMutex();
+ *
+ * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this
+ * macro to be available.
+ *
+ * This macro must not be used on mutexes created using xSemaphoreCreateMutex().
+ *
+ * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex
+ * doesn't become available again until the owner has called
+ * xSemaphoreGiveRecursive() for each successful 'take' request.  For example,
+ * if a task successfully 'takes' the same mutex 5 times then the mutex will
+ * not be available to any other task until it has also  'given' the mutex back
+ * exactly five times.
+ *
+ * @param xMutex A handle to the mutex being obtained.  This is the
+ * handle returned by xSemaphoreCreateRecursiveMutex();
+ *
+ * @param xBlockTime The time in ticks to wait for the semaphore to become
+ * available.  The macro portTICK_PERIOD_MS can be used to convert this to a
+ * real time.  A block time of zero can be used to poll the semaphore.  If
+ * the task already owns the semaphore then xSemaphoreTakeRecursive() will
+ * return immediately no matter what the value of xBlockTime.
+ *
+ * @return pdTRUE if the semaphore was obtained.  pdFALSE if xBlockTime
+ * expired without the semaphore becoming available.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTakeRecursive( xSemaphore, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, but instead buried in a more complex
+			// call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ </pre>
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive
+ * \ingroup Semaphores
+ */
+#define xSemaphoreTakeRecursive( xMutex, xBlockTime )	xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) )
+
+
+/*
+ * xSemaphoreAltTake() is an alternative version of xSemaphoreTake().
+ *
+ * The source code that implements the alternative (Alt) API is much
+ * simpler	because it executes everything from within a critical section.
+ * This is	the approach taken by many other RTOSes, but FreeRTOS.org has the
+ * preferred fully featured API too.  The fully featured API has more
+ * complex	code that takes longer to execute, but makes much less use of
+ * critical sections.  Therefore the alternative API sacrifices interrupt
+ * responsiveness to gain execution speed, whereas the fully featured API
+ * sacrifices execution speed to ensure better interrupt responsiveness.
+ */
+#define xSemaphoreAltTake( xSemaphore, xBlockTime )		xQueueAltGenericReceive( ( QueueHandle_t ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE )
+
+/**
+ * semphr. h
+ * <pre>xSemaphoreGive( SemaphoreHandle_t xSemaphore )</pre>
+ *
+ * <i>Macro</i> to release a semaphore.  The semaphore must have previously been
+ * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or
+ * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake().
+ *
+ * This macro must not be used from an ISR.  See xSemaphoreGiveFromISR () for
+ * an alternative which can be used from an ISR.
+ *
+ * This macro must also not be used on semaphores created using
+ * xSemaphoreCreateRecursiveMutex().
+ *
+ * @param xSemaphore A handle to the semaphore being released.  This is the
+ * handle returned when the semaphore was created.
+ *
+ * @return pdTRUE if the semaphore was released.  pdFALSE if an error occurred.
+ * Semaphores are implemented using queues.  An error can occur if there is
+ * no space on the queue to post a message - indicating that the
+ * semaphore was not first obtained correctly.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( TickType_t ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ </pre>
+ * \defgroup xSemaphoreGive xSemaphoreGive
+ * \ingroup Semaphores
+ */
+#define xSemaphoreGive( xSemaphore )		xQueueGenericSend( ( QueueHandle_t ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK )
+
+/**
+ * semphr. h
+ * <pre>xSemaphoreGiveRecursive( SemaphoreHandle_t xMutex )</pre>
+ *
+ * <i>Macro</i> to recursively release, or 'give', a mutex type semaphore.
+ * The mutex must have previously been created using a call to
+ * xSemaphoreCreateRecursiveMutex();
+ *
+ * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this
+ * macro to be available.
+ *
+ * This macro must not be used on mutexes created using xSemaphoreCreateMutex().
+ *
+ * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex
+ * doesn't become available again until the owner has called
+ * xSemaphoreGiveRecursive() for each successful 'take' request.  For example,
+ * if a task successfully 'takes' the same mutex 5 times then the mutex will
+ * not be available to any other task until it has also  'given' the mutex back
+ * exactly five times.
+ *
+ * @param xMutex A handle to the mutex being released, or 'given'.  This is the
+ * handle returned by xSemaphoreCreateMutex();
+ *
+ * @return pdTRUE if the semaphore was given.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.
+        if( xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( TickType_t ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ </pre>
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive
+ * \ingroup Semaphores
+ */
+#define xSemaphoreGiveRecursive( xMutex )	xQueueGiveMutexRecursive( ( xMutex ) )
+
+/*
+ * xSemaphoreAltGive() is an alternative version of xSemaphoreGive().
+ *
+ * The source code that implements the alternative (Alt) API is much
+ * simpler	because it executes everything from within a critical section.
+ * This is	the approach taken by many other RTOSes, but FreeRTOS.org has the
+ * preferred fully featured API too.  The fully featured API has more
+ * complex	code that takes longer to execute, but makes much less use of
+ * critical sections.  Therefore the alternative API sacrifices interrupt
+ * responsiveness to gain execution speed, whereas the fully featured API
+ * sacrifices execution speed to ensure better interrupt responsiveness.
+ */
+#define xSemaphoreAltGive( xSemaphore )		xQueueAltGenericSend( ( QueueHandle_t ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK )
+
+/**
+ * semphr. h
+ * <pre>
+ xSemaphoreGiveFromISR(
+                          SemaphoreHandle_t xSemaphore,
+                          BaseType_t *pxHigherPriorityTaskWoken
+                      )</pre>
+ *
+ * <i>Macro</i> to  release a semaphore.  The semaphore must have previously been
+ * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting().
+ *
+ * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex())
+ * must not be used with this macro.
+ *
+ * This macro can be used from an ISR.
+ *
+ * @param xSemaphore A handle to the semaphore being released.  This is the
+ * handle returned when the semaphore was created.
+ *
+ * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task
+ * to unblock, and the unblocked task has a priority higher than the currently
+ * running task.  If xSemaphoreGiveFromISR() sets this value to pdTRUE then
+ * a context switch should be requested before the interrupt is exited.
+ *
+ * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL.
+ *
+ * Example usage:
+ <pre>
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ SemaphoreHandle_t xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static uint8_t ucLocalTickCount = 0;
+ static BaseType_t xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ </pre>
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR
+ * \ingroup Semaphores
+ */
+#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken )	xQueueGiveFromISR( ( QueueHandle_t ) ( xSemaphore ), ( pxHigherPriorityTaskWoken ) )
+
+/**
+ * semphr. h
+ * <pre>
+ xSemaphoreTakeFromISR(
+                          SemaphoreHandle_t xSemaphore,
+                          BaseType_t *pxHigherPriorityTaskWoken
+                      )</pre>
+ *
+ * <i>Macro</i> to  take a semaphore from an ISR.  The semaphore must have
+ * previously been created with a call to vSemaphoreCreateBinary() or
+ * xSemaphoreCreateCounting().
+ *
+ * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex())
+ * must not be used with this macro.
+ *
+ * This macro can be used from an ISR, however taking a semaphore from an ISR
+ * is not a common operation.  It is likely to only be useful when taking a
+ * counting semaphore when an interrupt is obtaining an object from a resource
+ * pool (when the semaphore count indicates the number of resources available).
+ *
+ * @param xSemaphore A handle to the semaphore being taken.  This is the
+ * handle returned when the semaphore was created.
+ *
+ * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task
+ * to unblock, and the unblocked task has a priority higher than the currently
+ * running task.  If xSemaphoreTakeFromISR() sets this value to pdTRUE then
+ * a context switch should be requested before the interrupt is exited.
+ *
+ * @return pdTRUE if the semaphore was successfully taken, otherwise
+ * pdFALSE
+ */
+#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken )	xQueueReceiveFromISR( ( QueueHandle_t ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) )
+
+/**
+ * semphr. h
+ * <pre>SemaphoreHandle_t xSemaphoreCreateMutex( void )</pre>
+ *
+ * <i>Macro</i> that implements a mutex semaphore by using the existing queue
+ * mechanism.
+ *
+ * Mutexes created using this macro can be accessed using the xSemaphoreTake()
+ * and xSemaphoreGive() macros.  The xSemaphoreTakeRecursive() and
+ * xSemaphoreGiveRecursive() macros should not be used.
+ *
+ * This type of semaphore uses a priority inheritance mechanism so a task
+ * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the
+ * semaphore it is no longer required.
+ *
+ * Mutex type semaphores cannot be used from within interrupt service routines.
+ *
+ * See vSemaphoreCreateBinary() for an alternative implementation that can be
+ * used for pure synchronisation (where one task or interrupt always 'gives' the
+ * semaphore and another always 'takes' the semaphore) and from within interrupt
+ * service routines.
+ *
+ * @return xSemaphore Handle to the created mutex semaphore.  Should be of type
+ *		SemaphoreHandle_t.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ </pre>
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex
+ * \ingroup Semaphores
+ */
+#define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX )
+
+
+/**
+ * semphr. h
+ * <pre>SemaphoreHandle_t xSemaphoreCreateRecursiveMutex( void )</pre>
+ *
+ * <i>Macro</i> that implements a recursive mutex by using the existing queue
+ * mechanism.
+ *
+ * Mutexes created using this macro can be accessed using the
+ * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros.  The
+ * xSemaphoreTake() and xSemaphoreGive() macros should not be used.
+ *
+ * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex
+ * doesn't become available again until the owner has called
+ * xSemaphoreGiveRecursive() for each successful 'take' request.  For example,
+ * if a task successfully 'takes' the same mutex 5 times then the mutex will
+ * not be available to any other task until it has also  'given' the mutex back
+ * exactly five times.
+ *
+ * This type of semaphore uses a priority inheritance mechanism so a task
+ * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the
+ * semaphore it is no longer required.
+ *
+ * Mutex type semaphores cannot be used from within interrupt service routines.
+ *
+ * See vSemaphoreCreateBinary() for an alternative implementation that can be
+ * used for pure synchronisation (where one task or interrupt always 'gives' the
+ * semaphore and another always 'takes' the semaphore) and from within interrupt
+ * service routines.
+ *
+ * @return xSemaphore Handle to the created mutex semaphore.  Should be of type
+ *		SemaphoreHandle_t.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ </pre>
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex
+ * \ingroup Semaphores
+ */
+#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX )
+
+/**
+ * semphr. h
+ * <pre>SemaphoreHandle_t xSemaphoreCreateCounting( UBaseType_t uxMaxCount, UBaseType_t uxInitialCount )</pre>
+ *
+ * <i>Macro</i> that creates a counting semaphore by using the existing
+ * queue mechanism.
+ *
+ * Counting semaphores are typically used for two things:
+ *
+ * 1) Counting events.
+ *
+ *    In this usage scenario an event handler will 'give' a semaphore each time
+ *    an event occurs (incrementing the semaphore count value), and a handler
+ *    task will 'take' a semaphore each time it processes an event
+ *    (decrementing the semaphore count value).  The count value is therefore
+ *    the difference between the number of events that have occurred and the
+ *    number that have been processed.  In this case it is desirable for the
+ *    initial count value to be zero.
+ *
+ * 2) Resource management.
+ *
+ *    In this usage scenario the count value indicates the number of resources
+ *    available.  To obtain control of a resource a task must first obtain a
+ *    semaphore - decrementing the semaphore count value.  When the count value
+ *    reaches zero there are no free resources.  When a task finishes with the
+ *    resource it 'gives' the semaphore back - incrementing the semaphore count
+ *    value.  In this case it is desirable for the initial count value to be
+ *    equal to the maximum count value, indicating that all resources are free.
+ *
+ * @param uxMaxCount The maximum count value that can be reached.  When the
+ *        semaphore reaches this value it can no longer be 'given'.
+ *
+ * @param uxInitialCount The count value assigned to the semaphore when it is
+ *        created.
+ *
+ * @return Handle to the created semaphore.  Null if the semaphore could not be
+ *         created.
+ *
+ * Example usage:
+ <pre>
+ SemaphoreHandle_t xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ SemaphoreHandle_t xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.
+    }
+ }
+ </pre>
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting
+ * \ingroup Semaphores
+ */
+#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) )
+
+/**
+ * semphr. h
+ * <pre>void vSemaphoreDelete( SemaphoreHandle_t xSemaphore );</pre>
+ *
+ * Delete a semaphore.  This function must be used with care.  For example,
+ * do not delete a mutex type semaphore if the mutex is held by a task.
+ *
+ * @param xSemaphore A handle to the semaphore to be deleted.
+ *
+ * \defgroup vSemaphoreDelete vSemaphoreDelete
+ * \ingroup Semaphores
+ */
+#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( QueueHandle_t ) ( xSemaphore ) )
+
+/**
+ * semphr.h
+ * <pre>TaskHandle_t xSemaphoreGetMutexHolder( SemaphoreHandle_t xMutex );</pre>
+ *
+ * If xMutex is indeed a mutex type semaphore, return the current mutex holder.
+ * If xMutex is not a mutex type semaphore, or the mutex is available (not held
+ * by a task), return NULL.
+ *
+ * Note: This is a good way of determining if the calling task is the mutex
+ * holder, but not a good way of determining the identity of the mutex holder as
+ * the holder may change between the function exiting and the returned value
+ * being tested.
+ */
+#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) )
+
+#endif /* SEMAPHORE_H */
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/task.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/task.h
new file mode 100644
index 0000000000000000000000000000000000000000..b8d6dd89094179130a8ddcfac6ccda5bd341be98
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/task.h
@@ -0,0 +1,2037 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+#ifndef INC_TASK_H
+#define INC_TASK_H
+
+#ifndef INC_FREERTOS_H
+	#error "include FreeRTOS.h must appear in source files before include task.h"
+#endif
+
+#include "list.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*-----------------------------------------------------------
+ * MACROS AND DEFINITIONS
+ *----------------------------------------------------------*/
+
+#define tskKERNEL_VERSION_NUMBER "V8.2.3"
+#define tskKERNEL_VERSION_MAJOR 8
+#define tskKERNEL_VERSION_MINOR 2
+#define tskKERNEL_VERSION_BUILD 3
+
+/**
+ * task. h
+ *
+ * Type by which tasks are referenced.  For example, a call to xTaskCreate
+ * returns (via a pointer parameter) an TaskHandle_t variable that can then
+ * be used as a parameter to vTaskDelete to delete the task.
+ *
+ * \defgroup TaskHandle_t TaskHandle_t
+ * \ingroup Tasks
+ */
+typedef void * TaskHandle_t;
+
+/*
+ * Defines the prototype to which the application task hook function must
+ * conform.
+ */
+typedef BaseType_t (*TaskHookFunction_t)( void * );
+
+/* Task states returned by eTaskGetState. */
+typedef enum
+{
+	eRunning = 0,	/* A task is querying the state of itself, so must be running. */
+	eReady,			/* The task being queried is in a read or pending ready list. */
+	eBlocked,		/* The task being queried is in the Blocked state. */
+	eSuspended,		/* The task being queried is in the Suspended state, or is in the Blocked state with an infinite time out. */
+	eDeleted		/* The task being queried has been deleted, but its TCB has not yet been freed. */
+} eTaskState;
+
+/* Actions that can be performed when vTaskNotify() is called. */
+typedef enum
+{
+	eNoAction = 0,				/* Notify the task without updating its notify value. */
+	eSetBits,					/* Set bits in the task's notification value. */
+	eIncrement,					/* Increment the task's notification value. */
+	eSetValueWithOverwrite,		/* Set the task's notification value to a specific value even if the previous value has not yet been read by the task. */
+	eSetValueWithoutOverwrite	/* Set the task's notification value if the previous value has been read by the task. */
+} eNotifyAction;
+
+/*
+ * Used internally only.
+ */
+typedef struct xTIME_OUT
+{
+	BaseType_t xOverflowCount;
+	TickType_t xTimeOnEntering;
+} TimeOut_t;
+
+/*
+ * Defines the memory ranges allocated to the task when an MPU is used.
+ */
+typedef struct xMEMORY_REGION
+{
+	void *pvBaseAddress;
+	uint32_t ulLengthInBytes;
+	uint32_t ulParameters;
+} MemoryRegion_t;
+
+/*
+ * Parameters required to create an MPU protected task.
+ */
+typedef struct xTASK_PARAMETERS
+{
+	TaskFunction_t pvTaskCode;
+	const char * const pcName;	/*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+	uint16_t usStackDepth;
+	void *pvParameters;
+	UBaseType_t uxPriority;
+	StackType_t *puxStackBuffer;
+	MemoryRegion_t xRegions[ portNUM_CONFIGURABLE_REGIONS ];
+} TaskParameters_t;
+
+/* Used with the uxTaskGetSystemState() function to return the state of each task
+in the system. */
+typedef struct xTASK_STATUS
+{
+	TaskHandle_t xHandle;			/* The handle of the task to which the rest of the information in the structure relates. */
+	const char *pcTaskName;			/* A pointer to the task's name.  This value will be invalid if the task was deleted since the structure was populated! */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+	UBaseType_t xTaskNumber;		/* A number unique to the task. */
+	eTaskState eCurrentState;		/* The state in which the task existed when the structure was populated. */
+	UBaseType_t uxCurrentPriority;	/* The priority at which the task was running (may be inherited) when the structure was populated. */
+	UBaseType_t uxBasePriority;		/* The priority to which the task will return if the task's current priority has been inherited to avoid unbounded priority inversion when obtaining a mutex.  Only valid if configUSE_MUTEXES is defined as 1 in FreeRTOSConfig.h. */
+	uint32_t ulRunTimeCounter;		/* The total run time allocated to the task so far, as defined by the run time stats clock.  See http://www.freertos.org/rtos-run-time-stats.html.  Only valid when configGENERATE_RUN_TIME_STATS is defined as 1 in FreeRTOSConfig.h. */
+	uint16_t usStackHighWaterMark;	/* The minimum amount of stack space that has remained for the task since the task was created.  The closer this value is to zero the closer the task has come to overflowing its stack. */
+} TaskStatus_t;
+
+/* Possible return values for eTaskConfirmSleepModeStatus(). */
+typedef enum
+{
+	eAbortSleep = 0,		/* A task has been made ready or a context switch pended since portSUPPORESS_TICKS_AND_SLEEP() was called - abort entering a sleep mode. */
+	eStandardSleep,			/* Enter a sleep mode that will not last any longer than the expected idle time. */
+	eNoTasksWaitingTimeout	/* No tasks are waiting for a timeout so it is safe to enter a sleep mode that can only be exited by an external interrupt. */
+} eSleepModeStatus;
+
+
+/**
+ * Defines the priority used by the idle task.  This must not be modified.
+ *
+ * \ingroup TaskUtils
+ */
+#define tskIDLE_PRIORITY			( ( UBaseType_t ) 0U )
+
+/**
+ * task. h
+ *
+ * Macro for forcing a context switch.
+ *
+ * \defgroup taskYIELD taskYIELD
+ * \ingroup SchedulerControl
+ */
+#define taskYIELD()					portYIELD()
+
+/**
+ * task. h
+ *
+ * Macro to mark the start of a critical code region.  Preemptive context
+ * switches cannot occur when in a critical region.
+ *
+ * NOTE: This may alter the stack (depending on the portable implementation)
+ * so must be used with care!
+ *
+ * \defgroup taskENTER_CRITICAL taskENTER_CRITICAL
+ * \ingroup SchedulerControl
+ */
+#define taskENTER_CRITICAL()		portENTER_CRITICAL()
+#define taskENTER_CRITICAL_FROM_ISR() portSET_INTERRUPT_MASK_FROM_ISR()
+
+/**
+ * task. h
+ *
+ * Macro to mark the end of a critical code region.  Preemptive context
+ * switches cannot occur when in a critical region.
+ *
+ * NOTE: This may alter the stack (depending on the portable implementation)
+ * so must be used with care!
+ *
+ * \defgroup taskEXIT_CRITICAL taskEXIT_CRITICAL
+ * \ingroup SchedulerControl
+ */
+#define taskEXIT_CRITICAL()			portEXIT_CRITICAL()
+#define taskEXIT_CRITICAL_FROM_ISR( x ) portCLEAR_INTERRUPT_MASK_FROM_ISR( x )
+/**
+ * task. h
+ *
+ * Macro to disable all maskable interrupts.
+ *
+ * \defgroup taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS
+ * \ingroup SchedulerControl
+ */
+#define taskDISABLE_INTERRUPTS()	portDISABLE_INTERRUPTS()
+
+/**
+ * task. h
+ *
+ * Macro to enable microcontroller interrupts.
+ *
+ * \defgroup taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS
+ * \ingroup SchedulerControl
+ */
+#define taskENABLE_INTERRUPTS()		portENABLE_INTERRUPTS()
+
+/* Definitions returned by xTaskGetSchedulerState().  taskSCHEDULER_SUSPENDED is
+0 to generate more optimal code when configASSERT() is defined as the constant
+is used in assert() statements. */
+#define taskSCHEDULER_SUSPENDED		( ( BaseType_t ) 0 )
+#define taskSCHEDULER_NOT_STARTED	( ( BaseType_t ) 1 )
+#define taskSCHEDULER_RUNNING		( ( BaseType_t ) 2 )
+
+
+/*-----------------------------------------------------------
+ * TASK CREATION API
+ *----------------------------------------------------------*/
+
+/**
+ * task. h
+ *<pre>
+ BaseType_t xTaskCreate(
+							  TaskFunction_t pvTaskCode,
+							  const char * const pcName,
+							  uint16_t usStackDepth,
+							  void *pvParameters,
+							  UBaseType_t uxPriority,
+							  TaskHandle_t *pvCreatedTask
+						  );</pre>
+ *
+ * Create a new task and add it to the list of tasks that are ready to run.
+ *
+ * xTaskCreate() can only be used to create a task that has unrestricted
+ * access to the entire microcontroller memory map.  Systems that include MPU
+ * support can alternatively create an MPU constrained task using
+ * xTaskCreateRestricted().
+ *
+ * @param pvTaskCode Pointer to the task entry function.  Tasks
+ * must be implemented to never return (i.e. continuous loop).
+ *
+ * @param pcName A descriptive name for the task.  This is mainly used to
+ * facilitate debugging.  Max length defined by configMAX_TASK_NAME_LEN - default
+ * is 16.
+ *
+ * @param usStackDepth The size of the task stack specified as the number of
+ * variables the stack can hold - not the number of bytes.  For example, if
+ * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes
+ * will be allocated for stack storage.
+ *
+ * @param pvParameters Pointer that will be used as the parameter for the task
+ * being created.
+ *
+ * @param uxPriority The priority at which the task should run.  Systems that
+ * include MPU support can optionally create tasks in a privileged (system)
+ * mode by setting bit portPRIVILEGE_BIT of the priority parameter.  For
+ * example, to create a privileged task at priority 2 the uxPriority parameter
+ * should be set to ( 2 | portPRIVILEGE_BIT ).
+ *
+ * @param pvCreatedTask Used to pass back a handle by which the created task
+ * can be referenced.
+ *
+ * @return pdPASS if the task was successfully created and added to a ready
+ * list, otherwise an error code defined in the file projdefs.h
+ *
+ * Example usage:
+   <pre>
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static uint8_t ucParameterToPass;
+ TaskHandle_t xHandle = NULL;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+     configASSERT( xHandle );
+
+	 // Use the handle to delete the task.
+     if( xHandle != NULL )
+     {
+	     vTaskDelete( xHandle );
+     }
+ }
+   </pre>
+ * \defgroup xTaskCreate xTaskCreate
+ * \ingroup Tasks
+ */
+#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) )
+
+/**
+ * task. h
+ *<pre>
+ BaseType_t xTaskCreateRestricted( TaskParameters_t *pxTaskDefinition, TaskHandle_t *pxCreatedTask );</pre>
+ *
+ * xTaskCreateRestricted() should only be used in systems that include an MPU
+ * implementation.
+ *
+ * Create a new task and add it to the list of tasks that are ready to run.
+ * The function parameters define the memory regions and associated access
+ * permissions allocated to the task.
+ *
+ * @param pxTaskDefinition Pointer to a structure that contains a member
+ * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API
+ * documentation) plus an optional stack buffer and the memory region
+ * definitions.
+ *
+ * @param pxCreatedTask Used to pass back a handle by which the created task
+ * can be referenced.
+ *
+ * @return pdPASS if the task was successfully created and added to a ready
+ * list, otherwise an error code defined in the file projdefs.h
+ *
+ * Example usage:
+   <pre>
+// Create an TaskParameters_t structure that defines the task to be created.
+static const TaskParameters_t xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+TaskHandle_t xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// and/or timer task.
+	for( ;; );
+}
+   </pre>
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted
+ * \ingroup Tasks
+ */
+#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) )
+
+/**
+ * task. h
+ *<pre>
+ void vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions );</pre>
+ *
+ * Memory regions are assigned to a restricted task when the task is created by
+ * a call to xTaskCreateRestricted().  These regions can be redefined using
+ * vTaskAllocateMPURegions().
+ *
+ * @param xTask The handle of the task being updated.
+ *
+ * @param xRegions A pointer to an MemoryRegion_t structure that contains the
+ * new memory region definitions.
+ *
+ * Example usage:
+   <pre>
+// Define an array of MemoryRegion_t structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const MemoryRegion_t xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   </pre>
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted
+ * \ingroup Tasks
+ */
+void vTaskAllocateMPURegions( TaskHandle_t xTask, const MemoryRegion_t * const pxRegions ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void vTaskDelete( TaskHandle_t xTask );</pre>
+ *
+ * INCLUDE_vTaskDelete must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ * Remove a task from the RTOS real time kernel's management.  The task being
+ * deleted will be removed from all ready, blocked, suspended and event lists.
+ *
+ * NOTE:  The idle task is responsible for freeing the kernel allocated
+ * memory from tasks that have been deleted.  It is therefore important that
+ * the idle task is not starved of microcontroller processing time if your
+ * application makes any calls to vTaskDelete ().  Memory allocated by the
+ * task code is not automatically freed, and should be freed before the task
+ * is deleted.
+ *
+ * See the demo application file death.c for sample code that utilises
+ * vTaskDelete ().
+ *
+ * @param xTask The handle of the task to be deleted.  Passing NULL will
+ * cause the calling task to be deleted.
+ *
+ * Example usage:
+   <pre>
+ void vOtherFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   </pre>
+ * \defgroup vTaskDelete vTaskDelete
+ * \ingroup Tasks
+ */
+void vTaskDelete( TaskHandle_t xTaskToDelete ) PRIVILEGED_FUNCTION;
+
+/*-----------------------------------------------------------
+ * TASK CONTROL API
+ *----------------------------------------------------------*/
+
+/**
+ * task. h
+ * <pre>void vTaskDelay( const TickType_t xTicksToDelay );</pre>
+ *
+ * Delay a task for a given number of ticks.  The actual time that the
+ * task remains blocked depends on the tick rate.  The constant
+ * portTICK_PERIOD_MS can be used to calculate real time from the tick
+ * rate - with the resolution of one tick period.
+ *
+ * INCLUDE_vTaskDelay must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ *
+ * vTaskDelay() specifies a time at which the task wishes to unblock relative to
+ * the time at which vTaskDelay() is called.  For example, specifying a block
+ * period of 100 ticks will cause the task to unblock 100 ticks after
+ * vTaskDelay() is called.  vTaskDelay() does not therefore provide a good method
+ * of controlling the frequency of a periodic task as the path taken through the
+ * code, as well as other task and interrupt activity, will effect the frequency
+ * at which vTaskDelay() gets called and therefore the time at which the task
+ * next executes.  See vTaskDelayUntil() for an alternative API function designed
+ * to facilitate fixed frequency execution.  It does this by specifying an
+ * absolute time (rather than a relative time) at which the calling task should
+ * unblock.
+ *
+ * @param xTicksToDelay The amount of time, in tick periods, that
+ * the calling task should block.
+ *
+ * Example usage:
+
+ void vTaskFunction( void * pvParameters )
+ {
+ // Block for 500ms.
+ const TickType_t xDelay = 500 / portTICK_PERIOD_MS;
+
+	 for( ;; )
+	 {
+		 // Simply toggle the LED every 500ms, blocking between each toggle.
+		 vToggleLED();
+		 vTaskDelay( xDelay );
+	 }
+ }
+
+ * \defgroup vTaskDelay vTaskDelay
+ * \ingroup TaskCtrl
+ */
+void vTaskDelay( const TickType_t xTicksToDelay ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void vTaskDelayUntil( TickType_t *pxPreviousWakeTime, const TickType_t xTimeIncrement );</pre>
+ *
+ * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ * Delay a task until a specified time.  This function can be used by periodic
+ * tasks to ensure a constant execution frequency.
+ *
+ * This function differs from vTaskDelay () in one important aspect:  vTaskDelay () will
+ * cause a task to block for the specified number of ticks from the time vTaskDelay () is
+ * called.  It is therefore difficult to use vTaskDelay () by itself to generate a fixed
+ * execution frequency as the time between a task starting to execute and that task
+ * calling vTaskDelay () may not be fixed [the task may take a different path though the
+ * code between calls, or may get interrupted or preempted a different number of times
+ * each time it executes].
+ *
+ * Whereas vTaskDelay () specifies a wake time relative to the time at which the function
+ * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to
+ * unblock.
+ *
+ * The constant portTICK_PERIOD_MS can be used to calculate real time from the tick
+ * rate - with the resolution of one tick period.
+ *
+ * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the
+ * task was last unblocked.  The variable must be initialised with the current time
+ * prior to its first use (see the example below).  Following this the variable is
+ * automatically updated within vTaskDelayUntil ().
+ *
+ * @param xTimeIncrement The cycle time period.  The task will be unblocked at
+ * time *pxPreviousWakeTime + xTimeIncrement.  Calling vTaskDelayUntil with the
+ * same xTimeIncrement parameter value will cause the task to execute with
+ * a fixed interface period.
+ *
+ * Example usage:
+   <pre>
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ TickType_t xLastWakeTime;
+ const TickType_t xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   </pre>
+ * \defgroup vTaskDelayUntil vTaskDelayUntil
+ * \ingroup TaskCtrl
+ */
+void vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>UBaseType_t uxTaskPriorityGet( TaskHandle_t xTask );</pre>
+ *
+ * INCLUDE_uxTaskPriorityGet must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ * Obtain the priority of any task.
+ *
+ * @param xTask Handle of the task to be queried.  Passing a NULL
+ * handle results in the priority of the calling task being returned.
+ *
+ * @return The priority of xTask.
+ *
+ * Example usage:
+   <pre>
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   </pre>
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet
+ * \ingroup TaskCtrl
+ */
+UBaseType_t uxTaskPriorityGet( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>UBaseType_t uxTaskPriorityGetFromISR( TaskHandle_t xTask );</pre>
+ *
+ * A version of uxTaskPriorityGet() that can be used from an ISR.
+ */
+UBaseType_t uxTaskPriorityGetFromISR( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>eTaskState eTaskGetState( TaskHandle_t xTask );</pre>
+ *
+ * INCLUDE_eTaskGetState must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ * Obtain the state of any task.  States are encoded by the eTaskState
+ * enumerated type.
+ *
+ * @param xTask Handle of the task to be queried.
+ *
+ * @return The state of xTask at the time the function was called.  Note the
+ * state of the task might change between the function being called, and the
+ * functions return value being tested by the calling task.
+ */
+eTaskState eTaskGetState( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority );</pre>
+ *
+ * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ * Set the priority of any task.
+ *
+ * A context switch will occur before the function returns if the priority
+ * being set is higher than the currently executing task.
+ *
+ * @param xTask Handle to the task for which the priority is being set.
+ * Passing a NULL handle results in the priority of the calling task being set.
+ *
+ * @param uxNewPriority The priority to which the task will be set.
+ *
+ * Example usage:
+   <pre>
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   </pre>
+ * \defgroup vTaskPrioritySet vTaskPrioritySet
+ * \ingroup TaskCtrl
+ */
+void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void vTaskSuspend( TaskHandle_t xTaskToSuspend );</pre>
+ *
+ * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ * Suspend any task.  When suspended a task will never get any microcontroller
+ * processing time, no matter what its priority.
+ *
+ * Calls to vTaskSuspend are not accumulative -
+ * i.e. calling vTaskSuspend () twice on the same task still only requires one
+ * call to vTaskResume () to ready the suspended task.
+ *
+ * @param xTaskToSuspend Handle to the task being suspended.  Passing a NULL
+ * handle will cause the calling task to be suspended.
+ *
+ * Example usage:
+   <pre>
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   </pre>
+ * \defgroup vTaskSuspend vTaskSuspend
+ * \ingroup TaskCtrl
+ */
+void vTaskSuspend( TaskHandle_t xTaskToSuspend ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void vTaskResume( TaskHandle_t xTaskToResume );</pre>
+ *
+ * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available.
+ * See the configuration section for more information.
+ *
+ * Resumes a suspended task.
+ *
+ * A task that has been suspended by one or more calls to vTaskSuspend ()
+ * will be made available for running again by a single call to
+ * vTaskResume ().
+ *
+ * @param xTaskToResume Handle to the task being readied.
+ *
+ * Example usage:
+   <pre>
+ void vAFunction( void )
+ {
+ TaskHandle_t xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with its priority within the system.
+ }
+   </pre>
+ * \defgroup vTaskResume vTaskResume
+ * \ingroup TaskCtrl
+ */
+void vTaskResume( TaskHandle_t xTaskToResume ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void xTaskResumeFromISR( TaskHandle_t xTaskToResume );</pre>
+ *
+ * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be
+ * available.  See the configuration section for more information.
+ *
+ * An implementation of vTaskResume() that can be called from within an ISR.
+ *
+ * A task that has been suspended by one or more calls to vTaskSuspend ()
+ * will be made available for running again by a single call to
+ * xTaskResumeFromISR ().
+ *
+ * xTaskResumeFromISR() should not be used to synchronise a task with an
+ * interrupt if there is a chance that the interrupt could arrive prior to the
+ * task being suspended - as this can lead to interrupts being missed. Use of a
+ * semaphore as a synchronisation mechanism would avoid this eventuality.
+ *
+ * @param xTaskToResume Handle to the task being readied.
+ *
+ * @return pdTRUE if resuming the task should result in a context switch,
+ * otherwise pdFALSE. This is used by the ISR to determine if a context switch
+ * may be required following the ISR.
+ *
+ * \defgroup vTaskResumeFromISR vTaskResumeFromISR
+ * \ingroup TaskCtrl
+ */
+BaseType_t xTaskResumeFromISR( TaskHandle_t xTaskToResume ) PRIVILEGED_FUNCTION;
+
+/*-----------------------------------------------------------
+ * SCHEDULER CONTROL
+ *----------------------------------------------------------*/
+
+/**
+ * task. h
+ * <pre>void vTaskStartScheduler( void );</pre>
+ *
+ * Starts the real time kernel tick processing.  After calling the kernel
+ * has control over which tasks are executed and when.
+ *
+ * See the demo application file main.c for an example of creating
+ * tasks and starting the kernel.
+ *
+ * Example usage:
+   <pre>
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   </pre>
+ *
+ * \defgroup vTaskStartScheduler vTaskStartScheduler
+ * \ingroup SchedulerControl
+ */
+void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void vTaskEndScheduler( void );</pre>
+ *
+ * NOTE:  At the time of writing only the x86 real mode port, which runs on a PC
+ * in place of DOS, implements this function.
+ *
+ * Stops the real time kernel tick.  All created tasks will be automatically
+ * deleted and multitasking (either preemptive or cooperative) will
+ * stop.  Execution then resumes from the point where vTaskStartScheduler ()
+ * was called, as if vTaskStartScheduler () had just returned.
+ *
+ * See the demo application file main. c in the demo/PC directory for an
+ * example that uses vTaskEndScheduler ().
+ *
+ * vTaskEndScheduler () requires an exit function to be defined within the
+ * portable layer (see vPortEndScheduler () in port. c for the PC port).  This
+ * performs hardware specific operations such as stopping the kernel tick.
+ *
+ * vTaskEndScheduler () will cause all of the resources allocated by the
+ * kernel to be freed - but will not free resources allocated by application
+ * tasks.
+ *
+ * Example usage:
+   <pre>
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   </pre>
+ *
+ * \defgroup vTaskEndScheduler vTaskEndScheduler
+ * \ingroup SchedulerControl
+ */
+void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>void vTaskSuspendAll( void );</pre>
+ *
+ * Suspends the scheduler without disabling interrupts.  Context switches will
+ * not occur while the scheduler is suspended.
+ *
+ * After calling vTaskSuspendAll () the calling task will continue to execute
+ * without risk of being swapped out until a call to xTaskResumeAll () has been
+ * made.
+ *
+ * API functions that have the potential to cause a context switch (for example,
+ * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler
+ * is suspended.
+ *
+ * Example usage:
+   <pre>
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   </pre>
+ * \defgroup vTaskSuspendAll vTaskSuspendAll
+ * \ingroup SchedulerControl
+ */
+void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <pre>BaseType_t xTaskResumeAll( void );</pre>
+ *
+ * Resumes scheduler activity after it was suspended by a call to
+ * vTaskSuspendAll().
+ *
+ * xTaskResumeAll() only resumes the scheduler.  It does not unsuspend tasks
+ * that were previously suspended by a call to vTaskSuspend().
+ *
+ * @return If resuming the scheduler caused a context switch then pdTRUE is
+ *		  returned, otherwise pdFALSE is returned.
+ *
+ * Example usage:
+   <pre>
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   </pre>
+ * \defgroup xTaskResumeAll xTaskResumeAll
+ * \ingroup SchedulerControl
+ */
+BaseType_t xTaskResumeAll( void ) PRIVILEGED_FUNCTION;
+
+/*-----------------------------------------------------------
+ * TASK UTILITIES
+ *----------------------------------------------------------*/
+
+/**
+ * task. h
+ * <PRE>TickType_t xTaskGetTickCount( void );</PRE>
+ *
+ * @return The count of ticks since vTaskStartScheduler was called.
+ *
+ * \defgroup xTaskGetTickCount xTaskGetTickCount
+ * \ingroup TaskUtils
+ */
+TickType_t xTaskGetTickCount( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <PRE>TickType_t xTaskGetTickCountFromISR( void );</PRE>
+ *
+ * @return The count of ticks since vTaskStartScheduler was called.
+ *
+ * This is a version of xTaskGetTickCount() that is safe to be called from an
+ * ISR - provided that TickType_t is the natural word size of the
+ * microcontroller being used or interrupt nesting is either not supported or
+ * not being used.
+ *
+ * \defgroup xTaskGetTickCountFromISR xTaskGetTickCountFromISR
+ * \ingroup TaskUtils
+ */
+TickType_t xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <PRE>uint16_t uxTaskGetNumberOfTasks( void );</PRE>
+ *
+ * @return The number of tasks that the real time kernel is currently managing.
+ * This includes all ready, blocked and suspended tasks.  A task that
+ * has been deleted but not yet freed by the idle task will also be
+ * included in the count.
+ *
+ * \defgroup uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks
+ * \ingroup TaskUtils
+ */
+UBaseType_t uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <PRE>char *pcTaskGetTaskName( TaskHandle_t xTaskToQuery );</PRE>
+ *
+ * @return The text (human readable) name of the task referenced by the handle
+ * xTaskToQuery.  A task can query its own name by either passing in its own
+ * handle, or by setting xTaskToQuery to NULL.  INCLUDE_pcTaskGetTaskName must be
+ * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available.
+ *
+ * \defgroup pcTaskGetTaskName pcTaskGetTaskName
+ * \ingroup TaskUtils
+ */
+char *pcTaskGetTaskName( TaskHandle_t xTaskToQuery ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+/**
+ * task.h
+ * <PRE>UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask );</PRE>
+ *
+ * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for
+ * this function to be available.
+ *
+ * Returns the high water mark of the stack associated with xTask.  That is,
+ * the minimum free stack space there has been (in words, so on a 32 bit machine
+ * a value of 1 means 4 bytes) since the task started.  The smaller the returned
+ * number the closer the task has come to overflowing its stack.
+ *
+ * @param xTask Handle of the task associated with the stack to be checked.
+ * Set xTask to NULL to check the stack of the calling task.
+ *
+ * @return The smallest amount of free stack space there has been (in words, so
+ * actual spaces on the stack rather than bytes) since the task referenced by
+ * xTask was created.
+ */
+UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
+
+/* When using trace macros it is sometimes necessary to include task.h before
+FreeRTOS.h.  When this is done TaskHookFunction_t will not yet have been defined,
+so the following two prototypes will cause a compilation error.  This can be
+fixed by simply guarding against the inclusion of these two prototypes unless
+they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration
+constant. */
+#ifdef configUSE_APPLICATION_TASK_TAG
+	#if configUSE_APPLICATION_TASK_TAG == 1
+		/**
+		 * task.h
+		 * <pre>void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction );</pre>
+		 *
+		 * Sets pxHookFunction to be the task hook function used by the task xTask.
+		 * Passing xTask as NULL has the effect of setting the calling tasks hook
+		 * function.
+		 */
+		void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction ) PRIVILEGED_FUNCTION;
+
+		/**
+		 * task.h
+		 * <pre>void xTaskGetApplicationTaskTag( TaskHandle_t xTask );</pre>
+		 *
+		 * Returns the pxHookFunction value assigned to the task xTask.
+		 */
+		TaskHookFunction_t xTaskGetApplicationTaskTag( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
+	#endif /* configUSE_APPLICATION_TASK_TAG ==1 */
+#endif /* ifdef configUSE_APPLICATION_TASK_TAG */
+
+#if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 )
+
+	/* Each task contains an array of pointers that is dimensioned by the
+	configNUM_THREAD_LOCAL_STORAGE_POINTERS setting in FreeRTOSConfig.h.  The
+	kernel does not use the pointers itself, so the application writer can use
+	the pointers for any purpose they wish.  The following two functions are
+	used to set and query a pointer respectively. */
+	void vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue ) PRIVILEGED_FUNCTION;
+	void *pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex ) PRIVILEGED_FUNCTION;
+
+#endif
+
+/**
+ * task.h
+ * <pre>BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter );</pre>
+ *
+ * Calls the hook function associated with xTask.  Passing xTask as NULL has
+ * the effect of calling the Running tasks (the calling task) hook function.
+ *
+ * pvParameter is passed to the hook function for the task to interpret as it
+ * wants.  The return value is the value returned by the task hook function
+ * registered by the user.
+ */
+BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter ) PRIVILEGED_FUNCTION;
+
+/**
+ * xTaskGetIdleTaskHandle() is only available if
+ * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h.
+ *
+ * Simply returns the handle of the idle task.  It is not valid to call
+ * xTaskGetIdleTaskHandle() before the scheduler has been started.
+ */
+TaskHandle_t xTaskGetIdleTaskHandle( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * configUSE_TRACE_FACILITY must be defined as 1 in FreeRTOSConfig.h for
+ * uxTaskGetSystemState() to be available.
+ *
+ * uxTaskGetSystemState() populates an TaskStatus_t structure for each task in
+ * the system.  TaskStatus_t structures contain, among other things, members
+ * for the task handle, task name, task priority, task state, and total amount
+ * of run time consumed by the task.  See the TaskStatus_t structure
+ * definition in this file for the full member list.
+ *
+ * NOTE:  This function is intended for debugging use only as its use results in
+ * the scheduler remaining suspended for an extended period.
+ *
+ * @param pxTaskStatusArray A pointer to an array of TaskStatus_t structures.
+ * The array must contain at least one TaskStatus_t structure for each task
+ * that is under the control of the RTOS.  The number of tasks under the control
+ * of the RTOS can be determined using the uxTaskGetNumberOfTasks() API function.
+ *
+ * @param uxArraySize The size of the array pointed to by the pxTaskStatusArray
+ * parameter.  The size is specified as the number of indexes in the array, or
+ * the number of TaskStatus_t structures contained in the array, not by the
+ * number of bytes in the array.
+ *
+ * @param pulTotalRunTime If configGENERATE_RUN_TIME_STATS is set to 1 in
+ * FreeRTOSConfig.h then *pulTotalRunTime is set by uxTaskGetSystemState() to the
+ * total run time (as defined by the run time stats clock, see
+ * http://www.freertos.org/rtos-run-time-stats.html) since the target booted.
+ * pulTotalRunTime can be set to NULL to omit the total run time information.
+ *
+ * @return The number of TaskStatus_t structures that were populated by
+ * uxTaskGetSystemState().  This should equal the number returned by the
+ * uxTaskGetNumberOfTasks() API function, but will be zero if the value passed
+ * in the uxArraySize parameter was too small.
+ *
+ * Example usage:
+   <pre>
+    // This example demonstrates how a human readable table of run time stats
+	// information is generated from raw data provided by uxTaskGetSystemState().
+	// The human readable table is written to pcWriteBuffer
+	void vTaskGetRunTimeStats( char *pcWriteBuffer )
+	{
+	TaskStatus_t *pxTaskStatusArray;
+	volatile UBaseType_t uxArraySize, x;
+	uint32_t ulTotalRunTime, ulStatsAsPercentage;
+
+		// Make sure the write buffer does not contain a string.
+		*pcWriteBuffer = 0x00;
+
+		// Take a snapshot of the number of tasks in case it changes while this
+		// function is executing.
+		uxArraySize = uxTaskGetNumberOfTasks();
+
+		// Allocate a TaskStatus_t structure for each task.  An array could be
+		// allocated statically at compile time.
+		pxTaskStatusArray = pvPortMalloc( uxArraySize * sizeof( TaskStatus_t ) );
+
+		if( pxTaskStatusArray != NULL )
+		{
+			// Generate raw status information about each task.
+			uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, &ulTotalRunTime );
+
+			// For percentage calculations.
+			ulTotalRunTime /= 100UL;
+
+			// Avoid divide by zero errors.
+			if( ulTotalRunTime > 0 )
+			{
+				// For each populated position in the pxTaskStatusArray array,
+				// format the raw data as human readable ASCII data
+				for( x = 0; x < uxArraySize; x++ )
+				{
+					// What percentage of the total run time has the task used?
+					// This will always be rounded down to the nearest integer.
+					// ulTotalRunTimeDiv100 has already been divided by 100.
+					ulStatsAsPercentage = pxTaskStatusArray[ x ].ulRunTimeCounter / ulTotalRunTime;
+
+					if( ulStatsAsPercentage > 0UL )
+					{
+						sprintf( pcWriteBuffer, "%s\t\t%lu\t\t%lu%%\r\n", pxTaskStatusArray[ x ].pcTaskName, pxTaskStatusArray[ x ].ulRunTimeCounter, ulStatsAsPercentage );
+					}
+					else
+					{
+						// If the percentage is zero here then the task has
+						// consumed less than 1% of the total run time.
+						sprintf( pcWriteBuffer, "%s\t\t%lu\t\t<1%%\r\n", pxTaskStatusArray[ x ].pcTaskName, pxTaskStatusArray[ x ].ulRunTimeCounter );
+					}
+
+					pcWriteBuffer += strlen( ( char * ) pcWriteBuffer );
+				}
+			}
+
+			// The array is no longer needed, free the memory it consumes.
+			vPortFree( pxTaskStatusArray );
+		}
+	}
+	</pre>
+ */
+UBaseType_t uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <PRE>void vTaskList( char *pcWriteBuffer );</PRE>
+ *
+ * configUSE_TRACE_FACILITY and configUSE_STATS_FORMATTING_FUNCTIONS must
+ * both be defined as 1 for this function to be available.  See the
+ * configuration section of the FreeRTOS.org website for more information.
+ *
+ * NOTE 1: This function will disable interrupts for its duration.  It is
+ * not intended for normal application runtime use but as a debug aid.
+ *
+ * Lists all the current tasks, along with their current state and stack
+ * usage high water mark.
+ *
+ * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or
+ * suspended ('S').
+ *
+ * PLEASE NOTE:
+ *
+ * This function is provided for convenience only, and is used by many of the
+ * demo applications.  Do not consider it to be part of the scheduler.
+ *
+ * vTaskList() calls uxTaskGetSystemState(), then formats part of the
+ * uxTaskGetSystemState() output into a human readable table that displays task
+ * names, states and stack usage.
+ *
+ * vTaskList() has a dependency on the sprintf() C library function that might
+ * bloat the code size, use a lot of stack, and provide different results on
+ * different platforms.  An alternative, tiny, third party, and limited
+ * functionality implementation of sprintf() is provided in many of the
+ * FreeRTOS/Demo sub-directories in a file called printf-stdarg.c (note
+ * printf-stdarg.c does not provide a full snprintf() implementation!).
+ *
+ * It is recommended that production systems call uxTaskGetSystemState()
+ * directly to get access to raw stats data, rather than indirectly through a
+ * call to vTaskList().
+ *
+ * @param pcWriteBuffer A buffer into which the above mentioned details
+ * will be written, in ASCII form.  This buffer is assumed to be large
+ * enough to contain the generated report.  Approximately 40 bytes per
+ * task should be sufficient.
+ *
+ * \defgroup vTaskList vTaskList
+ * \ingroup TaskUtils
+ */
+void vTaskList( char * pcWriteBuffer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+/**
+ * task. h
+ * <PRE>void vTaskGetRunTimeStats( char *pcWriteBuffer );</PRE>
+ *
+ * configGENERATE_RUN_TIME_STATS and configUSE_STATS_FORMATTING_FUNCTIONS
+ * must both be defined as 1 for this function to be available.  The application
+ * must also then provide definitions for
+ * portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and portGET_RUN_TIME_COUNTER_VALUE()
+ * to configure a peripheral timer/counter and return the timers current count
+ * value respectively.  The counter should be at least 10 times the frequency of
+ * the tick count.
+ *
+ * NOTE 1: This function will disable interrupts for its duration.  It is
+ * not intended for normal application runtime use but as a debug aid.
+ *
+ * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total
+ * accumulated execution time being stored for each task.  The resolution
+ * of the accumulated time value depends on the frequency of the timer
+ * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro.
+ * Calling vTaskGetRunTimeStats() writes the total execution time of each
+ * task into a buffer, both as an absolute count value and as a percentage
+ * of the total system execution time.
+ *
+ * NOTE 2:
+ *
+ * This function is provided for convenience only, and is used by many of the
+ * demo applications.  Do not consider it to be part of the scheduler.
+ *
+ * vTaskGetRunTimeStats() calls uxTaskGetSystemState(), then formats part of the
+ * uxTaskGetSystemState() output into a human readable table that displays the
+ * amount of time each task has spent in the Running state in both absolute and
+ * percentage terms.
+ *
+ * vTaskGetRunTimeStats() has a dependency on the sprintf() C library function
+ * that might bloat the code size, use a lot of stack, and provide different
+ * results on different platforms.  An alternative, tiny, third party, and
+ * limited functionality implementation of sprintf() is provided in many of the
+ * FreeRTOS/Demo sub-directories in a file called printf-stdarg.c (note
+ * printf-stdarg.c does not provide a full snprintf() implementation!).
+ *
+ * It is recommended that production systems call uxTaskGetSystemState() directly
+ * to get access to raw stats data, rather than indirectly through a call to
+ * vTaskGetRunTimeStats().
+ *
+ * @param pcWriteBuffer A buffer into which the execution times will be
+ * written, in ASCII form.  This buffer is assumed to be large enough to
+ * contain the generated report.  Approximately 40 bytes per task should
+ * be sufficient.
+ *
+ * \defgroup vTaskGetRunTimeStats vTaskGetRunTimeStats
+ * \ingroup TaskUtils
+ */
+void vTaskGetRunTimeStats( char *pcWriteBuffer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+/**
+ * task. h
+ * <PRE>BaseType_t xTaskNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction );</PRE>
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this
+ * function to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * A notification sent to a task will remain pending until it is cleared by the
+ * task calling xTaskNotifyWait() or ulTaskNotifyTake().  If the task was
+ * already in the Blocked state to wait for a notification when the notification
+ * arrives then the task will automatically be removed from the Blocked state
+ * (unblocked) and the notification cleared.
+ *
+ * A task can use xTaskNotifyWait() to [optionally] block to wait for a
+ * notification to be pending, or ulTaskNotifyTake() to [optionally] block
+ * to wait for its notification value to have a non-zero value.  The task does
+ * not consume any CPU time while it is in the Blocked state.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details.
+ *
+ * @param xTaskToNotify The handle of the task being notified.  The handle to a
+ * task can be returned from the xTaskCreate() API function used to create the
+ * task, and the handle of the currently running task can be obtained by calling
+ * xTaskGetCurrentTaskHandle().
+ *
+ * @param ulValue Data that can be sent with the notification.  How the data is
+ * used depends on the value of the eAction parameter.
+ *
+ * @param eAction Specifies how the notification updates the task's notification
+ * value, if at all.  Valid values for eAction are as follows:
+ *
+ * eSetBits -
+ * The task's notification value is bitwise ORed with ulValue.  xTaskNofify()
+ * always returns pdPASS in this case.
+ *
+ * eIncrement -
+ * The task's notification value is incremented.  ulValue is not used and
+ * xTaskNotify() always returns pdPASS in this case.
+ *
+ * eSetValueWithOverwrite -
+ * The task's notification value is set to the value of ulValue, even if the
+ * task being notified had not yet processed the previous notification (the
+ * task already had a notification pending).  xTaskNotify() always returns
+ * pdPASS in this case.
+ *
+ * eSetValueWithoutOverwrite -
+ * If the task being notified did not already have a notification pending then
+ * the task's notification value is set to ulValue and xTaskNotify() will
+ * return pdPASS.  If the task being notified already had a notification
+ * pending then no action is performed and pdFAIL is returned.
+ *
+ * eNoAction -
+ * The task receives a notification without its notification value being
+ * updated.  ulValue is not used and xTaskNotify() always returns pdPASS in
+ * this case.
+ *
+ *  pulPreviousNotificationValue -
+ *  Can be used to pass out the subject task's notification value before any
+ *  bits are modified by the notify function.
+ *
+ * @return Dependent on the value of eAction.  See the description of the
+ * eAction parameter.
+ *
+ * \defgroup xTaskNotify xTaskNotify
+ * \ingroup TaskNotifications
+ */
+BaseType_t xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue ) PRIVILEGED_FUNCTION;
+#define xTaskNotify( xTaskToNotify, ulValue, eAction ) xTaskGenericNotify( ( xTaskToNotify ), ( ulValue ), ( eAction ), NULL )
+#define xTaskNotifyAndQuery( xTaskToNotify, ulValue, eAction, pulPreviousNotifyValue ) xTaskGenericNotify( ( xTaskToNotify ), ( ulValue ), ( eAction ), ( pulPreviousNotifyValue ) )
+
+/**
+ * task. h
+ * <PRE>BaseType_t xTaskNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, BaseType_t *pxHigherPriorityTaskWoken );</PRE>
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this
+ * function to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * A version of xTaskNotify() that can be used from an interrupt service routine
+ * (ISR).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * A notification sent to a task will remain pending until it is cleared by the
+ * task calling xTaskNotifyWait() or ulTaskNotifyTake().  If the task was
+ * already in the Blocked state to wait for a notification when the notification
+ * arrives then the task will automatically be removed from the Blocked state
+ * (unblocked) and the notification cleared.
+ *
+ * A task can use xTaskNotifyWait() to [optionally] block to wait for a
+ * notification to be pending, or ulTaskNotifyTake() to [optionally] block
+ * to wait for its notification value to have a non-zero value.  The task does
+ * not consume any CPU time while it is in the Blocked state.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details.
+ *
+ * @param xTaskToNotify The handle of the task being notified.  The handle to a
+ * task can be returned from the xTaskCreate() API function used to create the
+ * task, and the handle of the currently running task can be obtained by calling
+ * xTaskGetCurrentTaskHandle().
+ *
+ * @param ulValue Data that can be sent with the notification.  How the data is
+ * used depends on the value of the eAction parameter.
+ *
+ * @param eAction Specifies how the notification updates the task's notification
+ * value, if at all.  Valid values for eAction are as follows:
+ *
+ * eSetBits -
+ * The task's notification value is bitwise ORed with ulValue.  xTaskNofify()
+ * always returns pdPASS in this case.
+ *
+ * eIncrement -
+ * The task's notification value is incremented.  ulValue is not used and
+ * xTaskNotify() always returns pdPASS in this case.
+ *
+ * eSetValueWithOverwrite -
+ * The task's notification value is set to the value of ulValue, even if the
+ * task being notified had not yet processed the previous notification (the
+ * task already had a notification pending).  xTaskNotify() always returns
+ * pdPASS in this case.
+ *
+ * eSetValueWithoutOverwrite -
+ * If the task being notified did not already have a notification pending then
+ * the task's notification value is set to ulValue and xTaskNotify() will
+ * return pdPASS.  If the task being notified already had a notification
+ * pending then no action is performed and pdFAIL is returned.
+ *
+ * eNoAction -
+ * The task receives a notification without its notification value being
+ * updated.  ulValue is not used and xTaskNotify() always returns pdPASS in
+ * this case.
+ *
+ * @param pxHigherPriorityTaskWoken  xTaskNotifyFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending the notification caused the
+ * task to which the notification was sent to leave the Blocked state, and the
+ * unblocked task has a priority higher than the currently running task.  If
+ * xTaskNotifyFromISR() sets this value to pdTRUE then a context switch should
+ * be requested before the interrupt is exited.  How a context switch is
+ * requested from an ISR is dependent on the port - see the documentation page
+ * for the port in use.
+ *
+ * @return Dependent on the value of eAction.  See the description of the
+ * eAction parameter.
+ *
+ * \defgroup xTaskNotify xTaskNotify
+ * \ingroup TaskNotifications
+ */
+BaseType_t xTaskGenericNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+#define xTaskNotifyFromISR( xTaskToNotify, ulValue, eAction, pxHigherPriorityTaskWoken ) xTaskGenericNotifyFromISR( ( xTaskToNotify ), ( ulValue ), ( eAction ), NULL, ( pxHigherPriorityTaskWoken ) )
+#define xTaskNotifyAndQueryFromISR( xTaskToNotify, ulValue, eAction, pulPreviousNotificationValue, pxHigherPriorityTaskWoken ) xTaskGenericNotifyFromISR( ( xTaskToNotify ), ( ulValue ), ( eAction ), ( pulPreviousNotificationValue ), ( pxHigherPriorityTaskWoken ) )
+
+/**
+ * task. h
+ * <PRE>BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait );</pre>
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this
+ * function to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * A notification sent to a task will remain pending until it is cleared by the
+ * task calling xTaskNotifyWait() or ulTaskNotifyTake().  If the task was
+ * already in the Blocked state to wait for a notification when the notification
+ * arrives then the task will automatically be removed from the Blocked state
+ * (unblocked) and the notification cleared.
+ *
+ * A task can use xTaskNotifyWait() to [optionally] block to wait for a
+ * notification to be pending, or ulTaskNotifyTake() to [optionally] block
+ * to wait for its notification value to have a non-zero value.  The task does
+ * not consume any CPU time while it is in the Blocked state.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details.
+ *
+ * @param ulBitsToClearOnEntry Bits that are set in ulBitsToClearOnEntry value
+ * will be cleared in the calling task's notification value before the task
+ * checks to see if any notifications are pending, and optionally blocks if no
+ * notifications are pending.  Setting ulBitsToClearOnEntry to ULONG_MAX (if
+ * limits.h is included) or 0xffffffffUL (if limits.h is not included) will have
+ * the effect of resetting the task's notification value to 0.  Setting
+ * ulBitsToClearOnEntry to 0 will leave the task's notification value unchanged.
+ *
+ * @param ulBitsToClearOnExit If a notification is pending or received before
+ * the calling task exits the xTaskNotifyWait() function then the task's
+ * notification value (see the xTaskNotify() API function) is passed out using
+ * the pulNotificationValue parameter.  Then any bits that are set in
+ * ulBitsToClearOnExit will be cleared in the task's notification value (note
+ * *pulNotificationValue is set before any bits are cleared).  Setting
+ * ulBitsToClearOnExit to ULONG_MAX (if limits.h is included) or 0xffffffffUL
+ * (if limits.h is not included) will have the effect of resetting the task's
+ * notification value to 0 before the function exits.  Setting
+ * ulBitsToClearOnExit to 0 will leave the task's notification value unchanged
+ * when the function exits (in which case the value passed out in
+ * pulNotificationValue will match the task's notification value).
+ *
+ * @param pulNotificationValue Used to pass the task's notification value out
+ * of the function.  Note the value passed out will not be effected by the
+ * clearing of any bits caused by ulBitsToClearOnExit being non-zero.
+ *
+ * @param xTicksToWait The maximum amount of time that the task should wait in
+ * the Blocked state for a notification to be received, should a notification
+ * not already be pending when xTaskNotifyWait() was called.  The task
+ * will not consume any processing time while it is in the Blocked state.  This
+ * is specified in kernel ticks, the macro pdMS_TO_TICSK( value_in_ms ) can be
+ * used to convert a time specified in milliseconds to a time specified in
+ * ticks.
+ *
+ * @return If a notification was received (including notifications that were
+ * already pending when xTaskNotifyWait was called) then pdPASS is
+ * returned.  Otherwise pdFAIL is returned.
+ *
+ * \defgroup xTaskNotifyWait xTaskNotifyWait
+ * \ingroup TaskNotifications
+ */
+BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <PRE>BaseType_t xTaskNotifyGive( TaskHandle_t xTaskToNotify );</PRE>
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this macro
+ * to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * xTaskNotifyGive() is a helper macro intended for use when task notifications
+ * are used as light weight and faster binary or counting semaphore equivalents.
+ * Actual FreeRTOS semaphores are given using the xSemaphoreGive() API function,
+ * the equivalent action that instead uses a task notification is
+ * xTaskNotifyGive().
+ *
+ * When task notifications are being used as a binary or counting semaphore
+ * equivalent then the task being notified should wait for the notification
+ * using the ulTaskNotificationTake() API function rather than the
+ * xTaskNotifyWait() API function.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for more details.
+ *
+ * @param xTaskToNotify The handle of the task being notified.  The handle to a
+ * task can be returned from the xTaskCreate() API function used to create the
+ * task, and the handle of the currently running task can be obtained by calling
+ * xTaskGetCurrentTaskHandle().
+ *
+ * @return xTaskNotifyGive() is a macro that calls xTaskNotify() with the
+ * eAction parameter set to eIncrement - so pdPASS is always returned.
+ *
+ * \defgroup xTaskNotifyGive xTaskNotifyGive
+ * \ingroup TaskNotifications
+ */
+#define xTaskNotifyGive( xTaskToNotify ) xTaskGenericNotify( ( xTaskToNotify ), ( 0 ), eIncrement, NULL )
+
+/**
+ * task. h
+ * <PRE>void vTaskNotifyGiveFromISR( TaskHandle_t xTaskHandle, BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this macro
+ * to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * A version of xTaskNotifyGive() that can be called from an interrupt service
+ * routine (ISR).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * vTaskNotifyGiveFromISR() is intended for use when task notifications are
+ * used as light weight and faster binary or counting semaphore equivalents.
+ * Actual FreeRTOS semaphores are given from an ISR using the
+ * xSemaphoreGiveFromISR() API function, the equivalent action that instead uses
+ * a task notification is vTaskNotifyGiveFromISR().
+ *
+ * When task notifications are being used as a binary or counting semaphore
+ * equivalent then the task being notified should wait for the notification
+ * using the ulTaskNotificationTake() API function rather than the
+ * xTaskNotifyWait() API function.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for more details.
+ *
+ * @param xTaskToNotify The handle of the task being notified.  The handle to a
+ * task can be returned from the xTaskCreate() API function used to create the
+ * task, and the handle of the currently running task can be obtained by calling
+ * xTaskGetCurrentTaskHandle().
+ *
+ * @param pxHigherPriorityTaskWoken  vTaskNotifyGiveFromISR() will set
+ * *pxHigherPriorityTaskWoken to pdTRUE if sending the notification caused the
+ * task to which the notification was sent to leave the Blocked state, and the
+ * unblocked task has a priority higher than the currently running task.  If
+ * vTaskNotifyGiveFromISR() sets this value to pdTRUE then a context switch
+ * should be requested before the interrupt is exited.  How a context switch is
+ * requested from an ISR is dependent on the port - see the documentation page
+ * for the port in use.
+ *
+ * \defgroup xTaskNotifyWait xTaskNotifyWait
+ * \ingroup TaskNotifications
+ */
+void vTaskNotifyGiveFromISR( TaskHandle_t xTaskToNotify, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <PRE>uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait );</pre>
+ *
+ * configUSE_TASK_NOTIFICATIONS must be undefined or defined as 1 for this
+ * function to be available.
+ *
+ * When configUSE_TASK_NOTIFICATIONS is set to one each task has its own private
+ * "notification value", which is a 32-bit unsigned integer (uint32_t).
+ *
+ * Events can be sent to a task using an intermediary object.  Examples of such
+ * objects are queues, semaphores, mutexes and event groups.  Task notifications
+ * are a method of sending an event directly to a task without the need for such
+ * an intermediary object.
+ *
+ * A notification sent to a task can optionally perform an action, such as
+ * update, overwrite or increment the task's notification value.  In that way
+ * task notifications can be used to send data to a task, or be used as light
+ * weight and fast binary or counting semaphores.
+ *
+ * ulTaskNotifyTake() is intended for use when a task notification is used as a
+ * faster and lighter weight binary or counting semaphore alternative.  Actual
+ * FreeRTOS semaphores are taken using the xSemaphoreTake() API function, the
+ * equivalent action that instead uses a task notification is
+ * ulTaskNotifyTake().
+ *
+ * When a task is using its notification value as a binary or counting semaphore
+ * other tasks should send notifications to it using the xTaskNotifyGive()
+ * macro, or xTaskNotify() function with the eAction parameter set to
+ * eIncrement.
+ *
+ * ulTaskNotifyTake() can either clear the task's notification value to
+ * zero on exit, in which case the notification value acts like a binary
+ * semaphore, or decrement the task's notification value on exit, in which case
+ * the notification value acts like a counting semaphore.
+ *
+ * A task can use ulTaskNotifyTake() to [optionally] block to wait for a
+ * the task's notification value to be non-zero.  The task does not consume any
+ * CPU time while it is in the Blocked state.
+ *
+ * Where as xTaskNotifyWait() will return when a notification is pending,
+ * ulTaskNotifyTake() will return when the task's notification value is
+ * not zero.
+ *
+ * See http://www.FreeRTOS.org/RTOS-task-notifications.html for details.
+ *
+ * @param xClearCountOnExit if xClearCountOnExit is pdFALSE then the task's
+ * notification value is decremented when the function exits.  In this way the
+ * notification value acts like a counting semaphore.  If xClearCountOnExit is
+ * not pdFALSE then the task's notification value is cleared to zero when the
+ * function exits.  In this way the notification value acts like a binary
+ * semaphore.
+ *
+ * @param xTicksToWait The maximum amount of time that the task should wait in
+ * the Blocked state for the task's notification value to be greater than zero,
+ * should the count not already be greater than zero when
+ * ulTaskNotifyTake() was called.  The task will not consume any processing
+ * time while it is in the Blocked state.  This is specified in kernel ticks,
+ * the macro pdMS_TO_TICSK( value_in_ms ) can be used to convert a time
+ * specified in milliseconds to a time specified in ticks.
+ *
+ * @return The task's notification count before it is either cleared to zero or
+ * decremented (see the xClearCountOnExit parameter).
+ *
+ * \defgroup ulTaskNotifyTake ulTaskNotifyTake
+ * \ingroup TaskNotifications
+ */
+uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+/**
+ * task. h
+ * <PRE>BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask );</pre>
+ *
+ * If the notification state of the task referenced by the handle xTask is
+ * eNotified, then set the task's notification state to eNotWaitingNotification.
+ * The task's notification value is not altered.  Set xTask to NULL to clear the
+ * notification state of the calling task.
+ *
+ * @return pdTRUE if the task's notification state was set to
+ * eNotWaitingNotification, otherwise pdFALSE.
+ * \defgroup xTaskNotifyStateClear xTaskNotifyStateClear
+ * \ingroup TaskNotifications
+ */
+BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask );
+
+/*-----------------------------------------------------------
+ * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES
+ *----------------------------------------------------------*/
+
+/*
+ * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE.  IT IS ONLY
+ * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS
+ * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER.
+ *
+ * Called from the real time kernel tick (either preemptive or cooperative),
+ * this increments the tick count and checks if any tasks that are blocked
+ * for a finite period required removing from a blocked list and placing on
+ * a ready list.  If a non-zero value is returned then a context switch is
+ * required because either:
+ *   + A task was removed from a blocked list because its timeout had expired,
+ *     or
+ *   + Time slicing is in use and there is a task of equal priority to the
+ *     currently running task.
+ */
+BaseType_t xTaskIncrementTick( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE.  IT IS AN
+ * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER.
+ *
+ * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED.
+ *
+ * Removes the calling task from the ready list and places it both
+ * on the list of tasks waiting for a particular event, and the
+ * list of delayed tasks.  The task will be removed from both lists
+ * and replaced on the ready list should either the event occur (and
+ * there be no higher priority tasks waiting on the same event) or
+ * the delay period expires.
+ *
+ * The 'unordered' version replaces the event list item value with the
+ * xItemValue value, and inserts the list item at the end of the list.
+ *
+ * The 'ordered' version uses the existing event list item value (which is the
+ * owning tasks priority) to insert the list item into the event list is task
+ * priority order.
+ *
+ * @param pxEventList The list containing tasks that are blocked waiting
+ * for the event to occur.
+ *
+ * @param xItemValue The item value to use for the event list item when the
+ * event list is not ordered by task priority.
+ *
+ * @param xTicksToWait The maximum amount of time that the task should wait
+ * for the event to occur.  This is specified in kernel ticks,the constant
+ * portTICK_PERIOD_MS can be used to convert kernel ticks into a real time
+ * period.
+ */
+void vTaskPlaceOnEventList( List_t * const pxEventList, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+void vTaskPlaceOnUnorderedEventList( List_t * pxEventList, const TickType_t xItemValue, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+/*
+ * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE.  IT IS AN
+ * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER.
+ *
+ * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED.
+ *
+ * This function performs nearly the same function as vTaskPlaceOnEventList().
+ * The difference being that this function does not permit tasks to block
+ * indefinitely, whereas vTaskPlaceOnEventList() does.
+ *
+ */
+void vTaskPlaceOnEventListRestricted( List_t * const pxEventList, const TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely ) PRIVILEGED_FUNCTION;
+
+/*
+ * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE.  IT IS AN
+ * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER.
+ *
+ * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED.
+ *
+ * Removes a task from both the specified event list and the list of blocked
+ * tasks, and places it on a ready queue.
+ *
+ * xTaskRemoveFromEventList()/xTaskRemoveFromUnorderedEventList() will be called
+ * if either an event occurs to unblock a task, or the block timeout period
+ * expires.
+ *
+ * xTaskRemoveFromEventList() is used when the event list is in task priority
+ * order.  It removes the list item from the head of the event list as that will
+ * have the highest priority owning task of all the tasks on the event list.
+ * xTaskRemoveFromUnorderedEventList() is used when the event list is not
+ * ordered and the event list items hold something other than the owning tasks
+ * priority.  In this case the event list item value is updated to the value
+ * passed in the xItemValue parameter.
+ *
+ * @return pdTRUE if the task being removed has a higher priority than the task
+ * making the call, otherwise pdFALSE.
+ */
+BaseType_t xTaskRemoveFromEventList( const List_t * const pxEventList ) PRIVILEGED_FUNCTION;
+BaseType_t xTaskRemoveFromUnorderedEventList( ListItem_t * pxEventListItem, const TickType_t xItemValue ) PRIVILEGED_FUNCTION;
+
+/*
+ * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE.  IT IS ONLY
+ * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS
+ * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER.
+ *
+ * Sets the pointer to the current TCB to the TCB of the highest priority task
+ * that is ready to run.
+ */
+void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * THESE FUNCTIONS MUST NOT BE USED FROM APPLICATION CODE.  THEY ARE USED BY
+ * THE EVENT BITS MODULE.
+ */
+TickType_t uxTaskResetEventItemValue( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Return the handle of the calling task.
+ */
+TaskHandle_t xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Capture the current time status for future reference.
+ */
+void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut ) PRIVILEGED_FUNCTION;
+
+/*
+ * Compare the time status now with that previously captured to see if the
+ * timeout has expired.
+ */
+BaseType_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait ) PRIVILEGED_FUNCTION;
+
+/*
+ * Shortcut used by the queue implementation to prevent unnecessary call to
+ * taskYIELD();
+ */
+void vTaskMissedYield( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Returns the scheduler state as taskSCHEDULER_RUNNING,
+ * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED.
+ */
+BaseType_t xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Raises the priority of the mutex holder to that of the calling task should
+ * the mutex holder have a priority less than the calling task.
+ */
+void vTaskPriorityInherit( TaskHandle_t const pxMutexHolder ) PRIVILEGED_FUNCTION;
+
+/*
+ * Set the priority of a task back to its proper priority in the case that it
+ * inherited a higher priority while it was holding a semaphore.
+ */
+BaseType_t xTaskPriorityDisinherit( TaskHandle_t const pxMutexHolder ) PRIVILEGED_FUNCTION;
+
+/*
+ * Generic version of the task creation function which is in turn called by the
+ * xTaskCreate() and xTaskCreateRestricted() macros.
+ */
+BaseType_t xTaskGenericCreate( TaskFunction_t pxTaskCode, const char * const pcName, const uint16_t usStackDepth, void * const pvParameters, UBaseType_t uxPriority, TaskHandle_t * const pxCreatedTask, StackType_t * const puxStackBuffer, const MemoryRegion_t * const xRegions ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+/*
+ * Get the uxTCBNumber assigned to the task referenced by the xTask parameter.
+ */
+UBaseType_t uxTaskGetTaskNumber( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
+
+/*
+ * Set the uxTaskNumber of the task referenced by the xTask parameter to
+ * uxHandle.
+ */
+void vTaskSetTaskNumber( TaskHandle_t xTask, const UBaseType_t uxHandle ) PRIVILEGED_FUNCTION;
+
+/*
+ * Only available when configUSE_TICKLESS_IDLE is set to 1.
+ * If tickless mode is being used, or a low power mode is implemented, then
+ * the tick interrupt will not execute during idle periods.  When this is the
+ * case, the tick count value maintained by the scheduler needs to be kept up
+ * to date with the actual execution time by being skipped forward by a time
+ * equal to the idle period.
+ */
+void vTaskStepTick( const TickType_t xTicksToJump ) PRIVILEGED_FUNCTION;
+
+/*
+ * Only avilable when configUSE_TICKLESS_IDLE is set to 1.
+ * Provided for use within portSUPPRESS_TICKS_AND_SLEEP() to allow the port
+ * specific sleep function to determine if it is ok to proceed with the sleep,
+ * and if it is ok to proceed, if it is ok to sleep indefinitely.
+ *
+ * This function is necessary because portSUPPRESS_TICKS_AND_SLEEP() is only
+ * called with the scheduler suspended, not from within a critical section.  It
+ * is therefore possible for an interrupt to request a context switch between
+ * portSUPPRESS_TICKS_AND_SLEEP() and the low power mode actually being
+ * entered.  eTaskConfirmSleepModeStatus() should be called from a short
+ * critical section between the timer being stopped and the sleep mode being
+ * entered to ensure it is ok to proceed into the sleep mode.
+ */
+eSleepModeStatus eTaskConfirmSleepModeStatus( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * For internal use only.  Increment the mutex held count when a mutex is
+ * taken and return the handle of the task that has taken the mutex.
+ */
+void *pvTaskIncrementMutexHeldCount( void ) PRIVILEGED_FUNCTION;
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* INC_TASK_H */
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/include/timers.h b/crazyflie-firmware-src/src/lib/FreeRTOS/include/timers.h
new file mode 100644
index 0000000000000000000000000000000000000000..3c6c6bf308576cf9936700040b4385041042dce8
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/include/timers.h
@@ -0,0 +1,1146 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+#ifndef TIMERS_H
+#define TIMERS_H
+
+#ifndef INC_FREERTOS_H
+	#error "include FreeRTOS.h must appear in source files before include timers.h"
+#endif
+
+/*lint -e537 This headers are only multiply included if the application code
+happens to also be including task.h. */
+#include "task.h"
+/*lint +e537 */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*-----------------------------------------------------------
+ * MACROS AND DEFINITIONS
+ *----------------------------------------------------------*/
+
+/* IDs for commands that can be sent/received on the timer queue.  These are to
+be used solely through the macros that make up the public software timer API,
+as defined below.  The commands that are sent from interrupts must use the
+highest numbers as tmrFIRST_FROM_ISR_COMMAND is used to determine if the task
+or interrupt version of the queue send function should be used. */
+#define tmrCOMMAND_EXECUTE_CALLBACK_FROM_ISR 	( ( BaseType_t ) -2 )
+#define tmrCOMMAND_EXECUTE_CALLBACK				( ( BaseType_t ) -1 )
+#define tmrCOMMAND_START_DONT_TRACE				( ( BaseType_t ) 0 )
+#define tmrCOMMAND_START					    ( ( BaseType_t ) 1 )
+#define tmrCOMMAND_RESET						( ( BaseType_t ) 2 )
+#define tmrCOMMAND_STOP							( ( BaseType_t ) 3 )
+#define tmrCOMMAND_CHANGE_PERIOD				( ( BaseType_t ) 4 )
+#define tmrCOMMAND_DELETE						( ( BaseType_t ) 5 )
+
+#define tmrFIRST_FROM_ISR_COMMAND				( ( BaseType_t ) 6 )
+#define tmrCOMMAND_START_FROM_ISR				( ( BaseType_t ) 6 )
+#define tmrCOMMAND_RESET_FROM_ISR				( ( BaseType_t ) 7 )
+#define tmrCOMMAND_STOP_FROM_ISR				( ( BaseType_t ) 8 )
+#define tmrCOMMAND_CHANGE_PERIOD_FROM_ISR		( ( BaseType_t ) 9 )
+
+
+/**
+ * Type by which software timers are referenced.  For example, a call to
+ * xTimerCreate() returns an TimerHandle_t variable that can then be used to
+ * reference the subject timer in calls to other software timer API functions
+ * (for example, xTimerStart(), xTimerReset(), etc.).
+ */
+typedef void * TimerHandle_t;
+
+/*
+ * Defines the prototype to which timer callback functions must conform.
+ */
+typedef void (*TimerCallbackFunction_t)( TimerHandle_t xTimer );
+
+/*
+ * Defines the prototype to which functions used with the
+ * xTimerPendFunctionCallFromISR() function must conform.
+ */
+typedef void (*PendedFunction_t)( void *, uint32_t );
+
+/**
+ * TimerHandle_t xTimerCreate( 	const char * const pcTimerName,
+ * 								TickType_t xTimerPeriodInTicks,
+ * 								UBaseType_t uxAutoReload,
+ * 								void * pvTimerID,
+ * 								TimerCallbackFunction_t pxCallbackFunction );
+ *
+ * Creates a new software timer instance.  This allocates the storage required
+ * by the new timer, initialises the new timers internal state, and returns a
+ * handle by which the new timer can be referenced.
+ *
+ * Timers are created in the dormant state.  The xTimerStart(), xTimerReset(),
+ * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and
+ * xTimerChangePeriodFromISR() API functions can all be used to transition a
+ * timer into the active state.
+ *
+ * @param pcTimerName A text name that is assigned to the timer.  This is done
+ * purely to assist debugging.  The kernel itself only ever references a timer
+ * by its handle, and never by its name.
+ *
+ * @param xTimerPeriodInTicks The timer period.  The time is defined in tick
+ * periods so the constant portTICK_PERIOD_MS can be used to convert a time that
+ * has been specified in milliseconds.  For example, if the timer must expire
+ * after 100 ticks, then xTimerPeriodInTicks should be set to 100.
+ * Alternatively, if the timer must expire after 500ms, then xPeriod can be set
+ * to ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than or
+ * equal to 1000.
+ *
+ * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will
+ * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter.
+ * If uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and
+ * enter the dormant state after it expires.
+ *
+ * @param pvTimerID An identifier that is assigned to the timer being created.
+ * Typically this would be used in the timer callback function to identify which
+ * timer expired when the same callback function is assigned to more than one
+ * timer.
+ *
+ * @param pxCallbackFunction The function to call when the timer expires.
+ * Callback functions must have the prototype defined by TimerCallbackFunction_t,
+ * which is	"void vCallbackFunction( TimerHandle_t xTimer );".
+ *
+ * @return If the timer is successfully created then a handle to the newly
+ * created timer is returned.  If the timer cannot be created (because either
+ * there is insufficient FreeRTOS heap remaining to allocate the timer
+ * structures, or the timer period was set to 0) then NULL is returned.
+ *
+ * Example usage:
+ * @verbatim
+ * #define NUM_TIMERS 5
+ *
+ * // An array to hold handles to the created timers.
+ * TimerHandle_t xTimers[ NUM_TIMERS ];
+ *
+ * // An array to hold a count of the number of times each timer expires.
+ * int32_t lExpireCounters[ NUM_TIMERS ] = { 0 };
+ *
+ * // Define a callback function that will be used by multiple timer instances.
+ * // The callback function does nothing but count the number of times the
+ * // associated timer expires, and stop the timer once the timer has expired
+ * // 10 times.
+ * void vTimerCallback( TimerHandle_t pxTimer )
+ * {
+ * int32_t lArrayIndex;
+ * const int32_t xMaxExpiryCountBeforeStopping = 10;
+ *
+ * 	   // Optionally do something if the pxTimer parameter is NULL.
+ * 	   configASSERT( pxTimer );
+ *
+ *     // Which timer expired?
+ *     lArrayIndex = ( int32_t ) pvTimerGetTimerID( pxTimer );
+ *
+ *     // Increment the number of times that pxTimer has expired.
+ *     lExpireCounters[ lArrayIndex ] += 1;
+ *
+ *     // If the timer has expired 10 times then stop it from running.
+ *     if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping )
+ *     {
+ *         // Do not use a block time if calling a timer API function from a
+ *         // timer callback function, as doing so could cause a deadlock!
+ *         xTimerStop( pxTimer, 0 );
+ *     }
+ * }
+ *
+ * void main( void )
+ * {
+ * int32_t x;
+ *
+ *     // Create then start some timers.  Starting the timers before the scheduler
+ *     // has been started means the timers will start running immediately that
+ *     // the scheduler starts.
+ *     for( x = 0; x < NUM_TIMERS; x++ )
+ *     {
+ *         xTimers[ x ] = xTimerCreate(    "Timer",       // Just a text name, not used by the kernel.
+ *                                         ( 100 * x ),   // The timer period in ticks.
+ *                                         pdTRUE,        // The timers will auto-reload themselves when they expire.
+ *                                         ( void * ) x,  // Assign each timer a unique id equal to its array index.
+ *                                         vTimerCallback // Each timer calls the same callback when it expires.
+ *                                     );
+ *
+ *         if( xTimers[ x ] == NULL )
+ *         {
+ *             // The timer was not created.
+ *         }
+ *         else
+ *         {
+ *             // Start the timer.  No block time is specified, and even if one was
+ *             // it would be ignored because the scheduler has not yet been
+ *             // started.
+ *             if( xTimerStart( xTimers[ x ], 0 ) != pdPASS )
+ *             {
+ *                 // The timer could not be set into the Active state.
+ *             }
+ *         }
+ *     }
+ *
+ *     // ...
+ *     // Create tasks here.
+ *     // ...
+ *
+ *     // Starting the scheduler will start the timers running as they have already
+ *     // been set into the active state.
+ *     xTaskStartScheduler();
+ *
+ *     // Should not reach here.
+ *     for( ;; );
+ * }
+ * @endverbatim
+ */
+TimerHandle_t xTimerCreate( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+/**
+ * void *pvTimerGetTimerID( TimerHandle_t xTimer );
+ *
+ * Returns the ID assigned to the timer.
+ *
+ * IDs are assigned to timers using the pvTimerID parameter of the call to
+ * xTimerCreated() that was used to create the timer, and by calling the
+ * vTimerSetTimerID() API function.
+ *
+ * If the same callback function is assigned to multiple timers then the timer
+ * ID can be used as time specific (timer local) storage.
+ *
+ * @param xTimer The timer being queried.
+ *
+ * @return The ID assigned to the timer being queried.
+ *
+ * Example usage:
+ *
+ * See the xTimerCreate() API function example usage scenario.
+ */
+void *pvTimerGetTimerID( const TimerHandle_t xTimer ) PRIVILEGED_FUNCTION;
+
+/**
+ * void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID );
+ *
+ * Sets the ID assigned to the timer.
+ *
+ * IDs are assigned to timers using the pvTimerID parameter of the call to
+ * xTimerCreated() that was used to create the timer.
+ *
+ * If the same callback function is assigned to multiple timers then the timer
+ * ID can be used as time specific (timer local) storage.
+ *
+ * @param xTimer The timer being updated.
+ *
+ * @param pvNewID The ID to assign to the timer.
+ *
+ * Example usage:
+ *
+ * See the xTimerCreate() API function example usage scenario.
+ */
+void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID ) PRIVILEGED_FUNCTION;
+
+/**
+ * BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer );
+ *
+ * Queries a timer to see if it is active or dormant.
+ *
+ * A timer will be dormant if:
+ *     1) It has been created but not started, or
+ *     2) It is an expired one-shot timer that has not been restarted.
+ *
+ * Timers are created in the dormant state.  The xTimerStart(), xTimerReset(),
+ * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and
+ * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the
+ * active state.
+ *
+ * @param xTimer The timer being queried.
+ *
+ * @return pdFALSE will be returned if the timer is dormant.  A value other than
+ * pdFALSE will be returned if the timer is active.
+ *
+ * Example usage:
+ * @verbatim
+ * // This function assumes xTimer has already been created.
+ * void vAFunction( TimerHandle_t xTimer )
+ * {
+ *     if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )"
+ *     {
+ *         // xTimer is active, do something.
+ *     }
+ *     else
+ *     {
+ *         // xTimer is not active, do something else.
+ *     }
+ * }
+ * @endverbatim
+ */
+BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION;
+
+/**
+ * TaskHandle_t xTimerGetTimerDaemonTaskHandle( void );
+ *
+ * xTimerGetTimerDaemonTaskHandle() is only available if
+ * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h.
+ *
+ * Simply returns the handle of the timer service/daemon task.  It it not valid
+ * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started.
+ */
+TaskHandle_t xTimerGetTimerDaemonTaskHandle( void ) PRIVILEGED_FUNCTION;
+
+/**
+ * BaseType_t xTimerStart( TimerHandle_t xTimer, TickType_t xTicksToWait );
+ *
+ * Timer functionality is provided by a timer service/daemon task.  Many of the
+ * public FreeRTOS timer API functions send commands to the timer service task
+ * through a queue called the timer command queue.  The timer command queue is
+ * private to the kernel itself and is not directly accessible to application
+ * code.  The length of the timer command queue is set by the
+ * configTIMER_QUEUE_LENGTH configuration constant.
+ *
+ * xTimerStart() starts a timer that was previously created using the
+ * xTimerCreate() API function.  If the timer had already been started and was
+ * already in the active state, then xTimerStart() has equivalent functionality
+ * to the xTimerReset() API function.
+ *
+ * Starting a timer ensures the timer is in the active state.  If the timer
+ * is not stopped, deleted, or reset in the mean time, the callback function
+ * associated with the timer will get called 'n' ticks after xTimerStart() was
+ * called, where 'n' is the timers defined period.
+ *
+ * It is valid to call xTimerStart() before the scheduler has been started, but
+ * when this is done the timer will not actually start until the scheduler is
+ * started, and the timers expiry time will be relative to when the scheduler is
+ * started, not relative to when xTimerStart() was called.
+ *
+ * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart()
+ * to be available.
+ *
+ * @param xTimer The handle of the timer being started/restarted.
+ *
+ * @param xTicksToWait Specifies the time, in ticks, that the calling task should
+ * be held in the Blocked state to wait for the start command to be successfully
+ * sent to the timer command queue, should the queue already be full when
+ * xTimerStart() was called.  xTicksToWait is ignored if xTimerStart() is called
+ * before the scheduler is started.
+ *
+ * @return pdFAIL will be returned if the start command could not be sent to
+ * the timer command queue even after xTicksToWait ticks had passed.  pdPASS will
+ * be returned if the command was successfully sent to the timer command queue.
+ * When the command is actually processed will depend on the priority of the
+ * timer service/daemon task relative to other tasks in the system, although the
+ * timers expiry time is relative to when xTimerStart() is actually called.  The
+ * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY
+ * configuration constant.
+ *
+ * Example usage:
+ *
+ * See the xTimerCreate() API function example usage scenario.
+ *
+ */
+#define xTimerStart( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xTicksToWait ) )
+
+/**
+ * BaseType_t xTimerStop( TimerHandle_t xTimer, TickType_t xTicksToWait );
+ *
+ * Timer functionality is provided by a timer service/daemon task.  Many of the
+ * public FreeRTOS timer API functions send commands to the timer service task
+ * through a queue called the timer command queue.  The timer command queue is
+ * private to the kernel itself and is not directly accessible to application
+ * code.  The length of the timer command queue is set by the
+ * configTIMER_QUEUE_LENGTH configuration constant.
+ *
+ * xTimerStop() stops a timer that was previously started using either of the
+ * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(),
+ * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions.
+ *
+ * Stopping a timer ensures the timer is not in the active state.
+ *
+ * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop()
+ * to be available.
+ *
+ * @param xTimer The handle of the timer being stopped.
+ *
+ * @param xTicksToWait Specifies the time, in ticks, that the calling task should
+ * be held in the Blocked state to wait for the stop command to be successfully
+ * sent to the timer command queue, should the queue already be full when
+ * xTimerStop() was called.  xTicksToWait is ignored if xTimerStop() is called
+ * before the scheduler is started.
+ *
+ * @return pdFAIL will be returned if the stop command could not be sent to
+ * the timer command queue even after xTicksToWait ticks had passed.  pdPASS will
+ * be returned if the command was successfully sent to the timer command queue.
+ * When the command is actually processed will depend on the priority of the
+ * timer service/daemon task relative to other tasks in the system.  The timer
+ * service/daemon task priority is set by the configTIMER_TASK_PRIORITY
+ * configuration constant.
+ *
+ * Example usage:
+ *
+ * See the xTimerCreate() API function example usage scenario.
+ *
+ */
+#define xTimerStop( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xTicksToWait ) )
+
+/**
+ * BaseType_t xTimerChangePeriod( 	TimerHandle_t xTimer,
+ *										TickType_t xNewPeriod,
+ *										TickType_t xTicksToWait );
+ *
+ * Timer functionality is provided by a timer service/daemon task.  Many of the
+ * public FreeRTOS timer API functions send commands to the timer service task
+ * through a queue called the timer command queue.  The timer command queue is
+ * private to the kernel itself and is not directly accessible to application
+ * code.  The length of the timer command queue is set by the
+ * configTIMER_QUEUE_LENGTH configuration constant.
+ *
+ * xTimerChangePeriod() changes the period of a timer that was previously
+ * created using the xTimerCreate() API function.
+ *
+ * xTimerChangePeriod() can be called to change the period of an active or
+ * dormant state timer.
+ *
+ * The configUSE_TIMERS configuration constant must be set to 1 for
+ * xTimerChangePeriod() to be available.
+ *
+ * @param xTimer The handle of the timer that is having its period changed.
+ *
+ * @param xNewPeriod The new period for xTimer. Timer periods are specified in
+ * tick periods, so the constant portTICK_PERIOD_MS can be used to convert a time
+ * that has been specified in milliseconds.  For example, if the timer must
+ * expire after 100 ticks, then xNewPeriod should be set to 100.  Alternatively,
+ * if the timer must expire after 500ms, then xNewPeriod can be set to
+ * ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than
+ * or equal to 1000.
+ *
+ * @param xTicksToWait Specifies the time, in ticks, that the calling task should
+ * be held in the Blocked state to wait for the change period command to be
+ * successfully sent to the timer command queue, should the queue already be
+ * full when xTimerChangePeriod() was called.  xTicksToWait is ignored if
+ * xTimerChangePeriod() is called before the scheduler is started.
+ *
+ * @return pdFAIL will be returned if the change period command could not be
+ * sent to the timer command queue even after xTicksToWait ticks had passed.
+ * pdPASS will be returned if the command was successfully sent to the timer
+ * command queue.  When the command is actually processed will depend on the
+ * priority of the timer service/daemon task relative to other tasks in the
+ * system.  The timer service/daemon task priority is set by the
+ * configTIMER_TASK_PRIORITY configuration constant.
+ *
+ * Example usage:
+ * @verbatim
+ * // This function assumes xTimer has already been created.  If the timer
+ * // referenced by xTimer is already active when it is called, then the timer
+ * // is deleted.  If the timer referenced by xTimer is not active when it is
+ * // called, then the period of the timer is set to 500ms and the timer is
+ * // started.
+ * void vAFunction( TimerHandle_t xTimer )
+ * {
+ *     if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )"
+ *     {
+ *         // xTimer is already active - delete it.
+ *         xTimerDelete( xTimer );
+ *     }
+ *     else
+ *     {
+ *         // xTimer is not active, change its period to 500ms.  This will also
+ *         // cause the timer to start.  Block for a maximum of 100 ticks if the
+ *         // change period command cannot immediately be sent to the timer
+ *         // command queue.
+ *         if( xTimerChangePeriod( xTimer, 500 / portTICK_PERIOD_MS, 100 ) == pdPASS )
+ *         {
+ *             // The command was successfully sent.
+ *         }
+ *         else
+ *         {
+ *             // The command could not be sent, even after waiting for 100 ticks
+ *             // to pass.  Take appropriate action here.
+ *         }
+ *     }
+ * }
+ * @endverbatim
+ */
+ #define xTimerChangePeriod( xTimer, xNewPeriod, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xTicksToWait ) )
+
+/**
+ * BaseType_t xTimerDelete( TimerHandle_t xTimer, TickType_t xTicksToWait );
+ *
+ * Timer functionality is provided by a timer service/daemon task.  Many of the
+ * public FreeRTOS timer API functions send commands to the timer service task
+ * through a queue called the timer command queue.  The timer command queue is
+ * private to the kernel itself and is not directly accessible to application
+ * code.  The length of the timer command queue is set by the
+ * configTIMER_QUEUE_LENGTH configuration constant.
+ *
+ * xTimerDelete() deletes a timer that was previously created using the
+ * xTimerCreate() API function.
+ *
+ * The configUSE_TIMERS configuration constant must be set to 1 for
+ * xTimerDelete() to be available.
+ *
+ * @param xTimer The handle of the timer being deleted.
+ *
+ * @param xTicksToWait Specifies the time, in ticks, that the calling task should
+ * be held in the Blocked state to wait for the delete command to be
+ * successfully sent to the timer command queue, should the queue already be
+ * full when xTimerDelete() was called.  xTicksToWait is ignored if xTimerDelete()
+ * is called before the scheduler is started.
+ *
+ * @return pdFAIL will be returned if the delete command could not be sent to
+ * the timer command queue even after xTicksToWait ticks had passed.  pdPASS will
+ * be returned if the command was successfully sent to the timer command queue.
+ * When the command is actually processed will depend on the priority of the
+ * timer service/daemon task relative to other tasks in the system.  The timer
+ * service/daemon task priority is set by the configTIMER_TASK_PRIORITY
+ * configuration constant.
+ *
+ * Example usage:
+ *
+ * See the xTimerChangePeriod() API function example usage scenario.
+ */
+#define xTimerDelete( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xTicksToWait ) )
+
+/**
+ * BaseType_t xTimerReset( TimerHandle_t xTimer, TickType_t xTicksToWait );
+ *
+ * Timer functionality is provided by a timer service/daemon task.  Many of the
+ * public FreeRTOS timer API functions send commands to the timer service task
+ * through a queue called the timer command queue.  The timer command queue is
+ * private to the kernel itself and is not directly accessible to application
+ * code.  The length of the timer command queue is set by the
+ * configTIMER_QUEUE_LENGTH configuration constant.
+ *
+ * xTimerReset() re-starts a timer that was previously created using the
+ * xTimerCreate() API function.  If the timer had already been started and was
+ * already in the active state, then xTimerReset() will cause the timer to
+ * re-evaluate its expiry time so that it is relative to when xTimerReset() was
+ * called.  If the timer was in the dormant state then xTimerReset() has
+ * equivalent functionality to the xTimerStart() API function.
+ *
+ * Resetting a timer ensures the timer is in the active state.  If the timer
+ * is not stopped, deleted, or reset in the mean time, the callback function
+ * associated with the timer will get called 'n' ticks after xTimerReset() was
+ * called, where 'n' is the timers defined period.
+ *
+ * It is valid to call xTimerReset() before the scheduler has been started, but
+ * when this is done the timer will not actually start until the scheduler is
+ * started, and the timers expiry time will be relative to when the scheduler is
+ * started, not relative to when xTimerReset() was called.
+ *
+ * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset()
+ * to be available.
+ *
+ * @param xTimer The handle of the timer being reset/started/restarted.
+ *
+ * @param xTicksToWait Specifies the time, in ticks, that the calling task should
+ * be held in the Blocked state to wait for the reset command to be successfully
+ * sent to the timer command queue, should the queue already be full when
+ * xTimerReset() was called.  xTicksToWait is ignored if xTimerReset() is called
+ * before the scheduler is started.
+ *
+ * @return pdFAIL will be returned if the reset command could not be sent to
+ * the timer command queue even after xTicksToWait ticks had passed.  pdPASS will
+ * be returned if the command was successfully sent to the timer command queue.
+ * When the command is actually processed will depend on the priority of the
+ * timer service/daemon task relative to other tasks in the system, although the
+ * timers expiry time is relative to when xTimerStart() is actually called.  The
+ * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY
+ * configuration constant.
+ *
+ * Example usage:
+ * @verbatim
+ * // When a key is pressed, an LCD back-light is switched on.  If 5 seconds pass
+ * // without a key being pressed, then the LCD back-light is switched off.  In
+ * // this case, the timer is a one-shot timer.
+ *
+ * TimerHandle_t xBacklightTimer = NULL;
+ *
+ * // The callback function assigned to the one-shot timer.  In this case the
+ * // parameter is not used.
+ * void vBacklightTimerCallback( TimerHandle_t pxTimer )
+ * {
+ *     // The timer expired, therefore 5 seconds must have passed since a key
+ *     // was pressed.  Switch off the LCD back-light.
+ *     vSetBacklightState( BACKLIGHT_OFF );
+ * }
+ *
+ * // The key press event handler.
+ * void vKeyPressEventHandler( char cKey )
+ * {
+ *     // Ensure the LCD back-light is on, then reset the timer that is
+ *     // responsible for turning the back-light off after 5 seconds of
+ *     // key inactivity.  Wait 10 ticks for the command to be successfully sent
+ *     // if it cannot be sent immediately.
+ *     vSetBacklightState( BACKLIGHT_ON );
+ *     if( xTimerReset( xBacklightTimer, 100 ) != pdPASS )
+ *     {
+ *         // The reset command was not executed successfully.  Take appropriate
+ *         // action here.
+ *     }
+ *
+ *     // Perform the rest of the key processing here.
+ * }
+ *
+ * void main( void )
+ * {
+ * int32_t x;
+ *
+ *     // Create then start the one-shot timer that is responsible for turning
+ *     // the back-light off if no keys are pressed within a 5 second period.
+ *     xBacklightTimer = xTimerCreate( "BacklightTimer",           // Just a text name, not used by the kernel.
+ *                                     ( 5000 / portTICK_PERIOD_MS), // The timer period in ticks.
+ *                                     pdFALSE,                    // The timer is a one-shot timer.
+ *                                     0,                          // The id is not used by the callback so can take any value.
+ *                                     vBacklightTimerCallback     // The callback function that switches the LCD back-light off.
+ *                                   );
+ *
+ *     if( xBacklightTimer == NULL )
+ *     {
+ *         // The timer was not created.
+ *     }
+ *     else
+ *     {
+ *         // Start the timer.  No block time is specified, and even if one was
+ *         // it would be ignored because the scheduler has not yet been
+ *         // started.
+ *         if( xTimerStart( xBacklightTimer, 0 ) != pdPASS )
+ *         {
+ *             // The timer could not be set into the Active state.
+ *         }
+ *     }
+ *
+ *     // ...
+ *     // Create tasks here.
+ *     // ...
+ *
+ *     // Starting the scheduler will start the timer running as it has already
+ *     // been set into the active state.
+ *     xTaskStartScheduler();
+ *
+ *     // Should not reach here.
+ *     for( ;; );
+ * }
+ * @endverbatim
+ */
+#define xTimerReset( xTimer, xTicksToWait ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_RESET, ( xTaskGetTickCount() ), NULL, ( xTicksToWait ) )
+
+/**
+ * BaseType_t xTimerStartFromISR( 	TimerHandle_t xTimer,
+ *									BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ * A version of xTimerStart() that can be called from an interrupt service
+ * routine.
+ *
+ * @param xTimer The handle of the timer being started/restarted.
+ *
+ * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most
+ * of its time in the Blocked state, waiting for messages to arrive on the timer
+ * command queue.  Calling xTimerStartFromISR() writes a message to the timer
+ * command queue, so has the potential to transition the timer service/daemon
+ * task out of the Blocked state.  If calling xTimerStartFromISR() causes the
+ * timer service/daemon task to leave the Blocked state, and the timer service/
+ * daemon task has a priority equal to or greater than the currently executing
+ * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will
+ * get set to pdTRUE internally within the xTimerStartFromISR() function.  If
+ * xTimerStartFromISR() sets this value to pdTRUE then a context switch should
+ * be performed before the interrupt exits.
+ *
+ * @return pdFAIL will be returned if the start command could not be sent to
+ * the timer command queue.  pdPASS will be returned if the command was
+ * successfully sent to the timer command queue.  When the command is actually
+ * processed will depend on the priority of the timer service/daemon task
+ * relative to other tasks in the system, although the timers expiry time is
+ * relative to when xTimerStartFromISR() is actually called.  The timer
+ * service/daemon task priority is set by the configTIMER_TASK_PRIORITY
+ * configuration constant.
+ *
+ * Example usage:
+ * @verbatim
+ * // This scenario assumes xBacklightTimer has already been created.  When a
+ * // key is pressed, an LCD back-light is switched on.  If 5 seconds pass
+ * // without a key being pressed, then the LCD back-light is switched off.  In
+ * // this case, the timer is a one-shot timer, and unlike the example given for
+ * // the xTimerReset() function, the key press event handler is an interrupt
+ * // service routine.
+ *
+ * // The callback function assigned to the one-shot timer.  In this case the
+ * // parameter is not used.
+ * void vBacklightTimerCallback( TimerHandle_t pxTimer )
+ * {
+ *     // The timer expired, therefore 5 seconds must have passed since a key
+ *     // was pressed.  Switch off the LCD back-light.
+ *     vSetBacklightState( BACKLIGHT_OFF );
+ * }
+ *
+ * // The key press interrupt service routine.
+ * void vKeyPressEventInterruptHandler( void )
+ * {
+ * BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+ *
+ *     // Ensure the LCD back-light is on, then restart the timer that is
+ *     // responsible for turning the back-light off after 5 seconds of
+ *     // key inactivity.  This is an interrupt service routine so can only
+ *     // call FreeRTOS API functions that end in "FromISR".
+ *     vSetBacklightState( BACKLIGHT_ON );
+ *
+ *     // xTimerStartFromISR() or xTimerResetFromISR() could be called here
+ *     // as both cause the timer to re-calculate its expiry time.
+ *     // xHigherPriorityTaskWoken was initialised to pdFALSE when it was
+ *     // declared (in this function).
+ *     if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS )
+ *     {
+ *         // The start command was not executed successfully.  Take appropriate
+ *         // action here.
+ *     }
+ *
+ *     // Perform the rest of the key processing here.
+ *
+ *     // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch
+ *     // should be performed.  The syntax required to perform a context switch
+ *     // from inside an ISR varies from port to port, and from compiler to
+ *     // compiler.  Inspect the demos for the port you are using to find the
+ *     // actual syntax required.
+ *     if( xHigherPriorityTaskWoken != pdFALSE )
+ *     {
+ *         // Call the interrupt safe yield function here (actual function
+ *         // depends on the FreeRTOS port being used).
+ *     }
+ * }
+ * @endverbatim
+ */
+#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START_FROM_ISR, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U )
+
+/**
+ * BaseType_t xTimerStopFromISR( 	TimerHandle_t xTimer,
+ *									BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ * A version of xTimerStop() that can be called from an interrupt service
+ * routine.
+ *
+ * @param xTimer The handle of the timer being stopped.
+ *
+ * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most
+ * of its time in the Blocked state, waiting for messages to arrive on the timer
+ * command queue.  Calling xTimerStopFromISR() writes a message to the timer
+ * command queue, so has the potential to transition the timer service/daemon
+ * task out of the Blocked state.  If calling xTimerStopFromISR() causes the
+ * timer service/daemon task to leave the Blocked state, and the timer service/
+ * daemon task has a priority equal to or greater than the currently executing
+ * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will
+ * get set to pdTRUE internally within the xTimerStopFromISR() function.  If
+ * xTimerStopFromISR() sets this value to pdTRUE then a context switch should
+ * be performed before the interrupt exits.
+ *
+ * @return pdFAIL will be returned if the stop command could not be sent to
+ * the timer command queue.  pdPASS will be returned if the command was
+ * successfully sent to the timer command queue.  When the command is actually
+ * processed will depend on the priority of the timer service/daemon task
+ * relative to other tasks in the system.  The timer service/daemon task
+ * priority is set by the configTIMER_TASK_PRIORITY configuration constant.
+ *
+ * Example usage:
+ * @verbatim
+ * // This scenario assumes xTimer has already been created and started.  When
+ * // an interrupt occurs, the timer should be simply stopped.
+ *
+ * // The interrupt service routine that stops the timer.
+ * void vAnExampleInterruptServiceRoutine( void )
+ * {
+ * BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+ *
+ *     // The interrupt has occurred - simply stop the timer.
+ *     // xHigherPriorityTaskWoken was set to pdFALSE where it was defined
+ *     // (within this function).  As this is an interrupt service routine, only
+ *     // FreeRTOS API functions that end in "FromISR" can be used.
+ *     if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS )
+ *     {
+ *         // The stop command was not executed successfully.  Take appropriate
+ *         // action here.
+ *     }
+ *
+ *     // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch
+ *     // should be performed.  The syntax required to perform a context switch
+ *     // from inside an ISR varies from port to port, and from compiler to
+ *     // compiler.  Inspect the demos for the port you are using to find the
+ *     // actual syntax required.
+ *     if( xHigherPriorityTaskWoken != pdFALSE )
+ *     {
+ *         // Call the interrupt safe yield function here (actual function
+ *         // depends on the FreeRTOS port being used).
+ *     }
+ * }
+ * @endverbatim
+ */
+#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP_FROM_ISR, 0, ( pxHigherPriorityTaskWoken ), 0U )
+
+/**
+ * BaseType_t xTimerChangePeriodFromISR( TimerHandle_t xTimer,
+ *										 TickType_t xNewPeriod,
+ *										 BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ * A version of xTimerChangePeriod() that can be called from an interrupt
+ * service routine.
+ *
+ * @param xTimer The handle of the timer that is having its period changed.
+ *
+ * @param xNewPeriod The new period for xTimer. Timer periods are specified in
+ * tick periods, so the constant portTICK_PERIOD_MS can be used to convert a time
+ * that has been specified in milliseconds.  For example, if the timer must
+ * expire after 100 ticks, then xNewPeriod should be set to 100.  Alternatively,
+ * if the timer must expire after 500ms, then xNewPeriod can be set to
+ * ( 500 / portTICK_PERIOD_MS ) provided configTICK_RATE_HZ is less than
+ * or equal to 1000.
+ *
+ * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most
+ * of its time in the Blocked state, waiting for messages to arrive on the timer
+ * command queue.  Calling xTimerChangePeriodFromISR() writes a message to the
+ * timer command queue, so has the potential to transition the timer service/
+ * daemon task out of the Blocked state.  If calling xTimerChangePeriodFromISR()
+ * causes the timer service/daemon task to leave the Blocked state, and the
+ * timer service/daemon task has a priority equal to or greater than the
+ * currently executing task (the task that was interrupted), then
+ * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the
+ * xTimerChangePeriodFromISR() function.  If xTimerChangePeriodFromISR() sets
+ * this value to pdTRUE then a context switch should be performed before the
+ * interrupt exits.
+ *
+ * @return pdFAIL will be returned if the command to change the timers period
+ * could not be sent to the timer command queue.  pdPASS will be returned if the
+ * command was successfully sent to the timer command queue.  When the command
+ * is actually processed will depend on the priority of the timer service/daemon
+ * task relative to other tasks in the system.  The timer service/daemon task
+ * priority is set by the configTIMER_TASK_PRIORITY configuration constant.
+ *
+ * Example usage:
+ * @verbatim
+ * // This scenario assumes xTimer has already been created and started.  When
+ * // an interrupt occurs, the period of xTimer should be changed to 500ms.
+ *
+ * // The interrupt service routine that changes the period of xTimer.
+ * void vAnExampleInterruptServiceRoutine( void )
+ * {
+ * BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+ *
+ *     // The interrupt has occurred - change the period of xTimer to 500ms.
+ *     // xHigherPriorityTaskWoken was set to pdFALSE where it was defined
+ *     // (within this function).  As this is an interrupt service routine, only
+ *     // FreeRTOS API functions that end in "FromISR" can be used.
+ *     if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS )
+ *     {
+ *         // The command to change the timers period was not executed
+ *         // successfully.  Take appropriate action here.
+ *     }
+ *
+ *     // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch
+ *     // should be performed.  The syntax required to perform a context switch
+ *     // from inside an ISR varies from port to port, and from compiler to
+ *     // compiler.  Inspect the demos for the port you are using to find the
+ *     // actual syntax required.
+ *     if( xHigherPriorityTaskWoken != pdFALSE )
+ *     {
+ *         // Call the interrupt safe yield function here (actual function
+ *         // depends on the FreeRTOS port being used).
+ *     }
+ * }
+ * @endverbatim
+ */
+#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD_FROM_ISR, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U )
+
+/**
+ * BaseType_t xTimerResetFromISR( 	TimerHandle_t xTimer,
+ *									BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ * A version of xTimerReset() that can be called from an interrupt service
+ * routine.
+ *
+ * @param xTimer The handle of the timer that is to be started, reset, or
+ * restarted.
+ *
+ * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most
+ * of its time in the Blocked state, waiting for messages to arrive on the timer
+ * command queue.  Calling xTimerResetFromISR() writes a message to the timer
+ * command queue, so has the potential to transition the timer service/daemon
+ * task out of the Blocked state.  If calling xTimerResetFromISR() causes the
+ * timer service/daemon task to leave the Blocked state, and the timer service/
+ * daemon task has a priority equal to or greater than the currently executing
+ * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will
+ * get set to pdTRUE internally within the xTimerResetFromISR() function.  If
+ * xTimerResetFromISR() sets this value to pdTRUE then a context switch should
+ * be performed before the interrupt exits.
+ *
+ * @return pdFAIL will be returned if the reset command could not be sent to
+ * the timer command queue.  pdPASS will be returned if the command was
+ * successfully sent to the timer command queue.  When the command is actually
+ * processed will depend on the priority of the timer service/daemon task
+ * relative to other tasks in the system, although the timers expiry time is
+ * relative to when xTimerResetFromISR() is actually called.  The timer service/daemon
+ * task priority is set by the configTIMER_TASK_PRIORITY configuration constant.
+ *
+ * Example usage:
+ * @verbatim
+ * // This scenario assumes xBacklightTimer has already been created.  When a
+ * // key is pressed, an LCD back-light is switched on.  If 5 seconds pass
+ * // without a key being pressed, then the LCD back-light is switched off.  In
+ * // this case, the timer is a one-shot timer, and unlike the example given for
+ * // the xTimerReset() function, the key press event handler is an interrupt
+ * // service routine.
+ *
+ * // The callback function assigned to the one-shot timer.  In this case the
+ * // parameter is not used.
+ * void vBacklightTimerCallback( TimerHandle_t pxTimer )
+ * {
+ *     // The timer expired, therefore 5 seconds must have passed since a key
+ *     // was pressed.  Switch off the LCD back-light.
+ *     vSetBacklightState( BACKLIGHT_OFF );
+ * }
+ *
+ * // The key press interrupt service routine.
+ * void vKeyPressEventInterruptHandler( void )
+ * {
+ * BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+ *
+ *     // Ensure the LCD back-light is on, then reset the timer that is
+ *     // responsible for turning the back-light off after 5 seconds of
+ *     // key inactivity.  This is an interrupt service routine so can only
+ *     // call FreeRTOS API functions that end in "FromISR".
+ *     vSetBacklightState( BACKLIGHT_ON );
+ *
+ *     // xTimerStartFromISR() or xTimerResetFromISR() could be called here
+ *     // as both cause the timer to re-calculate its expiry time.
+ *     // xHigherPriorityTaskWoken was initialised to pdFALSE when it was
+ *     // declared (in this function).
+ *     if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS )
+ *     {
+ *         // The reset command was not executed successfully.  Take appropriate
+ *         // action here.
+ *     }
+ *
+ *     // Perform the rest of the key processing here.
+ *
+ *     // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch
+ *     // should be performed.  The syntax required to perform a context switch
+ *     // from inside an ISR varies from port to port, and from compiler to
+ *     // compiler.  Inspect the demos for the port you are using to find the
+ *     // actual syntax required.
+ *     if( xHigherPriorityTaskWoken != pdFALSE )
+ *     {
+ *         // Call the interrupt safe yield function here (actual function
+ *         // depends on the FreeRTOS port being used).
+ *     }
+ * }
+ * @endverbatim
+ */
+#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_RESET_FROM_ISR, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U )
+
+
+/**
+ * BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend,
+ *                                          void *pvParameter1,
+ *                                          uint32_t ulParameter2,
+ *                                          BaseType_t *pxHigherPriorityTaskWoken );
+ *
+ *
+ * Used from application interrupt service routines to defer the execution of a
+ * function to the RTOS daemon task (the timer service task, hence this function
+ * is implemented in timers.c and is prefixed with 'Timer').
+ *
+ * Ideally an interrupt service routine (ISR) is kept as short as possible, but
+ * sometimes an ISR either has a lot of processing to do, or needs to perform
+ * processing that is not deterministic.  In these cases
+ * xTimerPendFunctionCallFromISR() can be used to defer processing of a function
+ * to the RTOS daemon task.
+ *
+ * A mechanism is provided that allows the interrupt to return directly to the
+ * task that will subsequently execute the pended callback function.  This
+ * allows the callback function to execute contiguously in time with the
+ * interrupt - just as if the callback had executed in the interrupt itself.
+ *
+ * @param xFunctionToPend The function to execute from the timer service/
+ * daemon task.  The function must conform to the PendedFunction_t
+ * prototype.
+ *
+ * @param pvParameter1 The value of the callback function's first parameter.
+ * The parameter has a void * type to allow it to be used to pass any type.
+ * For example, unsigned longs can be cast to a void *, or the void * can be
+ * used to point to a structure.
+ *
+ * @param ulParameter2 The value of the callback function's second parameter.
+ *
+ * @param pxHigherPriorityTaskWoken As mentioned above, calling this function
+ * will result in a message being sent to the timer daemon task.  If the
+ * priority of the timer daemon task (which is set using
+ * configTIMER_TASK_PRIORITY in FreeRTOSConfig.h) is higher than the priority of
+ * the currently running task (the task the interrupt interrupted) then
+ * *pxHigherPriorityTaskWoken will be set to pdTRUE within
+ * xTimerPendFunctionCallFromISR(), indicating that a context switch should be
+ * requested before the interrupt exits.  For that reason
+ * *pxHigherPriorityTaskWoken must be initialised to pdFALSE.  See the
+ * example code below.
+ *
+ * @return pdPASS is returned if the message was successfully sent to the
+ * timer daemon task, otherwise pdFALSE is returned.
+ *
+ * Example usage:
+ * @verbatim
+ *
+ *	// The callback function that will execute in the context of the daemon task.
+ *  // Note callback functions must all use this same prototype.
+ *  void vProcessInterface( void *pvParameter1, uint32_t ulParameter2 )
+ *	{
+ *		BaseType_t xInterfaceToService;
+ *
+ *		// The interface that requires servicing is passed in the second
+ *      // parameter.  The first parameter is not used in this case.
+ *		xInterfaceToService = ( BaseType_t ) ulParameter2;
+ *
+ *		// ...Perform the processing here...
+ *	}
+ *
+ *	// An ISR that receives data packets from multiple interfaces
+ *  void vAnISR( void )
+ *	{
+ *		BaseType_t xInterfaceToService, xHigherPriorityTaskWoken;
+ *
+ *		// Query the hardware to determine which interface needs processing.
+ *		xInterfaceToService = prvCheckInterfaces();
+ *
+ *      // The actual processing is to be deferred to a task.  Request the
+ *      // vProcessInterface() callback function is executed, passing in the
+ *		// number of the interface that needs processing.  The interface to
+ *		// service is passed in the second parameter.  The first parameter is
+ *		// not used in this case.
+ *		xHigherPriorityTaskWoken = pdFALSE;
+ *		xTimerPendFunctionCallFromISR( vProcessInterface, NULL, ( uint32_t ) xInterfaceToService, &xHigherPriorityTaskWoken );
+ *
+ *		// If xHigherPriorityTaskWoken is now set to pdTRUE then a context
+ *		// switch should be requested.  The macro used is port specific and will
+ *		// be either portYIELD_FROM_ISR() or portEND_SWITCHING_ISR() - refer to
+ *		// the documentation page for the port being used.
+ *		portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+ *
+ *	}
+ * @endverbatim
+ */
+BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, BaseType_t *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION;
+
+ /**
+  * BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend,
+  *                                    void *pvParameter1,
+  *                                    uint32_t ulParameter2,
+  *                                    TickType_t xTicksToWait );
+  *
+  *
+  * Used to defer the execution of a function to the RTOS daemon task (the timer
+  * service task, hence this function is implemented in timers.c and is prefixed
+  * with 'Timer').
+  *
+  * @param xFunctionToPend The function to execute from the timer service/
+  * daemon task.  The function must conform to the PendedFunction_t
+  * prototype.
+  *
+  * @param pvParameter1 The value of the callback function's first parameter.
+  * The parameter has a void * type to allow it to be used to pass any type.
+  * For example, unsigned longs can be cast to a void *, or the void * can be
+  * used to point to a structure.
+  *
+  * @param ulParameter2 The value of the callback function's second parameter.
+  *
+  * @param xTicksToWait Calling this function will result in a message being
+  * sent to the timer daemon task on a queue.  xTicksToWait is the amount of
+  * time the calling task should remain in the Blocked state (so not using any
+  * processing time) for space to become available on the timer queue if the
+  * queue is found to be full.
+  *
+  * @return pdPASS is returned if the message was successfully sent to the
+  * timer daemon task, otherwise pdFALSE is returned.
+  *
+  */
+BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+/**
+ * const char * const pcTimerGetTimerName( TimerHandle_t xTimer );
+ *
+ * Returns the name that was assigned to a timer when the timer was created.
+ *
+ * @param xTimer The handle of the timer being queried.
+ *
+ * @return The name assigned to the timer specified by the xTimer parameter.
+ */
+const char * pcTimerGetTimerName( TimerHandle_t xTimer ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+/*
+ * Functions beyond this part are not part of the public API and are intended
+ * for use by the kernel only.
+ */
+BaseType_t xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION;
+BaseType_t xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait ) PRIVILEGED_FUNCTION;
+
+#ifdef __cplusplus
+}
+#endif
+#endif /* TIMERS_H */
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/list.c b/crazyflie-firmware-src/src/lib/FreeRTOS/list.c
new file mode 100644
index 0000000000000000000000000000000000000000..ebacafddecef7493bf70a898db5c53d859352eef
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/list.c
@@ -0,0 +1,240 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+#include <stdlib.h>
+#include "FreeRTOS.h"
+#include "list.h"
+
+/*-----------------------------------------------------------
+ * PUBLIC LIST API documented in list.h
+ *----------------------------------------------------------*/
+
+void vListInitialise( List_t * const pxList )
+{
+	/* The list structure contains a list item which is used to mark the
+	end of the list.  To initialise the list the list end is inserted
+	as the only list entry. */
+	pxList->pxIndex = ( ListItem_t * ) &( pxList->xListEnd );			/*lint !e826 !e740 The mini list structure is used as the list end to save RAM.  This is checked and valid. */
+
+	/* The list end value is the highest possible value in the list to
+	ensure it remains at the end of the list. */
+	pxList->xListEnd.xItemValue = portMAX_DELAY;
+
+	/* The list end next and previous pointers point to itself so we know
+	when the list is empty. */
+	pxList->xListEnd.pxNext = ( ListItem_t * ) &( pxList->xListEnd );	/*lint !e826 !e740 The mini list structure is used as the list end to save RAM.  This is checked and valid. */
+	pxList->xListEnd.pxPrevious = ( ListItem_t * ) &( pxList->xListEnd );/*lint !e826 !e740 The mini list structure is used as the list end to save RAM.  This is checked and valid. */
+
+	pxList->uxNumberOfItems = ( UBaseType_t ) 0U;
+
+	/* Write known values into the list if
+	configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
+	listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList );
+	listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList );
+}
+/*-----------------------------------------------------------*/
+
+void vListInitialiseItem( ListItem_t * const pxItem )
+{
+	/* Make sure the list item is not recorded as being on a list. */
+	pxItem->pvContainer = NULL;
+
+	/* Write known values into the list item if
+	configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */
+	listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem );
+	listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem );
+}
+/*-----------------------------------------------------------*/
+
+void vListInsertEnd( List_t * const pxList, ListItem_t * const pxNewListItem )
+{
+ListItem_t * const pxIndex = pxList->pxIndex;
+
+	/* Only effective when configASSERT() is also defined, these tests may catch
+	the list data structures being overwritten in memory.  They will not catch
+	data errors caused by incorrect configuration or use of FreeRTOS. */
+	listTEST_LIST_INTEGRITY( pxList );
+	listTEST_LIST_ITEM_INTEGRITY( pxNewListItem );
+
+	/* Insert a new list item into pxList, but rather than sort the list,
+	makes the new list item the last item to be removed by a call to
+	listGET_OWNER_OF_NEXT_ENTRY(). */
+	pxNewListItem->pxNext = pxIndex;
+	pxNewListItem->pxPrevious = pxIndex->pxPrevious;
+
+	/* Only used during decision coverage testing. */
+	mtCOVERAGE_TEST_DELAY();
+
+	pxIndex->pxPrevious->pxNext = pxNewListItem;
+	pxIndex->pxPrevious = pxNewListItem;
+
+	/* Remember which list the item is in. */
+	pxNewListItem->pvContainer = ( void * ) pxList;
+
+	( pxList->uxNumberOfItems )++;
+}
+/*-----------------------------------------------------------*/
+
+void vListInsert( List_t * const pxList, ListItem_t * const pxNewListItem )
+{
+ListItem_t *pxIterator;
+const TickType_t xValueOfInsertion = pxNewListItem->xItemValue;
+
+	/* Only effective when configASSERT() is also defined, these tests may catch
+	the list data structures being overwritten in memory.  They will not catch
+	data errors caused by incorrect configuration or use of FreeRTOS. */
+	listTEST_LIST_INTEGRITY( pxList );
+	listTEST_LIST_ITEM_INTEGRITY( pxNewListItem );
+
+	/* Insert the new list item into the list, sorted in xItemValue order.
+
+	If the list already contains a list item with the same item value then the
+	new list item should be placed after it.  This ensures that TCB's which are
+	stored in ready lists (all of which have the same xItemValue value) get a
+	share of the CPU.  However, if the xItemValue is the same as the back marker
+	the iteration loop below will not end.  Therefore the value is checked
+	first, and the algorithm slightly modified if necessary. */
+	if( xValueOfInsertion == portMAX_DELAY )
+	{
+		pxIterator = pxList->xListEnd.pxPrevious;
+	}
+	else
+	{
+		/* *** NOTE ***********************************************************
+		If you find your application is crashing here then likely causes are
+		listed below.  In addition see http://www.freertos.org/FAQHelp.html for
+		more tips, and ensure configASSERT() is defined!
+		http://www.freertos.org/a00110.html#configASSERT
+
+			1) Stack overflow -
+			   see http://www.freertos.org/Stacks-and-stack-overflow-checking.html
+			2) Incorrect interrupt priority assignment, especially on Cortex-M
+			   parts where numerically high priority values denote low actual
+			   interrupt priorities, which can seem counter intuitive.  See
+			   http://www.freertos.org/RTOS-Cortex-M3-M4.html and the definition
+			   of configMAX_SYSCALL_INTERRUPT_PRIORITY on
+			   http://www.freertos.org/a00110.html
+			3) Calling an API function from within a critical section or when
+			   the scheduler is suspended, or calling an API function that does
+			   not end in "FromISR" from an interrupt.
+			4) Using a queue or semaphore before it has been initialised or
+			   before the scheduler has been started (are interrupts firing
+			   before vTaskStartScheduler() has been called?).
+		**********************************************************************/
+
+		for( pxIterator = ( ListItem_t * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) /*lint !e826 !e740 The mini list structure is used as the list end to save RAM.  This is checked and valid. */
+		{
+			/* There is nothing to do here, just iterating to the wanted
+			insertion position. */
+		}
+	}
+
+	pxNewListItem->pxNext = pxIterator->pxNext;
+	pxNewListItem->pxNext->pxPrevious = pxNewListItem;
+	pxNewListItem->pxPrevious = pxIterator;
+	pxIterator->pxNext = pxNewListItem;
+
+	/* Remember which list the item is in.  This allows fast removal of the
+	item later. */
+	pxNewListItem->pvContainer = ( void * ) pxList;
+
+	( pxList->uxNumberOfItems )++;
+}
+/*-----------------------------------------------------------*/
+
+UBaseType_t uxListRemove( ListItem_t * const pxItemToRemove )
+{
+/* The list item knows which list it is in.  Obtain the list from the list
+item. */
+List_t * const pxList = ( List_t * ) pxItemToRemove->pvContainer;
+
+	pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious;
+	pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext;
+
+	/* Only used during decision coverage testing. */
+	mtCOVERAGE_TEST_DELAY();
+
+	/* Make sure the index is left pointing to a valid item. */
+	if( pxList->pxIndex == pxItemToRemove )
+	{
+		pxList->pxIndex = pxItemToRemove->pxPrevious;
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	pxItemToRemove->pvContainer = NULL;
+	( pxList->uxNumberOfItems )--;
+
+	return pxList->uxNumberOfItems;
+}
+/*-----------------------------------------------------------*/
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM3/port.c b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM3/port.c
new file mode 100644
index 0000000000000000000000000000000000000000..263b9ed60bf70ffd741539b7f4c259694e222bda
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM3/port.c
@@ -0,0 +1,749 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/*-----------------------------------------------------------
+ * Implementation of functions defined in portable.h for the ARM CM3 port.
+ *----------------------------------------------------------*/
+
+/* Scheduler includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+
+/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is
+defined.  The value should also ensure backward compatibility.
+FreeRTOS.org versions prior to V4.4.0 did not include this definition. */
+#ifndef configKERNEL_INTERRUPT_PRIORITY
+	#define configKERNEL_INTERRUPT_PRIORITY 255
+#endif
+
+#ifndef configSYSTICK_CLOCK_HZ
+	#define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
+	/* Ensure the SysTick is clocked at the same frequency as the core. */
+	#define portNVIC_SYSTICK_CLK_BIT	( 1UL << 2UL )
+#else
+	/* The way the SysTick is clocked is not modified in case it is not the same
+	as the core. */
+	#define portNVIC_SYSTICK_CLK_BIT	( 0 )
+#endif
+
+/* Constants required to manipulate the core.  Registers first... */
+#define portNVIC_SYSTICK_CTRL_REG			( * ( ( volatile uint32_t * ) 0xe000e010 ) )
+#define portNVIC_SYSTICK_LOAD_REG			( * ( ( volatile uint32_t * ) 0xe000e014 ) )
+#define portNVIC_SYSTICK_CURRENT_VALUE_REG	( * ( ( volatile uint32_t * ) 0xe000e018 ) )
+#define portNVIC_SYSPRI2_REG				( * ( ( volatile uint32_t * ) 0xe000ed20 ) )
+/* ...then bits in the registers. */
+#define portNVIC_SYSTICK_INT_BIT			( 1UL << 1UL )
+#define portNVIC_SYSTICK_ENABLE_BIT			( 1UL << 0UL )
+#define portNVIC_SYSTICK_COUNT_FLAG_BIT		( 1UL << 16UL )
+#define portNVIC_PENDSVCLEAR_BIT 			( 1UL << 27UL )
+#define portNVIC_PEND_SYSTICK_CLEAR_BIT		( 1UL << 25UL )
+
+#define portNVIC_PENDSV_PRI					( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )
+#define portNVIC_SYSTICK_PRI				( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )
+
+/* Constants required to check the validity of an interrupt priority. */
+#define portFIRST_USER_INTERRUPT_NUMBER		( 16 )
+#define portNVIC_IP_REGISTERS_OFFSET_16 	( 0xE000E3F0 )
+#define portAIRCR_REG						( * ( ( volatile uint32_t * ) 0xE000ED0C ) )
+#define portMAX_8_BIT_VALUE					( ( uint8_t ) 0xff )
+#define portTOP_BIT_OF_BYTE					( ( uint8_t ) 0x80 )
+#define portMAX_PRIGROUP_BITS				( ( uint8_t ) 7 )
+#define portPRIORITY_GROUP_MASK				( 0x07UL << 8UL )
+#define portPRIGROUP_SHIFT					( 8UL )
+
+/* Masks off all bits but the VECTACTIVE bits in the ICSR register. */
+#define portVECTACTIVE_MASK					( 0xFFUL )
+
+/* Constants required to set up the initial stack. */
+#define portINITIAL_XPSR					( 0x01000000UL )
+
+/* The systick is a 24-bit counter. */
+#define portMAX_24_BIT_NUMBER				( 0xffffffUL )
+
+/* A fiddle factor to estimate the number of SysTick counts that would have
+occurred while the SysTick counter is stopped during tickless idle
+calculations. */
+#define portMISSED_COUNTS_FACTOR			( 45UL )
+
+/* Let the user override the pre-loading of the initial LR with the address of
+prvTaskExitError() in case it messes up unwinding of the stack in the
+debugger. */
+#ifdef configTASK_RETURN_ADDRESS
+	#define portTASK_RETURN_ADDRESS	configTASK_RETURN_ADDRESS
+#else
+	#define portTASK_RETURN_ADDRESS	prvTaskExitError
+#endif
+
+/* Each task maintains its own interrupt status in the critical nesting
+variable. */
+static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
+
+/*
+ * Setup the timer to generate the tick interrupts.  The implementation in this
+ * file is weak to allow application writers to change the timer used to
+ * generate the tick interrupt.
+ */
+void vPortSetupTimerInterrupt( void );
+
+/*
+ * Exception handlers.
+ */
+void xPortPendSVHandler( void ) __attribute__ (( naked ));
+void xPortSysTickHandler( void );
+void vPortSVCHandler( void ) __attribute__ (( naked ));
+
+/*
+ * Start first task is a separate function so it can be tested in isolation.
+ */
+static void prvPortStartFirstTask( void ) __attribute__ (( naked ));
+
+/*
+ * Used to catch tasks that attempt to return from their implementing function.
+ */
+static void prvTaskExitError( void );
+
+/*-----------------------------------------------------------*/
+
+/*
+ * The number of SysTick increments that make up one tick period.
+ */
+#if configUSE_TICKLESS_IDLE == 1
+	static uint32_t ulTimerCountsForOneTick = 0;
+#endif /* configUSE_TICKLESS_IDLE */
+
+/*
+ * The maximum number of tick periods that can be suppressed is limited by the
+ * 24 bit resolution of the SysTick timer.
+ */
+#if configUSE_TICKLESS_IDLE == 1
+	static uint32_t xMaximumPossibleSuppressedTicks = 0;
+#endif /* configUSE_TICKLESS_IDLE */
+
+/*
+ * Compensate for the CPU cycles that pass while the SysTick is stopped (low
+ * power functionality only.
+ */
+#if configUSE_TICKLESS_IDLE == 1
+	static uint32_t ulStoppedTimerCompensation = 0;
+#endif /* configUSE_TICKLESS_IDLE */
+
+/*
+ * Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure
+ * FreeRTOS API functions are not called from interrupts that have been assigned
+ * a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
+ */
+#if ( configASSERT_DEFINED == 1 )
+	 static uint8_t ucMaxSysCallPriority = 0;
+	 static uint32_t ulMaxPRIGROUPValue = 0;
+	 static const volatile uint8_t * const pcInterruptPriorityRegisters = ( const volatile uint8_t * const ) portNVIC_IP_REGISTERS_OFFSET_16;
+#endif /* configASSERT_DEFINED */
+
+/*-----------------------------------------------------------*/
+
+/*
+ * See header file for description.
+ */
+StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
+{
+	/* Simulate the stack frame as it would be created by a context switch
+	interrupt. */
+	pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */
+	*pxTopOfStack = portINITIAL_XPSR;	/* xPSR */
+	pxTopOfStack--;
+	*pxTopOfStack = ( StackType_t ) pxCode;	/* PC */
+	pxTopOfStack--;
+	*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS;	/* LR */
+	pxTopOfStack -= 5;	/* R12, R3, R2 and R1. */
+	*pxTopOfStack = ( StackType_t ) pvParameters;	/* R0 */
+	pxTopOfStack -= 8;	/* R11, R10, R9, R8, R7, R6, R5 and R4. */
+
+	return pxTopOfStack;
+}
+/*-----------------------------------------------------------*/
+
+static void prvTaskExitError( void )
+{
+	/* A function that implements a task must not exit or attempt to return to
+	its caller as there is nothing to return to.  If a task wants to exit it
+	should instead call vTaskDelete( NULL ).
+
+	Artificially force an assert() to be triggered if configASSERT() is
+	defined, then stop here so application writers can catch the error. */
+	configASSERT( uxCriticalNesting == ~0UL );
+	portDISABLE_INTERRUPTS();
+	for( ;; );
+}
+/*-----------------------------------------------------------*/
+
+void vPortSVCHandler( void )
+{
+	__asm volatile (
+					"	ldr	r3, pxCurrentTCBConst2		\n" /* Restore the context. */
+					"	ldr r1, [r3]					\n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */
+					"	ldr r0, [r1]					\n" /* The first item in pxCurrentTCB is the task top of stack. */
+					"	ldmia r0!, {r4-r11}				\n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */
+					"	msr psp, r0						\n" /* Restore the task stack pointer. */
+					"	isb								\n"
+					"	mov r0, #0 						\n"
+					"	msr	basepri, r0					\n"
+					"	orr r14, #0xd					\n"
+					"	bx r14							\n"
+					"									\n"
+					"	.align 2						\n"
+					"pxCurrentTCBConst2: .word pxCurrentTCB				\n"
+				);
+}
+/*-----------------------------------------------------------*/
+
+static void prvPortStartFirstTask( void )
+{
+	__asm volatile(
+					" ldr r0, =0xE000ED08 	\n" /* Use the NVIC offset register to locate the stack. */
+					" ldr r0, [r0] 			\n"
+					" ldr r0, [r0] 			\n"
+					" msr msp, r0			\n" /* Set the msp back to the start of the stack. */
+					" cpsie i				\n" /* Globally enable interrupts. */
+					" cpsie f				\n"
+					" dsb					\n"
+					" isb					\n"
+					" svc 0					\n" /* System call to start first task. */
+					" nop					\n"
+				);
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * See header file for description.
+ */
+BaseType_t xPortStartScheduler( void )
+{
+	/* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0.
+	See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */
+	configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY );
+
+	#if( configASSERT_DEFINED == 1 )
+	{
+		volatile uint32_t ulOriginalPriority;
+		volatile uint8_t * const pucFirstUserPriorityRegister = ( volatile uint8_t * const ) ( portNVIC_IP_REGISTERS_OFFSET_16 + portFIRST_USER_INTERRUPT_NUMBER );
+		volatile uint8_t ucMaxPriorityValue;
+
+		/* Determine the maximum priority from which ISR safe FreeRTOS API
+		functions can be called.  ISR safe functions are those that end in
+		"FromISR".  FreeRTOS maintains separate thread and ISR API functions to
+		ensure interrupt entry is as fast and simple as possible.
+
+		Save the interrupt priority value that is about to be clobbered. */
+		ulOriginalPriority = *pucFirstUserPriorityRegister;
+
+		/* Determine the number of priority bits available.  First write to all
+		possible bits. */
+		*pucFirstUserPriorityRegister = portMAX_8_BIT_VALUE;
+
+		/* Read the value back to see how many bits stuck. */
+		ucMaxPriorityValue = *pucFirstUserPriorityRegister;
+
+		/* Use the same mask on the maximum system call priority. */
+		ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
+
+		/* Calculate the maximum acceptable priority group value for the number
+		of bits read back. */
+		ulMaxPRIGROUPValue = portMAX_PRIGROUP_BITS;
+		while( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE )
+		{
+			ulMaxPRIGROUPValue--;
+			ucMaxPriorityValue <<= ( uint8_t ) 0x01;
+		}
+
+		/* Shift the priority group value back to its position within the AIRCR
+		register. */
+		ulMaxPRIGROUPValue <<= portPRIGROUP_SHIFT;
+		ulMaxPRIGROUPValue &= portPRIORITY_GROUP_MASK;
+
+		/* Restore the clobbered interrupt priority register to its original
+		value. */
+		*pucFirstUserPriorityRegister = ulOriginalPriority;
+	}
+	#endif /* conifgASSERT_DEFINED */
+
+	/* Make PendSV and SysTick the lowest priority interrupts. */
+	portNVIC_SYSPRI2_REG |= portNVIC_PENDSV_PRI;
+	portNVIC_SYSPRI2_REG |= portNVIC_SYSTICK_PRI;
+
+	/* Start the timer that generates the tick ISR.  Interrupts are disabled
+	here already. */
+	vPortSetupTimerInterrupt();
+
+	/* Initialise the critical nesting count ready for the first task. */
+	uxCriticalNesting = 0;
+
+	/* Start the first task. */
+	prvPortStartFirstTask();
+
+	/* Should never get here as the tasks will now be executing!  Call the task
+	exit error function to prevent compiler warnings about a static function
+	not being called in the case that the application writer overrides this
+	functionality by defining configTASK_RETURN_ADDRESS. */
+	prvTaskExitError();
+
+	/* Should not get here! */
+	return 0;
+}
+/*-----------------------------------------------------------*/
+
+void vPortEndScheduler( void )
+{
+	/* Not implemented in ports where there is nothing to return to.
+	Artificially force an assert. */
+	configASSERT( uxCriticalNesting == 1000UL );
+}
+/*-----------------------------------------------------------*/
+
+void vPortYield( void )
+{
+	/* Set a PendSV to request a context switch. */
+	portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
+
+	/* Barriers are normally not required but do ensure the code is completely
+	within the specified behaviour for the architecture. */
+	__asm volatile( "dsb" );
+	__asm volatile( "isb" );
+}
+/*-----------------------------------------------------------*/
+
+void vPortEnterCritical( void )
+{
+	portDISABLE_INTERRUPTS();
+	uxCriticalNesting++;
+	__asm volatile( "dsb" );
+	__asm volatile( "isb" );
+	
+	/* This is not the interrupt safe version of the enter critical function so
+	assert() if it is being called from an interrupt context.  Only API 
+	functions that end in "FromISR" can be used in an interrupt.  Only assert if
+	the critical nesting count is 1 to protect against recursive calls if the
+	assert function also uses a critical section. */
+	if( uxCriticalNesting == 1 )
+	{
+		configASSERT( ( portNVIC_INT_CTRL_REG & portVECTACTIVE_MASK ) == 0 );
+	}
+}
+/*-----------------------------------------------------------*/
+
+void vPortExitCritical( void )
+{
+	configASSERT( uxCriticalNesting );
+	uxCriticalNesting--;
+	if( uxCriticalNesting == 0 )
+	{
+		portENABLE_INTERRUPTS();
+	}
+}
+/*-----------------------------------------------------------*/
+
+__attribute__(( naked )) uint32_t ulPortSetInterruptMask( void )
+{
+	__asm volatile														\
+	(																	\
+		"	mrs r0, basepri											\n" \
+		"	mov r1, %0												\n"	\
+		"	msr basepri, r1											\n" \
+		"	bx lr													\n" \
+		:: "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "r0", "r1"	\
+	);
+
+	/* This return will not be reached but is necessary to prevent compiler
+	warnings. */
+	return 0;
+}
+/*-----------------------------------------------------------*/
+
+__attribute__(( naked )) void vPortClearInterruptMask( uint32_t ulNewMaskValue )
+{
+	__asm volatile													\
+	(																\
+		"	msr basepri, r0										\n"	\
+		"	bx lr												\n" \
+		:::"r0"														\
+	);
+
+	/* Just to avoid compiler warnings. */
+	( void ) ulNewMaskValue;
+}
+/*-----------------------------------------------------------*/
+
+void xPortPendSVHandler( void )
+{
+	/* This is a naked function. */
+
+	__asm volatile
+	(
+	"	mrs r0, psp							\n"
+	"	isb									\n"
+	"										\n"
+	"	ldr	r3, pxCurrentTCBConst			\n" /* Get the location of the current TCB. */
+	"	ldr	r2, [r3]						\n"
+	"										\n"
+	"	stmdb r0!, {r4-r11}					\n" /* Save the remaining registers. */
+	"	str r0, [r2]						\n" /* Save the new top of stack into the first member of the TCB. */
+	"										\n"
+	"	stmdb sp!, {r3, r14}				\n"
+	"	mov r0, %0							\n"
+	"	msr basepri, r0						\n"
+	"	bl vTaskSwitchContext				\n"
+	"	mov r0, #0							\n"
+	"	msr basepri, r0						\n"
+	"	ldmia sp!, {r3, r14}				\n"
+	"										\n"	/* Restore the context, including the critical nesting count. */
+	"	ldr r1, [r3]						\n"
+	"	ldr r0, [r1]						\n" /* The first item in pxCurrentTCB is the task top of stack. */
+	"	ldmia r0!, {r4-r11}					\n" /* Pop the registers. */
+	"	msr psp, r0							\n"
+	"	isb									\n"
+	"	bx r14								\n"
+	"										\n"
+	"	.align 2							\n"
+	"pxCurrentTCBConst: .word pxCurrentTCB	\n"
+	::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY)
+	);
+}
+/*-----------------------------------------------------------*/
+
+void xPortSysTickHandler( void )
+{
+	/* The SysTick runs at the lowest interrupt priority, so when this interrupt
+	executes all interrupts must be unmasked.  There is therefore no need to
+	save and then restore the interrupt mask value as its value is already
+	known. */
+	( void ) portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		/* Increment the RTOS tick. */
+		if( xTaskIncrementTick() != pdFALSE )
+		{
+			/* A context switch is required.  Context switching is performed in
+			the PendSV interrupt.  Pend the PendSV interrupt. */
+			portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
+		}
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( 0 );
+}
+/*-----------------------------------------------------------*/
+
+#if configUSE_TICKLESS_IDLE == 1
+
+	__attribute__((weak)) void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime )
+	{
+	uint32_t ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements, ulSysTickCTRL;
+	TickType_t xModifiableIdleTime;
+
+		/* Make sure the SysTick reload value does not overflow the counter. */
+		if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )
+		{
+			xExpectedIdleTime = xMaximumPossibleSuppressedTicks;
+		}
+
+		/* Stop the SysTick momentarily.  The time the SysTick is stopped for
+		is accounted for as best it can be, but using the tickless mode will
+		inevitably result in some tiny drift of the time maintained by the
+		kernel with respect to calendar time. */
+		portNVIC_SYSTICK_CTRL_REG &= ~portNVIC_SYSTICK_ENABLE_BIT;
+
+		/* Calculate the reload value required to wait xExpectedIdleTime
+		tick periods.  -1 is used because this code will execute part way
+		through one of the tick periods. */
+		ulReloadValue = portNVIC_SYSTICK_CURRENT_VALUE_REG + ( ulTimerCountsForOneTick * ( xExpectedIdleTime - 1UL ) );
+		if( ulReloadValue > ulStoppedTimerCompensation )
+		{
+			ulReloadValue -= ulStoppedTimerCompensation;
+		}
+
+		/* Enter a critical section but don't use the taskENTER_CRITICAL()
+		method as that will mask interrupts that should exit sleep mode. */
+		__asm volatile( "cpsid i" );
+
+		/* If a context switch is pending or a task is waiting for the scheduler
+		to be unsuspended then abandon the low power entry. */
+		if( eTaskConfirmSleepModeStatus() == eAbortSleep )
+		{
+			/* Restart from whatever is left in the count register to complete
+			this tick period. */
+			portNVIC_SYSTICK_LOAD_REG = portNVIC_SYSTICK_CURRENT_VALUE_REG;
+
+			/* Restart SysTick. */
+			portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
+
+			/* Reset the reload register to the value required for normal tick
+			periods. */
+			portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
+
+			/* Re-enable interrupts - see comments above the cpsid instruction()
+			above. */
+			__asm volatile( "cpsie i" );
+		}
+		else
+		{
+			/* Set the new reload value. */
+			portNVIC_SYSTICK_LOAD_REG = ulReloadValue;
+
+			/* Clear the SysTick count flag and set the count value back to
+			zero. */
+			portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
+
+			/* Restart SysTick. */
+			portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
+
+			/* Sleep until something happens.  configPRE_SLEEP_PROCESSING() can
+			set its parameter to 0 to indicate that its implementation contains
+			its own wait for interrupt or wait for event instruction, and so wfi
+			should not be executed again.  However, the original expected idle
+			time variable must remain unmodified, so a copy is taken. */
+			xModifiableIdleTime = xExpectedIdleTime;
+			configPRE_SLEEP_PROCESSING( xModifiableIdleTime );
+			if( xModifiableIdleTime > 0 )
+			{
+				__asm volatile( "dsb" );
+				__asm volatile( "wfi" );
+				__asm volatile( "isb" );
+			}
+			configPOST_SLEEP_PROCESSING( xExpectedIdleTime );
+
+			/* Stop SysTick.  Again, the time the SysTick is stopped for is
+			accounted for as best it can be, but using the tickless mode will
+			inevitably result in some tiny drift of the time maintained by the
+			kernel with respect to calendar time. */
+			ulSysTickCTRL = portNVIC_SYSTICK_CTRL_REG;
+			portNVIC_SYSTICK_CTRL_REG = ( ulSysTickCTRL & ~portNVIC_SYSTICK_ENABLE_BIT );
+
+			/* Re-enable interrupts - see comments above the cpsid instruction()
+			above. */
+			__asm volatile( "cpsie i" );
+
+			if( ( ulSysTickCTRL & portNVIC_SYSTICK_COUNT_FLAG_BIT ) != 0 )
+			{
+				uint32_t ulCalculatedLoadValue;
+
+				/* The tick interrupt has already executed, and the SysTick
+				count reloaded with ulReloadValue.  Reset the
+				portNVIC_SYSTICK_LOAD_REG with whatever remains of this tick
+				period. */
+				ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL ) - ( ulReloadValue - portNVIC_SYSTICK_CURRENT_VALUE_REG );
+
+				/* Don't allow a tiny value, or values that have somehow
+				underflowed because the post sleep hook did something
+				that took too long. */
+				if( ( ulCalculatedLoadValue < ulStoppedTimerCompensation ) || ( ulCalculatedLoadValue > ulTimerCountsForOneTick ) )
+				{
+					ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL );
+				}
+
+				portNVIC_SYSTICK_LOAD_REG = ulCalculatedLoadValue;
+
+				/* The tick interrupt handler will already have pended the tick
+				processing in the kernel.  As the pending tick will be
+				processed as soon as this function exits, the tick value
+				maintained by the tick is stepped forward by one less than the
+				time spent waiting. */
+				ulCompleteTickPeriods = xExpectedIdleTime - 1UL;
+			}
+			else
+			{
+				/* Something other than the tick interrupt ended the sleep.
+				Work out how long the sleep lasted rounded to complete tick
+				periods (not the ulReload value which accounted for part
+				ticks). */
+				ulCompletedSysTickDecrements = ( xExpectedIdleTime * ulTimerCountsForOneTick ) - portNVIC_SYSTICK_CURRENT_VALUE_REG;
+
+				/* How many complete tick periods passed while the processor
+				was waiting? */
+				ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick;
+
+				/* The reload value is set to whatever fraction of a single tick
+				period remains. */
+				portNVIC_SYSTICK_LOAD_REG = ( ( ulCompleteTickPeriods + 1 ) * ulTimerCountsForOneTick ) - ulCompletedSysTickDecrements;
+			}
+
+			/* Restart SysTick so it runs from portNVIC_SYSTICK_LOAD_REG
+			again, then set portNVIC_SYSTICK_LOAD_REG back to its standard
+			value.  The critical section is used to ensure the tick interrupt
+			can only execute once in the case that the reload register is near
+			zero. */
+			portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
+			portENTER_CRITICAL();
+			{
+				portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
+				vTaskStepTick( ulCompleteTickPeriods );
+				portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
+			}
+			portEXIT_CRITICAL();
+		}
+	}
+
+#endif /* #if configUSE_TICKLESS_IDLE */
+/*-----------------------------------------------------------*/
+
+/*
+ * Setup the systick timer to generate the tick interrupts at the required
+ * frequency.
+ */
+__attribute__(( weak )) void vPortSetupTimerInterrupt( void )
+{
+	/* Calculate the constants required to configure the tick interrupt. */
+	#if configUSE_TICKLESS_IDLE == 1
+	{
+		ulTimerCountsForOneTick = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ );
+		xMaximumPossibleSuppressedTicks = portMAX_24_BIT_NUMBER / ulTimerCountsForOneTick;
+		ulStoppedTimerCompensation = portMISSED_COUNTS_FACTOR / ( configCPU_CLOCK_HZ / configSYSTICK_CLOCK_HZ );
+	}
+	#endif /* configUSE_TICKLESS_IDLE */
+
+	/* Configure SysTick to interrupt at the requested rate. */
+	portNVIC_SYSTICK_LOAD_REG = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL;
+	portNVIC_SYSTICK_CTRL_REG = ( portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT );
+}
+/*-----------------------------------------------------------*/
+
+#if( configASSERT_DEFINED == 1 )
+
+	void vPortValidateInterruptPriority( void )
+	{
+	uint32_t ulCurrentInterrupt;
+	uint8_t ucCurrentPriority;
+
+		/* Obtain the number of the currently executing interrupt. */
+		__asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) );
+
+		/* Is the interrupt number a user defined interrupt? */
+		if( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER )
+		{
+			/* Look up the interrupt's priority. */
+			ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ];
+
+			/* The following assertion will fail if a service routine (ISR) for
+			an interrupt that has been assigned a priority above
+			configMAX_SYSCALL_INTERRUPT_PRIORITY calls an ISR safe FreeRTOS API
+			function.  ISR safe FreeRTOS API functions must *only* be called
+			from interrupts that have been assigned a priority at or below
+			configMAX_SYSCALL_INTERRUPT_PRIORITY.
+
+			Numerically low interrupt priority numbers represent logically high
+			interrupt priorities, therefore the priority of the interrupt must
+			be set to a value equal to or numerically *higher* than
+			configMAX_SYSCALL_INTERRUPT_PRIORITY.
+
+			Interrupts that	use the FreeRTOS API must not be left at their
+			default priority of	zero as that is the highest possible priority,
+			which is guaranteed to be above configMAX_SYSCALL_INTERRUPT_PRIORITY,
+			and	therefore also guaranteed to be invalid.
+
+			FreeRTOS maintains separate thread and ISR API functions to ensure
+			interrupt entry is as fast and simple as possible.
+
+			The following links provide detailed information:
+			http://www.freertos.org/RTOS-Cortex-M3-M4.html
+			http://www.freertos.org/FAQHelp.html */
+			configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
+		}
+
+		/* Priority grouping:  The interrupt controller (NVIC) allows the bits
+		that define each interrupt's priority to be split between bits that
+		define the interrupt's pre-emption priority bits and bits that define
+		the interrupt's sub-priority.  For simplicity all bits must be defined
+		to be pre-emption priority bits.  The following assertion will fail if
+		this is not the case (if some bits represent a sub-priority).
+
+		If the application only uses CMSIS libraries for interrupt
+		configuration then the correct setting can be achieved on all Cortex-M
+		devices by calling NVIC_SetPriorityGrouping( 0 ); before starting the
+		scheduler.  Note however that some vendor specific peripheral libraries
+		assume a non-zero priority group setting, in which cases using a value
+		of zero will result in unpredicable behaviour. */
+		configASSERT( ( portAIRCR_REG & portPRIORITY_GROUP_MASK ) <= ulMaxPRIGROUPValue );
+	}
+
+#endif /* configASSERT_DEFINED */
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM3/portmacro.h b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM3/portmacro.h
new file mode 100644
index 0000000000000000000000000000000000000000..a8ebb722cf75be9d84813a81d5c9e1fe239d8a36
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM3/portmacro.h
@@ -0,0 +1,203 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+#ifndef PORTMACRO_H
+#define PORTMACRO_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*-----------------------------------------------------------
+ * Port specific definitions.
+ *
+ * The settings in this file configure FreeRTOS correctly for the
+ * given hardware and compiler.
+ *
+ * These settings should not be altered.
+ *-----------------------------------------------------------
+ */
+
+/* Type definitions. */
+#define portCHAR		char
+#define portFLOAT		float
+#define portDOUBLE		double
+#define portLONG		long
+#define portSHORT		short
+#define portSTACK_TYPE	uint32_t
+#define portBASE_TYPE	long
+
+typedef portSTACK_TYPE StackType_t;
+typedef long BaseType_t;
+typedef unsigned long UBaseType_t;
+
+#if( configUSE_16_BIT_TICKS == 1 )
+	typedef uint16_t TickType_t;
+	#define portMAX_DELAY ( TickType_t ) 0xffff
+#else
+	typedef uint32_t TickType_t;
+	#define portMAX_DELAY ( TickType_t ) 0xffffffffUL
+
+	/* 32-bit tick type on a 32-bit architecture, so reads of the tick count do
+	not need to be guarded with a critical section. */
+	#define portTICK_TYPE_IS_ATOMIC 1
+#endif
+/*-----------------------------------------------------------*/
+
+/* Architecture specifics. */
+#define portSTACK_GROWTH			( -1 )
+#define portTICK_PERIOD_MS			( ( TickType_t ) 1000 / configTICK_RATE_HZ )
+#define portBYTE_ALIGNMENT			8
+/*-----------------------------------------------------------*/
+
+
+/* Scheduler utilities. */
+extern void vPortYield( void );
+#define portNVIC_INT_CTRL_REG		( * ( ( volatile uint32_t * ) 0xe000ed04 ) )
+#define portNVIC_PENDSVSET_BIT		( 1UL << 28UL )
+#define portYIELD()					vPortYield()
+#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT
+#define portYIELD_FROM_ISR( x ) portEND_SWITCHING_ISR( x )
+/*-----------------------------------------------------------*/
+
+/* Critical section management. */
+extern void vPortEnterCritical( void );
+extern void vPortExitCritical( void );
+extern uint32_t ulPortSetInterruptMask( void );
+extern void vPortClearInterruptMask( uint32_t ulNewMaskValue );
+#define portSET_INTERRUPT_MASK_FROM_ISR()		ulPortSetInterruptMask()
+#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x)	vPortClearInterruptMask(x)
+#define portDISABLE_INTERRUPTS()				ulPortSetInterruptMask()
+#define portENABLE_INTERRUPTS()					vPortClearInterruptMask(0)
+#define portENTER_CRITICAL()					vPortEnterCritical()
+#define portEXIT_CRITICAL()						vPortExitCritical()
+/*-----------------------------------------------------------*/
+
+/* Task function macros as described on the FreeRTOS.org WEB site.  These are
+not necessary for to use this port.  They are defined so the common demo files
+(which build with all the ports) will build. */
+#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters )
+#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters )
+/*-----------------------------------------------------------*/
+
+/* Tickless idle/low power functionality. */
+#ifndef portSUPPRESS_TICKS_AND_SLEEP
+	extern void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime );
+	#define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) vPortSuppressTicksAndSleep( xExpectedIdleTime )
+#endif
+/*-----------------------------------------------------------*/
+
+/* Architecture specific optimisations. */
+#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION
+	#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
+#endif
+
+#if configUSE_PORT_OPTIMISED_TASK_SELECTION == 1
+
+	/* Generic helper function. */
+	__attribute__( ( always_inline ) ) static inline uint8_t ucPortCountLeadingZeros( uint32_t ulBitmap )
+	{
+	uint8_t ucReturn;
+
+		__asm volatile ( "clz %0, %1" : "=r" ( ucReturn ) : "r" ( ulBitmap ) );
+		return ucReturn;
+	}
+
+	/* Check the configuration. */
+	#if( configMAX_PRIORITIES > 32 )
+		#error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32.  It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice.
+	#endif
+
+	/* Store/clear the ready priorities in a bit map. */
+	#define portRECORD_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) |= ( 1UL << ( uxPriority ) )
+	#define portRESET_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) &= ~( 1UL << ( uxPriority ) )
+
+	/*-----------------------------------------------------------*/
+
+	#define portGET_HIGHEST_PRIORITY( uxTopPriority, uxReadyPriorities ) uxTopPriority = ( 31 - ucPortCountLeadingZeros( ( uxReadyPriorities ) ) )
+
+#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */
+
+/*-----------------------------------------------------------*/
+
+#ifdef configASSERT
+	void vPortValidateInterruptPriority( void );
+	#define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() 	vPortValidateInterruptPriority()
+#endif
+
+/* portNOP() is not required by this port. */
+#define portNOP()
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PORTMACRO_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM4F/port.c b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM4F/port.c
new file mode 100644
index 0000000000000000000000000000000000000000..4732d98e0aff72db19564d09fc0fdeb93c57251e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM4F/port.c
@@ -0,0 +1,757 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/*-----------------------------------------------------------
+ * Implementation of functions defined in portable.h for the ARM CM4F port.
+ *----------------------------------------------------------*/
+
+/* Scheduler includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+
+#ifndef __VFP_FP__
+	#error This port can only be used when the project options are configured to enable hardware floating point support.
+#endif
+
+#ifndef configSYSTICK_CLOCK_HZ
+	#define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
+	/* Ensure the SysTick is clocked at the same frequency as the core. */
+	#define portNVIC_SYSTICK_CLK_BIT	( 1UL << 2UL )
+#else
+	/* The way the SysTick is clocked is not modified in case it is not the same
+	as the core. */
+	#define portNVIC_SYSTICK_CLK_BIT	( 0 )
+#endif
+
+/* Constants required to manipulate the core.  Registers first... */
+#define portNVIC_SYSTICK_CTRL_REG			( * ( ( volatile uint32_t * ) 0xe000e010 ) )
+#define portNVIC_SYSTICK_LOAD_REG			( * ( ( volatile uint32_t * ) 0xe000e014 ) )
+#define portNVIC_SYSTICK_CURRENT_VALUE_REG	( * ( ( volatile uint32_t * ) 0xe000e018 ) )
+#define portNVIC_SYSPRI2_REG				( * ( ( volatile uint32_t * ) 0xe000ed20 ) )
+/* ...then bits in the registers. */
+#define portNVIC_SYSTICK_INT_BIT			( 1UL << 1UL )
+#define portNVIC_SYSTICK_ENABLE_BIT			( 1UL << 0UL )
+#define portNVIC_SYSTICK_COUNT_FLAG_BIT		( 1UL << 16UL )
+#define portNVIC_PENDSVCLEAR_BIT 			( 1UL << 27UL )
+#define portNVIC_PEND_SYSTICK_CLEAR_BIT		( 1UL << 25UL )
+
+/* Constants used to detect a Cortex-M7 r0p1 core, which should use the ARM_CM7
+r0p1 port. */
+#define portCPUID							( * ( ( volatile uint32_t * ) 0xE000ed00 ) )
+#define portCORTEX_M7_r0p1_ID				( 0x410FC271UL )
+#define portCORTEX_M7_r0p0_ID				( 0x410FC270UL )
+
+#define portNVIC_PENDSV_PRI					( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )
+#define portNVIC_SYSTICK_PRI				( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )
+
+/* Constants required to check the validity of an interrupt priority. */
+#define portFIRST_USER_INTERRUPT_NUMBER		( 16 )
+#define portNVIC_IP_REGISTERS_OFFSET_16 	( 0xE000E3F0 )
+#define portAIRCR_REG						( * ( ( volatile uint32_t * ) 0xE000ED0C ) )
+#define portMAX_8_BIT_VALUE					( ( uint8_t ) 0xff )
+#define portTOP_BIT_OF_BYTE					( ( uint8_t ) 0x80 )
+#define portMAX_PRIGROUP_BITS				( ( uint8_t ) 7 )
+#define portPRIORITY_GROUP_MASK				( 0x07UL << 8UL )
+#define portPRIGROUP_SHIFT					( 8UL )
+
+/* Masks off all bits but the VECTACTIVE bits in the ICSR register. */
+#define portVECTACTIVE_MASK					( 0xFFUL )
+
+/* Constants required to manipulate the VFP. */
+#define portFPCCR							( ( volatile uint32_t * ) 0xe000ef34 ) /* Floating point context control register. */
+#define portASPEN_AND_LSPEN_BITS			( 0x3UL << 30UL )
+
+/* Constants required to set up the initial stack. */
+#define portINITIAL_XPSR					( 0x01000000 )
+#define portINITIAL_EXEC_RETURN				( 0xfffffffd )
+
+/* The systick is a 24-bit counter. */
+#define portMAX_24_BIT_NUMBER				( 0xffffffUL )
+
+/* A fiddle factor to estimate the number of SysTick counts that would have
+occurred while the SysTick counter is stopped during tickless idle
+calculations. */
+#define portMISSED_COUNTS_FACTOR			( 45UL )
+
+/* Let the user override the pre-loading of the initial LR with the address of
+prvTaskExitError() in case it messes up unwinding of the stack in the
+debugger. */
+#ifdef configTASK_RETURN_ADDRESS
+	#define portTASK_RETURN_ADDRESS	configTASK_RETURN_ADDRESS
+#else
+	#define portTASK_RETURN_ADDRESS	prvTaskExitError
+#endif
+
+/* Each task maintains its own interrupt status in the critical nesting
+variable. */
+static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
+
+/*
+ * Setup the timer to generate the tick interrupts.  The implementation in this
+ * file is weak to allow application writers to change the timer used to
+ * generate the tick interrupt.
+ */
+void vPortSetupTimerInterrupt( void );
+
+/*
+ * Exception handlers.
+ */
+void xPortPendSVHandler( void ) __attribute__ (( naked ));
+void xPortSysTickHandler( void );
+void vPortSVCHandler( void ) __attribute__ (( naked ));
+
+/*
+ * Start first task is a separate function so it can be tested in isolation.
+ */
+static void prvPortStartFirstTask( void ) __attribute__ (( naked ));
+
+/*
+ * Function to enable the VFP.
+ */
+ static void vPortEnableVFP( void ) __attribute__ (( naked ));
+
+/*
+ * Used to catch tasks that attempt to return from their implementing function.
+ */
+static void prvTaskExitError( void );
+
+/*-----------------------------------------------------------*/
+
+/*
+ * The number of SysTick increments that make up one tick period.
+ */
+#if configUSE_TICKLESS_IDLE == 1
+	static uint32_t ulTimerCountsForOneTick = 0;
+#endif /* configUSE_TICKLESS_IDLE */
+
+/*
+ * The maximum number of tick periods that can be suppressed is limited by the
+ * 24 bit resolution of the SysTick timer.
+ */
+#if configUSE_TICKLESS_IDLE == 1
+	static uint32_t xMaximumPossibleSuppressedTicks = 0;
+#endif /* configUSE_TICKLESS_IDLE */
+
+/*
+ * Compensate for the CPU cycles that pass while the SysTick is stopped (low
+ * power functionality only.
+ */
+#if configUSE_TICKLESS_IDLE == 1
+	static uint32_t ulStoppedTimerCompensation = 0;
+#endif /* configUSE_TICKLESS_IDLE */
+
+/*
+ * Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure
+ * FreeRTOS API functions are not called from interrupts that have been assigned
+ * a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
+ */
+#if ( configASSERT_DEFINED == 1 )
+	 static uint8_t ucMaxSysCallPriority = 0;
+	 static uint32_t ulMaxPRIGROUPValue = 0;
+	 static const volatile uint8_t * const pcInterruptPriorityRegisters = ( const volatile uint8_t * const ) portNVIC_IP_REGISTERS_OFFSET_16;
+#endif /* configASSERT_DEFINED */
+
+/*-----------------------------------------------------------*/
+
+/*
+ * See header file for description.
+ */
+StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
+{
+	/* Simulate the stack frame as it would be created by a context switch
+	interrupt. */
+
+	/* Offset added to account for the way the MCU uses the stack on entry/exit
+	of interrupts, and to ensure alignment. */
+	pxTopOfStack--;
+
+	*pxTopOfStack = portINITIAL_XPSR;	/* xPSR */
+	pxTopOfStack--;
+	*pxTopOfStack = ( StackType_t ) pxCode;	/* PC */
+	pxTopOfStack--;
+	*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS;	/* LR */
+
+	/* Save code space by skipping register initialisation. */
+	pxTopOfStack -= 5;	/* R12, R3, R2 and R1. */
+	*pxTopOfStack = ( StackType_t ) pvParameters;	/* R0 */
+
+	/* A save method is being used that requires each task to maintain its
+	own exec return value. */
+	pxTopOfStack--;
+	*pxTopOfStack = portINITIAL_EXEC_RETURN;
+
+	pxTopOfStack -= 8;	/* R11, R10, R9, R8, R7, R6, R5 and R4. */
+
+	return pxTopOfStack;
+}
+/*-----------------------------------------------------------*/
+
+static void prvTaskExitError( void )
+{
+	/* A function that implements a task must not exit or attempt to return to
+	its caller as there is nothing to return to.  If a task wants to exit it
+	should instead call vTaskDelete( NULL ).
+
+	Artificially force an assert() to be triggered if configASSERT() is
+	defined, then stop here so application writers can catch the error. */
+	configASSERT( uxCriticalNesting == ~0UL );
+	portDISABLE_INTERRUPTS();
+	for( ;; );
+}
+/*-----------------------------------------------------------*/
+
+void vPortSVCHandler( void )
+{
+	__asm volatile (
+					"	ldr	r3, pxCurrentTCBConst2		\n" /* Restore the context. */
+					"	ldr r1, [r3]					\n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */
+					"	ldr r0, [r1]					\n" /* The first item in pxCurrentTCB is the task top of stack. */
+					"	ldmia r0!, {r4-r11, r14}		\n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */
+					"	msr psp, r0						\n" /* Restore the task stack pointer. */
+					"	isb								\n"
+					"	mov r0, #0 						\n"
+					"	msr	basepri, r0					\n"
+					"	bx r14							\n"
+					"									\n"
+					"	.align 2						\n"
+					"pxCurrentTCBConst2: .word pxCurrentTCB				\n"
+				);
+}
+/*-----------------------------------------------------------*/
+
+static void prvPortStartFirstTask( void )
+{
+	__asm volatile(
+					" ldr r0, =0xE000ED08 	\n" /* Use the NVIC offset register to locate the stack. */
+					" ldr r0, [r0] 			\n"
+					" ldr r0, [r0] 			\n"
+					" msr msp, r0			\n" /* Set the msp back to the start of the stack. */
+					" cpsie i				\n" /* Globally enable interrupts. */
+					" cpsie f				\n"
+					" dsb					\n"
+					" isb					\n"
+					" svc 0					\n" /* System call to start first task. */
+					" nop					\n"
+				);
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * See header file for description.
+ */
+BaseType_t xPortStartScheduler( void )
+{
+	/* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0.
+	See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */
+	configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY );
+
+	/* This port can be used on all revisions of the Cortex-M7 core other than
+	the r0p1 parts.  r0p1 parts should use the port from the
+	/source/portable/GCC/ARM_CM7/r0p1 directory. */
+	configASSERT( portCPUID != portCORTEX_M7_r0p1_ID );
+	configASSERT( portCPUID != portCORTEX_M7_r0p0_ID );
+
+	#if( configASSERT_DEFINED == 1 )
+	{
+		volatile uint32_t ulOriginalPriority;
+		volatile uint8_t * const pucFirstUserPriorityRegister = ( volatile uint8_t * const ) ( portNVIC_IP_REGISTERS_OFFSET_16 + portFIRST_USER_INTERRUPT_NUMBER );
+		volatile uint8_t ucMaxPriorityValue;
+
+		/* Determine the maximum priority from which ISR safe FreeRTOS API
+		functions can be called.  ISR safe functions are those that end in
+		"FromISR".  FreeRTOS maintains separate thread and ISR API functions to
+		ensure interrupt entry is as fast and simple as possible.
+
+		Save the interrupt priority value that is about to be clobbered. */
+		ulOriginalPriority = *pucFirstUserPriorityRegister;
+
+		/* Determine the number of priority bits available.  First write to all
+		possible bits. */
+		*pucFirstUserPriorityRegister = portMAX_8_BIT_VALUE;
+
+		/* Read the value back to see how many bits stuck. */
+		ucMaxPriorityValue = *pucFirstUserPriorityRegister;
+
+		/* Use the same mask on the maximum system call priority. */
+		ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
+
+		/* Calculate the maximum acceptable priority group value for the number
+		of bits read back. */
+		ulMaxPRIGROUPValue = portMAX_PRIGROUP_BITS;
+		while( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE )
+		{
+			ulMaxPRIGROUPValue--;
+			ucMaxPriorityValue <<= ( uint8_t ) 0x01;
+		}
+
+		/* Shift the priority group value back to its position within the AIRCR
+		register. */
+		ulMaxPRIGROUPValue <<= portPRIGROUP_SHIFT;
+		ulMaxPRIGROUPValue &= portPRIORITY_GROUP_MASK;
+
+		/* Restore the clobbered interrupt priority register to its original
+		value. */
+		*pucFirstUserPriorityRegister = ulOriginalPriority;
+	}
+	#endif /* conifgASSERT_DEFINED */
+
+	/* Make PendSV and SysTick the lowest priority interrupts. */
+	portNVIC_SYSPRI2_REG |= portNVIC_PENDSV_PRI;
+	portNVIC_SYSPRI2_REG |= portNVIC_SYSTICK_PRI;
+
+	/* Start the timer that generates the tick ISR.  Interrupts are disabled
+	here already. */
+	vPortSetupTimerInterrupt();
+
+	/* Initialise the critical nesting count ready for the first task. */
+	uxCriticalNesting = 0;
+
+	/* Ensure the VFP is enabled - it should be anyway. */
+	vPortEnableVFP();
+
+	/* Lazy save always. */
+	*( portFPCCR ) |= portASPEN_AND_LSPEN_BITS;
+
+	/* Start the first task. */
+	prvPortStartFirstTask();
+
+	/* Should never get here as the tasks will now be executing!  Call the task
+	exit error function to prevent compiler warnings about a static function
+	not being called in the case that the application writer overrides this
+	functionality by defining configTASK_RETURN_ADDRESS. */
+	prvTaskExitError();
+
+	/* Should not get here! */
+	return 0;
+}
+/*-----------------------------------------------------------*/
+
+void vPortEndScheduler( void )
+{
+	/* Not implemented in ports where there is nothing to return to.
+	Artificially force an assert. */
+	configASSERT( uxCriticalNesting == 1000UL );
+}
+/*-----------------------------------------------------------*/
+
+void vPortEnterCritical( void )
+{
+	portDISABLE_INTERRUPTS();
+	uxCriticalNesting++;
+
+	/* This is not the interrupt safe version of the enter critical function so
+	assert() if it is being called from an interrupt context.  Only API
+	functions that end in "FromISR" can be used in an interrupt.  Only assert if
+	the critical nesting count is 1 to protect against recursive calls if the
+	assert function also uses a critical section. */
+	if( uxCriticalNesting == 1 )
+	{
+		configASSERT( ( portNVIC_INT_CTRL_REG & portVECTACTIVE_MASK ) == 0 );
+	}
+}
+/*-----------------------------------------------------------*/
+
+void vPortExitCritical( void )
+{
+	configASSERT( uxCriticalNesting );
+	uxCriticalNesting--;
+	if( uxCriticalNesting == 0 )
+	{
+		portENABLE_INTERRUPTS();
+	}
+}
+/*-----------------------------------------------------------*/
+
+void xPortPendSVHandler( void )
+{
+	/* This is a naked function. */
+
+	__asm volatile
+	(
+	"	mrs r0, psp							\n"
+	"	isb									\n"
+	"										\n"
+	"	ldr	r3, pxCurrentTCBConst			\n" /* Get the location of the current TCB. */
+	"	ldr	r2, [r3]						\n"
+	"										\n"
+	"	tst r14, #0x10						\n" /* Is the task using the FPU context?  If so, push high vfp registers. */
+	"	it eq								\n"
+	"	vstmdbeq r0!, {s16-s31}				\n"
+	"										\n"
+	"	stmdb r0!, {r4-r11, r14}			\n" /* Save the core registers. */
+	"										\n"
+	"	str r0, [r2]						\n" /* Save the new top of stack into the first member of the TCB. */
+	"										\n"
+	"	stmdb sp!, {r3}						\n"
+	"	mov r0, %0 							\n"
+	"	msr basepri, r0						\n"
+	"	dsb									\n"
+	"   isb									\n"
+	"	bl vTaskSwitchContext				\n"
+	"	mov r0, #0							\n"
+	"	msr basepri, r0						\n"
+	"	ldmia sp!, {r3}						\n"
+	"										\n"
+	"	ldr r1, [r3]						\n" /* The first item in pxCurrentTCB is the task top of stack. */
+	"	ldr r0, [r1]						\n"
+	"										\n"
+	"	ldmia r0!, {r4-r11, r14}			\n" /* Pop the core registers. */
+	"										\n"
+	"	tst r14, #0x10						\n" /* Is the task using the FPU context?  If so, pop the high vfp registers too. */
+	"	it eq								\n"
+	"	vldmiaeq r0!, {s16-s31}				\n"
+	"										\n"
+	"	msr psp, r0							\n"
+	"	isb									\n"
+	"										\n"
+	#ifdef WORKAROUND_PMU_CM001 /* XMC4000 specific errata workaround. */
+		#if WORKAROUND_PMU_CM001 == 1
+	"			push { r14 }				\n"
+	"			pop { pc }					\n"
+		#endif
+	#endif
+	"										\n"
+	"	bx r14								\n"
+	"										\n"
+	"	.align 2							\n"
+	"pxCurrentTCBConst: .word pxCurrentTCB	\n"
+	::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY)
+	);
+}
+/*-----------------------------------------------------------*/
+
+void xPortSysTickHandler( void )
+{
+	/* The SysTick runs at the lowest interrupt priority, so when this interrupt
+	executes all interrupts must be unmasked.  There is therefore no need to
+	save and then restore the interrupt mask value as its value is already
+	known. */
+	( void ) portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		/* Increment the RTOS tick. */
+		if( xTaskIncrementTick() != pdFALSE )
+		{
+			/* A context switch is required.  Context switching is performed in
+			the PendSV interrupt.  Pend the PendSV interrupt. */
+			portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
+		}
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( 0 );
+}
+/*-----------------------------------------------------------*/
+
+#if configUSE_TICKLESS_IDLE == 1
+
+	__attribute__((weak)) void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime )
+	{
+	uint32_t ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements, ulSysTickCTRL;
+	TickType_t xModifiableIdleTime;
+
+		/* Make sure the SysTick reload value does not overflow the counter. */
+		if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )
+		{
+			xExpectedIdleTime = xMaximumPossibleSuppressedTicks;
+		}
+
+		/* Stop the SysTick momentarily.  The time the SysTick is stopped for
+		is accounted for as best it can be, but using the tickless mode will
+		inevitably result in some tiny drift of the time maintained by the
+		kernel with respect to calendar time. */
+		portNVIC_SYSTICK_CTRL_REG &= ~portNVIC_SYSTICK_ENABLE_BIT;
+
+		/* Calculate the reload value required to wait xExpectedIdleTime
+		tick periods.  -1 is used because this code will execute part way
+		through one of the tick periods. */
+		ulReloadValue = portNVIC_SYSTICK_CURRENT_VALUE_REG + ( ulTimerCountsForOneTick * ( xExpectedIdleTime - 1UL ) );
+		if( ulReloadValue > ulStoppedTimerCompensation )
+		{
+			ulReloadValue -= ulStoppedTimerCompensation;
+		}
+
+		/* Enter a critical section but don't use the taskENTER_CRITICAL()
+		method as that will mask interrupts that should exit sleep mode. */
+		__asm volatile( "cpsid i" );
+
+		/* If a context switch is pending or a task is waiting for the scheduler
+		to be unsuspended then abandon the low power entry. */
+		if( eTaskConfirmSleepModeStatus() == eAbortSleep )
+		{
+			/* Restart from whatever is left in the count register to complete
+			this tick period. */
+			portNVIC_SYSTICK_LOAD_REG = portNVIC_SYSTICK_CURRENT_VALUE_REG;
+
+			/* Restart SysTick. */
+			portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
+
+			/* Reset the reload register to the value required for normal tick
+			periods. */
+			portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
+
+			/* Re-enable interrupts - see comments above the cpsid instruction()
+			above. */
+			__asm volatile( "cpsie i" );
+		}
+		else
+		{
+			/* Set the new reload value. */
+			portNVIC_SYSTICK_LOAD_REG = ulReloadValue;
+
+			/* Clear the SysTick count flag and set the count value back to
+			zero. */
+			portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
+
+			/* Restart SysTick. */
+			portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
+
+			/* Sleep until something happens.  configPRE_SLEEP_PROCESSING() can
+			set its parameter to 0 to indicate that its implementation contains
+			its own wait for interrupt or wait for event instruction, and so wfi
+			should not be executed again.  However, the original expected idle
+			time variable must remain unmodified, so a copy is taken. */
+			xModifiableIdleTime = xExpectedIdleTime;
+			configPRE_SLEEP_PROCESSING( xModifiableIdleTime );
+			if( xModifiableIdleTime > 0 )
+			{
+				__asm volatile( "dsb" );
+				__asm volatile( "wfi" );
+				__asm volatile( "isb" );
+			}
+			configPOST_SLEEP_PROCESSING( xExpectedIdleTime );
+
+			/* Stop SysTick.  Again, the time the SysTick is stopped for is
+			accounted for as best it can be, but using the tickless mode will
+			inevitably result in some tiny drift of the time maintained by the
+			kernel with respect to calendar time. */
+			ulSysTickCTRL = portNVIC_SYSTICK_CTRL_REG;
+			portNVIC_SYSTICK_CTRL_REG = ( ulSysTickCTRL & ~portNVIC_SYSTICK_ENABLE_BIT );
+
+			/* Re-enable interrupts - see comments above the cpsid instruction()
+			above. */
+			__asm volatile( "cpsie i" );
+
+			if( ( ulSysTickCTRL & portNVIC_SYSTICK_COUNT_FLAG_BIT ) != 0 )
+			{
+				uint32_t ulCalculatedLoadValue;
+
+				/* The tick interrupt has already executed, and the SysTick
+				count reloaded with ulReloadValue.  Reset the
+				portNVIC_SYSTICK_LOAD_REG with whatever remains of this tick
+				period. */
+				ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL ) - ( ulReloadValue - portNVIC_SYSTICK_CURRENT_VALUE_REG );
+
+				/* Don't allow a tiny value, or values that have somehow
+				underflowed because the post sleep hook did something
+				that took too long. */
+				if( ( ulCalculatedLoadValue < ulStoppedTimerCompensation ) || ( ulCalculatedLoadValue > ulTimerCountsForOneTick ) )
+				{
+					ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL );
+				}
+
+				portNVIC_SYSTICK_LOAD_REG = ulCalculatedLoadValue;
+
+				/* The tick interrupt handler will already have pended the tick
+				processing in the kernel.  As the pending tick will be
+				processed as soon as this function exits, the tick value
+				maintained by the tick is stepped forward by one less than the
+				time spent waiting. */
+				ulCompleteTickPeriods = xExpectedIdleTime - 1UL;
+			}
+			else
+			{
+				/* Something other than the tick interrupt ended the sleep.
+				Work out how long the sleep lasted rounded to complete tick
+				periods (not the ulReload value which accounted for part
+				ticks). */
+				ulCompletedSysTickDecrements = ( xExpectedIdleTime * ulTimerCountsForOneTick ) - portNVIC_SYSTICK_CURRENT_VALUE_REG;
+
+				/* How many complete tick periods passed while the processor
+				was waiting? */
+				ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick;
+
+				/* The reload value is set to whatever fraction of a single tick
+				period remains. */
+				portNVIC_SYSTICK_LOAD_REG = ( ( ulCompleteTickPeriods + 1 ) * ulTimerCountsForOneTick ) - ulCompletedSysTickDecrements;
+			}
+
+			/* Restart SysTick so it runs from portNVIC_SYSTICK_LOAD_REG
+			again, then set portNVIC_SYSTICK_LOAD_REG back to its standard
+			value.  The critical section is used to ensure the tick interrupt
+			can only execute once in the case that the reload register is near
+			zero. */
+			portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
+			portENTER_CRITICAL();
+			{
+				portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
+				vTaskStepTick( ulCompleteTickPeriods );
+				portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
+			}
+			portEXIT_CRITICAL();
+		}
+	}
+
+#endif /* #if configUSE_TICKLESS_IDLE */
+/*-----------------------------------------------------------*/
+
+/*
+ * Setup the systick timer to generate the tick interrupts at the required
+ * frequency.
+ */
+__attribute__(( weak )) void vPortSetupTimerInterrupt( void )
+{
+	/* Calculate the constants required to configure the tick interrupt. */
+	#if configUSE_TICKLESS_IDLE == 1
+	{
+		ulTimerCountsForOneTick = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ );
+		xMaximumPossibleSuppressedTicks = portMAX_24_BIT_NUMBER / ulTimerCountsForOneTick;
+		ulStoppedTimerCompensation = portMISSED_COUNTS_FACTOR / ( configCPU_CLOCK_HZ / configSYSTICK_CLOCK_HZ );
+	}
+	#endif /* configUSE_TICKLESS_IDLE */
+
+	/* Configure SysTick to interrupt at the requested rate. */
+	portNVIC_SYSTICK_LOAD_REG = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL;
+	portNVIC_SYSTICK_CTRL_REG = ( portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT );
+}
+/*-----------------------------------------------------------*/
+
+/* This is a naked function. */
+static void vPortEnableVFP( void )
+{
+	__asm volatile
+	(
+		"	ldr.w r0, =0xE000ED88		\n" /* The FPU enable bits are in the CPACR. */
+		"	ldr r1, [r0]				\n"
+		"								\n"
+		"	orr r1, r1, #( 0xf << 20 )	\n" /* Enable CP10 and CP11 coprocessors, then save back. */
+		"	str r1, [r0]				\n"
+		"	bx r14						"
+	);
+}
+/*-----------------------------------------------------------*/
+
+#if( configASSERT_DEFINED == 1 )
+
+	void vPortValidateInterruptPriority( void )
+	{
+	uint32_t ulCurrentInterrupt;
+	uint8_t ucCurrentPriority;
+
+		/* Obtain the number of the currently executing interrupt. */
+		__asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) );
+
+		/* Is the interrupt number a user defined interrupt? */
+		if( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER )
+		{
+			/* Look up the interrupt's priority. */
+			ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ];
+
+			/* The following assertion will fail if a service routine (ISR) for
+			an interrupt that has been assigned a priority above
+			configMAX_SYSCALL_INTERRUPT_PRIORITY calls an ISR safe FreeRTOS API
+			function.  ISR safe FreeRTOS API functions must *only* be called
+			from interrupts that have been assigned a priority at or below
+			configMAX_SYSCALL_INTERRUPT_PRIORITY.
+
+			Numerically low interrupt priority numbers represent logically high
+			interrupt priorities, therefore the priority of the interrupt must
+			be set to a value equal to or numerically *higher* than
+			configMAX_SYSCALL_INTERRUPT_PRIORITY.
+
+			Interrupts that	use the FreeRTOS API must not be left at their
+			default priority of	zero as that is the highest possible priority,
+			which is guaranteed to be above configMAX_SYSCALL_INTERRUPT_PRIORITY,
+			and	therefore also guaranteed to be invalid.
+
+			FreeRTOS maintains separate thread and ISR API functions to ensure
+			interrupt entry is as fast and simple as possible.
+
+			The following links provide detailed information:
+			http://www.freertos.org/RTOS-Cortex-M3-M4.html
+			http://www.freertos.org/FAQHelp.html */
+			configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
+		}
+
+		/* Priority grouping:  The interrupt controller (NVIC) allows the bits
+		that define each interrupt's priority to be split between bits that
+		define the interrupt's pre-emption priority bits and bits that define
+		the interrupt's sub-priority.  For simplicity all bits must be defined
+		to be pre-emption priority bits.  The following assertion will fail if
+		this is not the case (if some bits represent a sub-priority).
+
+		If the application only uses CMSIS libraries for interrupt
+		configuration then the correct setting can be achieved on all Cortex-M
+		devices by calling NVIC_SetPriorityGrouping( 0 ); before starting the
+		scheduler.  Note however that some vendor specific peripheral libraries
+		assume a non-zero priority group setting, in which cases using a value
+		of zero will result in unpredicable behaviour. */
+		configASSERT( ( portAIRCR_REG & portPRIORITY_GROUP_MASK ) <= ulMaxPRIGROUPValue );
+	}
+
+#endif /* configASSERT_DEFINED */
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM4F/portmacro.h b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM4F/portmacro.h
new file mode 100644
index 0000000000000000000000000000000000000000..073e408abbe3a0f3c20ade07da7c02deeb876a3d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/GCC/ARM_CM4F/portmacro.h
@@ -0,0 +1,262 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+#ifndef PORTMACRO_H
+#define PORTMACRO_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*-----------------------------------------------------------
+ * Port specific definitions.
+ *
+ * The settings in this file configure FreeRTOS correctly for the
+ * given hardware and compiler.
+ *
+ * These settings should not be altered.
+ *-----------------------------------------------------------
+ */
+
+/* Type definitions. */
+#define portCHAR		char
+#define portFLOAT		float
+#define portDOUBLE		double
+#define portLONG		long
+#define portSHORT		short
+#define portSTACK_TYPE	uint32_t
+#define portBASE_TYPE	long
+
+typedef portSTACK_TYPE StackType_t;
+typedef long BaseType_t;
+typedef unsigned long UBaseType_t;
+
+#if( configUSE_16_BIT_TICKS == 1 )
+	typedef uint16_t TickType_t;
+	#define portMAX_DELAY ( TickType_t ) 0xffff
+#else
+	typedef uint32_t TickType_t;
+	#define portMAX_DELAY ( TickType_t ) 0xffffffffUL
+
+	/* 32-bit tick type on a 32-bit architecture, so reads of the tick count do
+	not need to be guarded with a critical section. */
+	#define portTICK_TYPE_IS_ATOMIC 1
+#endif
+/*-----------------------------------------------------------*/
+
+/* Architecture specifics. */
+#define portSTACK_GROWTH			( -1 )
+#define portTICK_PERIOD_MS			( ( TickType_t ) 1000 / configTICK_RATE_HZ )
+#define portBYTE_ALIGNMENT			8
+/*-----------------------------------------------------------*/
+
+/* Scheduler utilities. */
+#define portYIELD() 															\
+{																				\
+	/* Set a PendSV to request a context switch. */								\
+	portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;								\
+																				\
+	/* Barriers are normally not required but do ensure the code is completely	\
+	within the specified behaviour for the architecture. */						\
+	__asm volatile( "dsb" );													\
+	__asm volatile( "isb" );													\
+}
+
+#define portNVIC_INT_CTRL_REG		( * ( ( volatile uint32_t * ) 0xe000ed04 ) )
+#define portNVIC_PENDSVSET_BIT		( 1UL << 28UL )
+#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired != pdFALSE ) portYIELD()
+#define portYIELD_FROM_ISR( x ) portEND_SWITCHING_ISR( x )
+/*-----------------------------------------------------------*/
+
+/* Critical section management. */
+extern void vPortEnterCritical( void );
+extern void vPortExitCritical( void );
+#define portSET_INTERRUPT_MASK_FROM_ISR()		ulPortRaiseBASEPRI()
+#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x)	vPortSetBASEPRI(x)
+#define portDISABLE_INTERRUPTS()				vPortRaiseBASEPRI()
+#define portENABLE_INTERRUPTS()					vPortSetBASEPRI(0)
+#define portENTER_CRITICAL()					vPortEnterCritical()
+#define portEXIT_CRITICAL()						vPortExitCritical()
+
+/*-----------------------------------------------------------*/
+
+/* Task function macros as described on the FreeRTOS.org WEB site.  These are
+not necessary for to use this port.  They are defined so the common demo files
+(which build with all the ports) will build. */
+#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters )
+#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters )
+/*-----------------------------------------------------------*/
+
+/* Tickless idle/low power functionality. */
+#ifndef portSUPPRESS_TICKS_AND_SLEEP
+	extern void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime );
+	#define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) vPortSuppressTicksAndSleep( xExpectedIdleTime )
+#endif
+/*-----------------------------------------------------------*/
+
+/* Architecture specific optimisations. */
+#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION
+	#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
+#endif
+
+#if configUSE_PORT_OPTIMISED_TASK_SELECTION == 1
+
+	/* Generic helper function. */
+	__attribute__( ( always_inline ) ) static inline uint8_t ucPortCountLeadingZeros( uint32_t ulBitmap )
+	{
+	uint8_t ucReturn;
+
+		__asm volatile ( "clz %0, %1" : "=r" ( ucReturn ) : "r" ( ulBitmap ) );
+		return ucReturn;
+	}
+
+	/* Check the configuration. */
+	#if( configMAX_PRIORITIES > 32 )
+		#error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32.  It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice.
+	#endif
+
+	/* Store/clear the ready priorities in a bit map. */
+	#define portRECORD_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) |= ( 1UL << ( uxPriority ) )
+	#define portRESET_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) &= ~( 1UL << ( uxPriority ) )
+
+	/*-----------------------------------------------------------*/
+
+	#define portGET_HIGHEST_PRIORITY( uxTopPriority, uxReadyPriorities ) uxTopPriority = ( 31 - ucPortCountLeadingZeros( ( uxReadyPriorities ) ) )
+
+#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */
+
+/*-----------------------------------------------------------*/
+
+#ifdef configASSERT
+	void vPortValidateInterruptPriority( void );
+	#define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() 	vPortValidateInterruptPriority()
+#endif
+
+/* portNOP() is not required by this port. */
+#define portNOP()
+
+#ifndef portFORCE_INLINE
+	#define portFORCE_INLINE inline __attribute__(( always_inline))
+#endif
+
+/*-----------------------------------------------------------*/
+
+portFORCE_INLINE static void vPortRaiseBASEPRI( void )
+{
+uint32_t ulNewBASEPRI;
+
+	__asm volatile
+	(
+		"	mov %0, %1												\n"	\
+		"	msr basepri, %0											\n" \
+		"	isb														\n" \
+		"	dsb														\n" \
+		:"=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY )
+	);
+}
+
+/*-----------------------------------------------------------*/
+
+portFORCE_INLINE static uint32_t ulPortRaiseBASEPRI( void )
+{
+uint32_t ulOriginalBASEPRI, ulNewBASEPRI;
+
+	__asm volatile
+	(
+		"	mrs %0, basepri											\n" \
+		"	mov %1, %2												\n"	\
+		"	msr basepri, %1											\n" \
+		"	isb														\n" \
+		"	dsb														\n" \
+		:"=r" (ulOriginalBASEPRI), "=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY )
+	);
+
+	/* This return will not be reached but is necessary to prevent compiler
+	warnings. */
+	return ulOriginalBASEPRI;
+}
+/*-----------------------------------------------------------*/
+
+portFORCE_INLINE static void vPortSetBASEPRI( uint32_t ulNewMaskValue )
+{
+	__asm volatile
+	(
+		"	msr basepri, %0	" :: "r" ( ulNewMaskValue )
+	);
+}
+/*-----------------------------------------------------------*/
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PORTMACRO_H */
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_1.c b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_1.c
new file mode 100644
index 0000000000000000000000000000000000000000..aeca28735c9913d0418a62cf69f9ae731a2294c9
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_1.c
@@ -0,0 +1,174 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+/*
+ * The simplest possible implementation of pvPortMalloc().  Note that this
+ * implementation does NOT allow allocated memory to be freed again.
+ *
+ * See heap_2.c, heap_3.c and heap_4.c for alternative implementations, and the
+ * memory management pages of http://www.FreeRTOS.org for more information.
+ */
+#include <stdlib.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+/* A few bytes might be lost to byte aligning the heap start address. */
+#define configADJUSTED_HEAP_SIZE	( configTOTAL_HEAP_SIZE - portBYTE_ALIGNMENT )
+
+/* Allocate the memory for the heap. */
+static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ];
+static size_t xNextFreeByte = ( size_t ) 0;
+
+/*-----------------------------------------------------------*/
+
+void *pvPortMalloc( size_t xWantedSize )
+{
+void *pvReturn = NULL;
+static uint8_t *pucAlignedHeap = NULL;
+
+	/* Ensure that blocks are always aligned to the required number of bytes. */
+	#if portBYTE_ALIGNMENT != 1
+		if( xWantedSize & portBYTE_ALIGNMENT_MASK )
+		{
+			/* Byte alignment required. */
+			xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) );
+		}
+	#endif
+
+	vTaskSuspendAll();
+	{
+		if( pucAlignedHeap == NULL )
+		{
+			/* Ensure the heap starts on a correctly aligned boundary. */
+			pucAlignedHeap = ( uint8_t * ) ( ( ( portPOINTER_SIZE_TYPE ) &ucHeap[ portBYTE_ALIGNMENT ] ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) );
+		}
+
+		/* Check there is enough room left for the allocation. */
+		if( ( ( xNextFreeByte + xWantedSize ) < configADJUSTED_HEAP_SIZE ) &&
+			( ( xNextFreeByte + xWantedSize ) > xNextFreeByte )	)/* Check for overflow. */
+		{
+			/* Return the next free byte then increment the index past this
+			block. */
+			pvReturn = pucAlignedHeap + xNextFreeByte;
+			xNextFreeByte += xWantedSize;
+		}
+
+		traceMALLOC( pvReturn, xWantedSize );
+	}
+	( void ) xTaskResumeAll();
+
+	#if( configUSE_MALLOC_FAILED_HOOK == 1 )
+	{
+		if( pvReturn == NULL )
+		{
+			extern void vApplicationMallocFailedHook( void );
+			vApplicationMallocFailedHook();
+		}
+	}
+	#endif
+
+	return pvReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vPortFree( void *pv )
+{
+	/* Memory cannot be freed using this scheme.  See heap_2.c, heap_3.c and
+	heap_4.c for alternative implementations, and the memory management pages of
+	http://www.FreeRTOS.org for more information. */
+	( void ) pv;
+
+	/* Force an assert as it is invalid to call this function. */
+	configASSERT( pv == NULL );
+}
+/*-----------------------------------------------------------*/
+
+void vPortInitialiseBlocks( void )
+{
+	/* Only required when static memory is not cleared. */
+	xNextFreeByte = ( size_t ) 0;
+}
+/*-----------------------------------------------------------*/
+
+size_t xPortGetFreeHeapSize( void )
+{
+	return ( configADJUSTED_HEAP_SIZE - xNextFreeByte );
+}
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_2.c b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_2.c
new file mode 100644
index 0000000000000000000000000000000000000000..2e7aa19c835be378f8c846e4c1f3f68ef87e3e53
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_2.c
@@ -0,0 +1,303 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/*
+ * A sample implementation of pvPortMalloc() and vPortFree() that permits
+ * allocated blocks to be freed, but does not combine adjacent free blocks
+ * into a single larger block (and so will fragment memory).  See heap_4.c for
+ * an equivalent that does combine adjacent blocks into single larger blocks.
+ *
+ * See heap_1.c, heap_3.c and heap_4.c for alternative implementations, and the
+ * memory management pages of http://www.FreeRTOS.org for more information.
+ */
+#include <stdlib.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+/* A few bytes might be lost to byte aligning the heap start address. */
+#define configADJUSTED_HEAP_SIZE	( configTOTAL_HEAP_SIZE - portBYTE_ALIGNMENT )
+
+/*
+ * Initialises the heap structures before their first use.
+ */
+static void prvHeapInit( void );
+
+/* Allocate the memory for the heap. */
+static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ];
+
+/* Define the linked list structure.  This is used to link free blocks in order
+of their size. */
+typedef struct A_BLOCK_LINK
+{
+	struct A_BLOCK_LINK *pxNextFreeBlock;	/*<< The next free block in the list. */
+	size_t xBlockSize;						/*<< The size of the free block. */
+} BlockLink_t;
+
+
+static const uint16_t heapSTRUCT_SIZE	= ( ( sizeof ( BlockLink_t ) + ( portBYTE_ALIGNMENT - 1 ) ) & ~portBYTE_ALIGNMENT_MASK );
+#define heapMINIMUM_BLOCK_SIZE	( ( size_t ) ( heapSTRUCT_SIZE * 2 ) )
+
+/* Create a couple of list links to mark the start and end of the list. */
+static BlockLink_t xStart, xEnd;
+
+/* Keeps track of the number of free bytes remaining, but says nothing about
+fragmentation. */
+static size_t xFreeBytesRemaining = configADJUSTED_HEAP_SIZE;
+
+/* STATIC FUNCTIONS ARE DEFINED AS MACROS TO MINIMIZE THE FUNCTION CALL DEPTH. */
+
+/*
+ * Insert a block into the list of free blocks - which is ordered by size of
+ * the block.  Small blocks at the start of the list and large blocks at the end
+ * of the list.
+ */
+#define prvInsertBlockIntoFreeList( pxBlockToInsert )								\
+{																					\
+BlockLink_t *pxIterator;																\
+size_t xBlockSize;																	\
+																					\
+	xBlockSize = pxBlockToInsert->xBlockSize;										\
+																					\
+	/* Iterate through the list until a block is found that has a larger size */	\
+	/* than the block we are inserting. */											\
+	for( pxIterator = &xStart; pxIterator->pxNextFreeBlock->xBlockSize < xBlockSize; pxIterator = pxIterator->pxNextFreeBlock )	\
+	{																				\
+		/* There is nothing to do here - just iterate to the correct position. */	\
+	}																				\
+																					\
+	/* Update the list to include the block being inserted in the correct */		\
+	/* position. */																	\
+	pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock;					\
+	pxIterator->pxNextFreeBlock = pxBlockToInsert;									\
+}
+/*-----------------------------------------------------------*/
+
+void *pvPortMalloc( size_t xWantedSize )
+{
+BlockLink_t *pxBlock, *pxPreviousBlock, *pxNewBlockLink;
+static BaseType_t xHeapHasBeenInitialised = pdFALSE;
+void *pvReturn = NULL;
+
+	vTaskSuspendAll();
+	{
+		/* If this is the first call to malloc then the heap will require
+		initialisation to setup the list of free blocks. */
+		if( xHeapHasBeenInitialised == pdFALSE )
+		{
+			prvHeapInit();
+			xHeapHasBeenInitialised = pdTRUE;
+		}
+
+		/* The wanted size is increased so it can contain a BlockLink_t
+		structure in addition to the requested amount of bytes. */
+		if( xWantedSize > 0 )
+		{
+			xWantedSize += heapSTRUCT_SIZE;
+
+			/* Ensure that blocks are always aligned to the required number of bytes. */
+			if( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) != 0 )
+			{
+				/* Byte alignment required. */
+				xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) );
+			}
+		}
+
+		if( ( xWantedSize > 0 ) && ( xWantedSize < configADJUSTED_HEAP_SIZE ) )
+		{
+			/* Blocks are stored in byte order - traverse the list from the start
+			(smallest) block until one of adequate size is found. */
+			pxPreviousBlock = &xStart;
+			pxBlock = xStart.pxNextFreeBlock;
+			while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock != NULL ) )
+			{
+				pxPreviousBlock = pxBlock;
+				pxBlock = pxBlock->pxNextFreeBlock;
+			}
+
+			/* If we found the end marker then a block of adequate size was not found. */
+			if( pxBlock != &xEnd )
+			{
+				/* Return the memory space - jumping over the BlockLink_t structure
+				at its start. */
+				pvReturn = ( void * ) ( ( ( uint8_t * ) pxPreviousBlock->pxNextFreeBlock ) + heapSTRUCT_SIZE );
+
+				/* This block is being returned for use so must be taken out of the
+				list of free blocks. */
+				pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock;
+
+				/* If the block is larger than required it can be split into two. */
+				if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE )
+				{
+					/* This block is to be split into two.  Create a new block
+					following the number of bytes requested. The void cast is
+					used to prevent byte alignment warnings from the compiler. */
+					pxNewBlockLink = ( void * ) ( ( ( uint8_t * ) pxBlock ) + xWantedSize );
+
+					/* Calculate the sizes of two blocks split from the single
+					block. */
+					pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize;
+					pxBlock->xBlockSize = xWantedSize;
+
+					/* Insert the new block into the list of free blocks. */
+					prvInsertBlockIntoFreeList( ( pxNewBlockLink ) );
+				}
+
+				xFreeBytesRemaining -= pxBlock->xBlockSize;
+			}
+		}
+
+		traceMALLOC( pvReturn, xWantedSize );
+	}
+	( void ) xTaskResumeAll();
+
+	#if( configUSE_MALLOC_FAILED_HOOK == 1 )
+	{
+		if( pvReturn == NULL )
+		{
+			extern void vApplicationMallocFailedHook( void );
+			vApplicationMallocFailedHook();
+		}
+	}
+	#endif
+
+	return pvReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vPortFree( void *pv )
+{
+uint8_t *puc = ( uint8_t * ) pv;
+BlockLink_t *pxLink;
+
+	if( pv != NULL )
+	{
+		/* The memory being freed will have an BlockLink_t structure immediately
+		before it. */
+		puc -= heapSTRUCT_SIZE;
+
+		/* This unexpected casting is to keep some compilers from issuing
+		byte alignment warnings. */
+		pxLink = ( void * ) puc;
+
+		vTaskSuspendAll();
+		{
+			/* Add this block to the list of free blocks. */
+			prvInsertBlockIntoFreeList( ( ( BlockLink_t * ) pxLink ) );
+			xFreeBytesRemaining += pxLink->xBlockSize;
+			traceFREE( pv, pxLink->xBlockSize );
+		}
+		( void ) xTaskResumeAll();
+	}
+}
+/*-----------------------------------------------------------*/
+
+size_t xPortGetFreeHeapSize( void )
+{
+	return xFreeBytesRemaining;
+}
+/*-----------------------------------------------------------*/
+
+void vPortInitialiseBlocks( void )
+{
+	/* This just exists to keep the linker quiet. */
+}
+/*-----------------------------------------------------------*/
+
+static void prvHeapInit( void )
+{
+BlockLink_t *pxFirstFreeBlock;
+uint8_t *pucAlignedHeap;
+
+	/* Ensure the heap starts on a correctly aligned boundary. */
+	pucAlignedHeap = ( uint8_t * ) ( ( ( portPOINTER_SIZE_TYPE ) &ucHeap[ portBYTE_ALIGNMENT ] ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) );
+
+	/* xStart is used to hold a pointer to the first item in the list of free
+	blocks.  The void cast is used to prevent compiler warnings. */
+	xStart.pxNextFreeBlock = ( void * ) pucAlignedHeap;
+	xStart.xBlockSize = ( size_t ) 0;
+
+	/* xEnd is used to mark the end of the list of free blocks. */
+	xEnd.xBlockSize = configADJUSTED_HEAP_SIZE;
+	xEnd.pxNextFreeBlock = NULL;
+
+	/* To start with there is a single free block that is sized to take up the
+	entire heap space. */
+	pxFirstFreeBlock = ( void * ) pucAlignedHeap;
+	pxFirstFreeBlock->xBlockSize = configADJUSTED_HEAP_SIZE;
+	pxFirstFreeBlock->pxNextFreeBlock = &xEnd;
+}
+/*-----------------------------------------------------------*/
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_3.c b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_3.c
new file mode 100644
index 0000000000000000000000000000000000000000..df3a9460cddec035804bb122af8ddcffd713e4a6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_3.c
@@ -0,0 +1,135 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+
+/*
+ * Implementation of pvPortMalloc() and vPortFree() that relies on the
+ * compilers own malloc() and free() implementations.
+ *
+ * This file can only be used if the linker is configured to to generate
+ * a heap memory area.
+ *
+ * See heap_1.c, heap_2.c and heap_4.c for alternative implementations, and the
+ * memory management pages of http://www.FreeRTOS.org for more information.
+ */
+
+#include <stdlib.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+/*-----------------------------------------------------------*/
+
+void *pvPortMalloc( size_t xWantedSize )
+{
+void *pvReturn;
+
+	vTaskSuspendAll();
+	{
+		pvReturn = malloc( xWantedSize );
+		traceMALLOC( pvReturn, xWantedSize );
+	}
+	( void ) xTaskResumeAll();
+
+	#if( configUSE_MALLOC_FAILED_HOOK == 1 )
+	{
+		if( pvReturn == NULL )
+		{
+			extern void vApplicationMallocFailedHook( void );
+			vApplicationMallocFailedHook();
+		}
+	}
+	#endif
+
+	return pvReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vPortFree( void *pv )
+{
+	if( pv )
+	{
+		vTaskSuspendAll();
+		{
+			free( pv );
+			traceFREE( pv, 0 );
+		}
+		( void ) xTaskResumeAll();
+	}
+}
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_4.c b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_4.c
new file mode 100644
index 0000000000000000000000000000000000000000..f139ef0512d9b11f7a9a6d7b015ca6c7a9edaeef
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_4.c
@@ -0,0 +1,474 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/*
+ * A sample implementation of pvPortMalloc() and vPortFree() that combines
+ * (coalescences) adjacent memory blocks as they are freed, and in so doing
+ * limits memory fragmentation.
+ *
+ * See heap_1.c, heap_2.c and heap_3.c for alternative implementations, and the
+ * memory management pages of http://www.FreeRTOS.org for more information.
+ */
+#include <stdlib.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+/* Block sizes must not get too small. */
+#define heapMINIMUM_BLOCK_SIZE	( ( size_t ) ( xHeapStructSize << 1 ) )
+
+/* Assumes 8bit bytes! */
+#define heapBITS_PER_BYTE		( ( size_t ) 8 )
+
+/* Allocate the memory for the heap. */
+#if( configAPPLICATION_ALLOCATED_HEAP == 1 )
+	/* The application writer has already defined the array used for the RTOS
+	heap - probably so it can be placed in a special segment or address. */
+	extern uint8_t ucHeap[ configTOTAL_HEAP_SIZE ];
+#else
+	static uint8_t ucHeap[ configTOTAL_HEAP_SIZE ];
+#endif /* configAPPLICATION_ALLOCATED_HEAP */
+
+/* Define the linked list structure.  This is used to link free blocks in order
+of their memory address. */
+typedef struct A_BLOCK_LINK
+{
+	struct A_BLOCK_LINK *pxNextFreeBlock;	/*<< The next free block in the list. */
+	size_t xBlockSize;						/*<< The size of the free block. */
+} BlockLink_t;
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Inserts a block of memory that is being freed into the correct position in
+ * the list of free memory blocks.  The block being freed will be merged with
+ * the block in front it and/or the block behind it if the memory blocks are
+ * adjacent to each other.
+ */
+static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert );
+
+/*
+ * Called automatically to setup the required heap structures the first time
+ * pvPortMalloc() is called.
+ */
+static void prvHeapInit( void );
+
+/*-----------------------------------------------------------*/
+
+/* The size of the structure placed at the beginning of each allocated memory
+block must by correctly byte aligned. */
+static const size_t xHeapStructSize	= ( sizeof( BlockLink_t ) + ( ( size_t ) ( portBYTE_ALIGNMENT - 1 ) ) ) & ~( ( size_t ) portBYTE_ALIGNMENT_MASK );
+
+/* Create a couple of list links to mark the start and end of the list. */
+static BlockLink_t xStart, *pxEnd = NULL;
+
+/* Keeps track of the number of free bytes remaining, but says nothing about
+fragmentation. */
+static size_t xFreeBytesRemaining = 0U;
+static size_t xMinimumEverFreeBytesRemaining = 0U;
+
+/* Gets set to the top bit of an size_t type.  When this bit in the xBlockSize
+member of an BlockLink_t structure is set then the block belongs to the
+application.  When the bit is free the block is still part of the free heap
+space. */
+static size_t xBlockAllocatedBit = 0;
+
+/*-----------------------------------------------------------*/
+
+void *pvPortMalloc( size_t xWantedSize )
+{
+BlockLink_t *pxBlock, *pxPreviousBlock, *pxNewBlockLink;
+void *pvReturn = NULL;
+
+	vTaskSuspendAll();
+	{
+		/* If this is the first call to malloc then the heap will require
+		initialisation to setup the list of free blocks. */
+		if( pxEnd == NULL )
+		{
+			prvHeapInit();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		/* Check the requested block size is not so large that the top bit is
+		set.  The top bit of the block size member of the BlockLink_t structure
+		is used to determine who owns the block - the application or the
+		kernel, so it must be free. */
+		if( ( xWantedSize & xBlockAllocatedBit ) == 0 )
+		{
+			/* The wanted size is increased so it can contain a BlockLink_t
+			structure in addition to the requested amount of bytes. */
+			if( xWantedSize > 0 )
+			{
+				xWantedSize += xHeapStructSize;
+
+				/* Ensure that blocks are always aligned to the required number
+				of bytes. */
+				if( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) != 0x00 )
+				{
+					/* Byte alignment required. */
+					xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) );
+					configASSERT( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) == 0 );
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			if( ( xWantedSize > 0 ) && ( xWantedSize <= xFreeBytesRemaining ) )
+			{
+				/* Traverse the list from the start	(lowest address) block until
+				one	of adequate size is found. */
+				pxPreviousBlock = &xStart;
+				pxBlock = xStart.pxNextFreeBlock;
+				while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock != NULL ) )
+				{
+					pxPreviousBlock = pxBlock;
+					pxBlock = pxBlock->pxNextFreeBlock;
+				}
+
+				/* If the end marker was reached then a block of adequate size
+				was	not found. */
+				if( pxBlock != pxEnd )
+				{
+					/* Return the memory space pointed to - jumping over the
+					BlockLink_t structure at its start. */
+					pvReturn = ( void * ) ( ( ( uint8_t * ) pxPreviousBlock->pxNextFreeBlock ) + xHeapStructSize );
+
+					/* This block is being returned for use so must be taken out
+					of the list of free blocks. */
+					pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock;
+
+					/* If the block is larger than required it can be split into
+					two. */
+					if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE )
+					{
+						/* This block is to be split into two.  Create a new
+						block following the number of bytes requested. The void
+						cast is used to prevent byte alignment warnings from the
+						compiler. */
+						pxNewBlockLink = ( void * ) ( ( ( uint8_t * ) pxBlock ) + xWantedSize );
+						configASSERT( ( ( ( size_t ) pxNewBlockLink ) & portBYTE_ALIGNMENT_MASK ) == 0 );
+
+						/* Calculate the sizes of two blocks split from the
+						single block. */
+						pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize;
+						pxBlock->xBlockSize = xWantedSize;
+
+						/* Insert the new block into the list of free blocks. */
+						prvInsertBlockIntoFreeList( pxNewBlockLink );
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					xFreeBytesRemaining -= pxBlock->xBlockSize;
+
+					if( xFreeBytesRemaining < xMinimumEverFreeBytesRemaining )
+					{
+						xMinimumEverFreeBytesRemaining = xFreeBytesRemaining;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					/* The block is being returned - it is allocated and owned
+					by the application and has no "next" block. */
+					pxBlock->xBlockSize |= xBlockAllocatedBit;
+					pxBlock->pxNextFreeBlock = NULL;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		traceMALLOC( pvReturn, xWantedSize );
+	}
+	( void ) xTaskResumeAll();
+
+	#if( configUSE_MALLOC_FAILED_HOOK == 1 )
+	{
+		if( pvReturn == NULL )
+		{
+			extern void vApplicationMallocFailedHook( void );
+			vApplicationMallocFailedHook();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	#endif
+
+	configASSERT( ( ( ( uint32_t ) pvReturn ) & portBYTE_ALIGNMENT_MASK ) == 0 );
+	return pvReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vPortFree( void *pv )
+{
+uint8_t *puc = ( uint8_t * ) pv;
+BlockLink_t *pxLink;
+
+	if( pv != NULL )
+	{
+		/* The memory being freed will have an BlockLink_t structure immediately
+		before it. */
+		puc -= xHeapStructSize;
+
+		/* This casting is to keep the compiler from issuing warnings. */
+		pxLink = ( void * ) puc;
+
+		/* Check the block is actually allocated. */
+		configASSERT( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 );
+		configASSERT( pxLink->pxNextFreeBlock == NULL );
+
+		if( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 )
+		{
+			if( pxLink->pxNextFreeBlock == NULL )
+			{
+				/* The block is being returned to the heap - it is no longer
+				allocated. */
+				pxLink->xBlockSize &= ~xBlockAllocatedBit;
+
+				vTaskSuspendAll();
+				{
+					/* Add this block to the list of free blocks. */
+					xFreeBytesRemaining += pxLink->xBlockSize;
+					traceFREE( pv, pxLink->xBlockSize );
+					prvInsertBlockIntoFreeList( ( ( BlockLink_t * ) pxLink ) );
+				}
+				( void ) xTaskResumeAll();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+}
+/*-----------------------------------------------------------*/
+
+size_t xPortGetFreeHeapSize( void )
+{
+	return xFreeBytesRemaining;
+}
+/*-----------------------------------------------------------*/
+
+size_t xPortGetMinimumEverFreeHeapSize( void )
+{
+	return xMinimumEverFreeBytesRemaining;
+}
+/*-----------------------------------------------------------*/
+
+void vPortInitialiseBlocks( void )
+{
+	/* This just exists to keep the linker quiet. */
+}
+/*-----------------------------------------------------------*/
+
+static void prvHeapInit( void )
+{
+BlockLink_t *pxFirstFreeBlock;
+uint8_t *pucAlignedHeap;
+size_t uxAddress;
+size_t xTotalHeapSize = configTOTAL_HEAP_SIZE;
+
+	/* Ensure the heap starts on a correctly aligned boundary. */
+	uxAddress = ( size_t ) ucHeap;
+
+	if( ( uxAddress & portBYTE_ALIGNMENT_MASK ) != 0 )
+	{
+		uxAddress += ( portBYTE_ALIGNMENT - 1 );
+		uxAddress &= ~( ( size_t ) portBYTE_ALIGNMENT_MASK );
+		xTotalHeapSize -= uxAddress - ( size_t ) ucHeap;
+	}
+
+	pucAlignedHeap = ( uint8_t * ) uxAddress;
+
+	/* xStart is used to hold a pointer to the first item in the list of free
+	blocks.  The void cast is used to prevent compiler warnings. */
+	xStart.pxNextFreeBlock = ( void * ) pucAlignedHeap;
+	xStart.xBlockSize = ( size_t ) 0;
+
+	/* pxEnd is used to mark the end of the list of free blocks and is inserted
+	at the end of the heap space. */
+	uxAddress = ( ( size_t ) pucAlignedHeap ) + xTotalHeapSize;
+	uxAddress -= xHeapStructSize;
+	uxAddress &= ~( ( size_t ) portBYTE_ALIGNMENT_MASK );
+	pxEnd = ( void * ) uxAddress;
+	pxEnd->xBlockSize = 0;
+	pxEnd->pxNextFreeBlock = NULL;
+
+	/* To start with there is a single free block that is sized to take up the
+	entire heap space, minus the space taken by pxEnd. */
+	pxFirstFreeBlock = ( void * ) pucAlignedHeap;
+	pxFirstFreeBlock->xBlockSize = uxAddress - ( size_t ) pxFirstFreeBlock;
+	pxFirstFreeBlock->pxNextFreeBlock = pxEnd;
+
+	/* Only one block exists - and it covers the entire usable heap space. */
+	xMinimumEverFreeBytesRemaining = pxFirstFreeBlock->xBlockSize;
+	xFreeBytesRemaining = pxFirstFreeBlock->xBlockSize;
+
+	/* Work out the position of the top bit in a size_t variable. */
+	xBlockAllocatedBit = ( ( size_t ) 1 ) << ( ( sizeof( size_t ) * heapBITS_PER_BYTE ) - 1 );
+}
+/*-----------------------------------------------------------*/
+
+static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert )
+{
+BlockLink_t *pxIterator;
+uint8_t *puc;
+
+	/* Iterate through the list until a block is found that has a higher address
+	than the block being inserted. */
+	for( pxIterator = &xStart; pxIterator->pxNextFreeBlock < pxBlockToInsert; pxIterator = pxIterator->pxNextFreeBlock )
+	{
+		/* Nothing to do here, just iterate to the right position. */
+	}
+
+	/* Do the block being inserted, and the block it is being inserted after
+	make a contiguous block of memory? */
+	puc = ( uint8_t * ) pxIterator;
+	if( ( puc + pxIterator->xBlockSize ) == ( uint8_t * ) pxBlockToInsert )
+	{
+		pxIterator->xBlockSize += pxBlockToInsert->xBlockSize;
+		pxBlockToInsert = pxIterator;
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	/* Do the block being inserted, and the block it is being inserted before
+	make a contiguous block of memory? */
+	puc = ( uint8_t * ) pxBlockToInsert;
+	if( ( puc + pxBlockToInsert->xBlockSize ) == ( uint8_t * ) pxIterator->pxNextFreeBlock )
+	{
+		if( pxIterator->pxNextFreeBlock != pxEnd )
+		{
+			/* Form one big block from the two blocks. */
+			pxBlockToInsert->xBlockSize += pxIterator->pxNextFreeBlock->xBlockSize;
+			pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock->pxNextFreeBlock;
+		}
+		else
+		{
+			pxBlockToInsert->pxNextFreeBlock = pxEnd;
+		}
+	}
+	else
+	{
+		pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock;
+	}
+
+	/* If the block being inserted plugged a gab, so was merged with the block
+	before and the block after, then it's pxNextFreeBlock pointer will have
+	already been set, and should not be set here as that would make it point
+	to itself. */
+	if( pxIterator != pxBlockToInsert )
+	{
+		pxIterator->pxNextFreeBlock = pxBlockToInsert;
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+}
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_5.c b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_5.c
new file mode 100644
index 0000000000000000000000000000000000000000..2f7b50abf0fbafcbd186bad9441665ba6f7569bd
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/portable/MemMang/heap_5.c
@@ -0,0 +1,523 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/*
+ * A sample implementation of pvPortMalloc() that allows the heap to be defined
+ * across multiple non-contigous blocks and combines (coalescences) adjacent
+ * memory blocks as they are freed.
+ *
+ * See heap_1.c, heap_2.c, heap_3.c and heap_4.c for alternative
+ * implementations, and the memory management pages of http://www.FreeRTOS.org
+ * for more information.
+ *
+ * Usage notes:
+ *
+ * vPortDefineHeapRegions() ***must*** be called before pvPortMalloc().
+ * pvPortMalloc() will be called if any task objects (tasks, queues, event
+ * groups, etc.) are created, therefore vPortDefineHeapRegions() ***must*** be
+ * called before any other objects are defined.
+ *
+ * vPortDefineHeapRegions() takes a single parameter.  The parameter is an array
+ * of HeapRegion_t structures.  HeapRegion_t is defined in portable.h as
+ *
+ * typedef struct HeapRegion
+ * {
+ *	uint8_t *pucStartAddress; << Start address of a block of memory that will be part of the heap.
+ *	size_t xSizeInBytes;	  << Size of the block of memory.
+ * } HeapRegion_t;
+ *
+ * The array is terminated using a NULL zero sized region definition, and the
+ * memory regions defined in the array ***must*** appear in address order from
+ * low address to high address.  So the following is a valid example of how
+ * to use the function.
+ *
+ * HeapRegion_t xHeapRegions[] =
+ * {
+ * 	{ ( uint8_t * ) 0x80000000UL, 0x10000 }, << Defines a block of 0x10000 bytes starting at address 0x80000000
+ * 	{ ( uint8_t * ) 0x90000000UL, 0xa0000 }, << Defines a block of 0xa0000 bytes starting at address of 0x90000000
+ * 	{ NULL, 0 }                << Terminates the array.
+ * };
+ *
+ * vPortDefineHeapRegions( xHeapRegions ); << Pass the array into vPortDefineHeapRegions().
+ *
+ * Note 0x80000000 is the lower address so appears in the array first.
+ *
+ */
+#include <stdlib.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+/* Block sizes must not get too small. */
+#define heapMINIMUM_BLOCK_SIZE	( ( size_t ) ( xHeapStructSize << 1 ) )
+
+/* Assumes 8bit bytes! */
+#define heapBITS_PER_BYTE		( ( size_t ) 8 )
+
+/* Define the linked list structure.  This is used to link free blocks in order
+of their memory address. */
+typedef struct A_BLOCK_LINK
+{
+	struct A_BLOCK_LINK *pxNextFreeBlock;	/*<< The next free block in the list. */
+	size_t xBlockSize;						/*<< The size of the free block. */
+} BlockLink_t;
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Inserts a block of memory that is being freed into the correct position in
+ * the list of free memory blocks.  The block being freed will be merged with
+ * the block in front it and/or the block behind it if the memory blocks are
+ * adjacent to each other.
+ */
+static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert );
+
+/*-----------------------------------------------------------*/
+
+/* The size of the structure placed at the beginning of each allocated memory
+block must by correctly byte aligned. */
+static const size_t xHeapStructSize	= ( sizeof( BlockLink_t ) + ( ( size_t ) ( portBYTE_ALIGNMENT - 1 ) ) ) & ~( ( size_t ) portBYTE_ALIGNMENT_MASK );
+
+/* Create a couple of list links to mark the start and end of the list. */
+static BlockLink_t xStart, *pxEnd = NULL;
+
+/* Keeps track of the number of free bytes remaining, but says nothing about
+fragmentation. */
+static size_t xFreeBytesRemaining = 0U;
+static size_t xMinimumEverFreeBytesRemaining = 0U;
+
+/* Gets set to the top bit of an size_t type.  When this bit in the xBlockSize
+member of an BlockLink_t structure is set then the block belongs to the
+application.  When the bit is free the block is still part of the free heap
+space. */
+static size_t xBlockAllocatedBit = 0;
+
+/*-----------------------------------------------------------*/
+
+void *pvPortMalloc( size_t xWantedSize )
+{
+BlockLink_t *pxBlock, *pxPreviousBlock, *pxNewBlockLink;
+void *pvReturn = NULL;
+
+	/* The heap must be initialised before the first call to
+	prvPortMalloc(). */
+	configASSERT( pxEnd );
+
+	vTaskSuspendAll();
+	{
+		/* Check the requested block size is not so large that the top bit is
+		set.  The top bit of the block size member of the BlockLink_t structure
+		is used to determine who owns the block - the application or the
+		kernel, so it must be free. */
+		if( ( xWantedSize & xBlockAllocatedBit ) == 0 )
+		{
+			/* The wanted size is increased so it can contain a BlockLink_t
+			structure in addition to the requested amount of bytes. */
+			if( xWantedSize > 0 )
+			{
+				xWantedSize += xHeapStructSize;
+
+				/* Ensure that blocks are always aligned to the required number
+				of bytes. */
+				if( ( xWantedSize & portBYTE_ALIGNMENT_MASK ) != 0x00 )
+				{
+					/* Byte alignment required. */
+					xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) );
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			if( ( xWantedSize > 0 ) && ( xWantedSize <= xFreeBytesRemaining ) )
+			{
+				/* Traverse the list from the start	(lowest address) block until
+				one	of adequate size is found. */
+				pxPreviousBlock = &xStart;
+				pxBlock = xStart.pxNextFreeBlock;
+				while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock != NULL ) )
+				{
+					pxPreviousBlock = pxBlock;
+					pxBlock = pxBlock->pxNextFreeBlock;
+				}
+
+				/* If the end marker was reached then a block of adequate size
+				was	not found. */
+				if( pxBlock != pxEnd )
+				{
+					/* Return the memory space pointed to - jumping over the
+					BlockLink_t structure at its start. */
+					pvReturn = ( void * ) ( ( ( uint8_t * ) pxPreviousBlock->pxNextFreeBlock ) + xHeapStructSize );
+
+					/* This block is being returned for use so must be taken out
+					of the list of free blocks. */
+					pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock;
+
+					/* If the block is larger than required it can be split into
+					two. */
+					if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE )
+					{
+						/* This block is to be split into two.  Create a new
+						block following the number of bytes requested. The void
+						cast is used to prevent byte alignment warnings from the
+						compiler. */
+						pxNewBlockLink = ( void * ) ( ( ( uint8_t * ) pxBlock ) + xWantedSize );
+
+						/* Calculate the sizes of two blocks split from the
+						single block. */
+						pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize;
+						pxBlock->xBlockSize = xWantedSize;
+
+						/* Insert the new block into the list of free blocks. */
+						prvInsertBlockIntoFreeList( ( pxNewBlockLink ) );
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					xFreeBytesRemaining -= pxBlock->xBlockSize;
+
+					if( xFreeBytesRemaining < xMinimumEverFreeBytesRemaining )
+					{
+						xMinimumEverFreeBytesRemaining = xFreeBytesRemaining;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					/* The block is being returned - it is allocated and owned
+					by the application and has no "next" block. */
+					pxBlock->xBlockSize |= xBlockAllocatedBit;
+					pxBlock->pxNextFreeBlock = NULL;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		traceMALLOC( pvReturn, xWantedSize );
+	}
+	( void ) xTaskResumeAll();
+
+	#if( configUSE_MALLOC_FAILED_HOOK == 1 )
+	{
+		if( pvReturn == NULL )
+		{
+			extern void vApplicationMallocFailedHook( void );
+			vApplicationMallocFailedHook();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	#endif
+
+	return pvReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vPortFree( void *pv )
+{
+uint8_t *puc = ( uint8_t * ) pv;
+BlockLink_t *pxLink;
+
+	if( pv != NULL )
+	{
+		/* The memory being freed will have an BlockLink_t structure immediately
+		before it. */
+		puc -= xHeapStructSize;
+
+		/* This casting is to keep the compiler from issuing warnings. */
+		pxLink = ( void * ) puc;
+
+		/* Check the block is actually allocated. */
+		configASSERT( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 );
+		configASSERT( pxLink->pxNextFreeBlock == NULL );
+
+		if( ( pxLink->xBlockSize & xBlockAllocatedBit ) != 0 )
+		{
+			if( pxLink->pxNextFreeBlock == NULL )
+			{
+				/* The block is being returned to the heap - it is no longer
+				allocated. */
+				pxLink->xBlockSize &= ~xBlockAllocatedBit;
+
+				vTaskSuspendAll();
+				{
+					/* Add this block to the list of free blocks. */
+					xFreeBytesRemaining += pxLink->xBlockSize;
+					traceFREE( pv, pxLink->xBlockSize );
+					prvInsertBlockIntoFreeList( ( ( BlockLink_t * ) pxLink ) );
+				}
+				( void ) xTaskResumeAll();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+}
+/*-----------------------------------------------------------*/
+
+size_t xPortGetFreeHeapSize( void )
+{
+	return xFreeBytesRemaining;
+}
+/*-----------------------------------------------------------*/
+
+size_t xPortGetMinimumEverFreeHeapSize( void )
+{
+	return xMinimumEverFreeBytesRemaining;
+}
+/*-----------------------------------------------------------*/
+
+static void prvInsertBlockIntoFreeList( BlockLink_t *pxBlockToInsert )
+{
+BlockLink_t *pxIterator;
+uint8_t *puc;
+
+	/* Iterate through the list until a block is found that has a higher address
+	than the block being inserted. */
+	for( pxIterator = &xStart; pxIterator->pxNextFreeBlock < pxBlockToInsert; pxIterator = pxIterator->pxNextFreeBlock )
+	{
+		/* Nothing to do here, just iterate to the right position. */
+	}
+
+	/* Do the block being inserted, and the block it is being inserted after
+	make a contiguous block of memory? */
+	puc = ( uint8_t * ) pxIterator;
+	if( ( puc + pxIterator->xBlockSize ) == ( uint8_t * ) pxBlockToInsert )
+	{
+		pxIterator->xBlockSize += pxBlockToInsert->xBlockSize;
+		pxBlockToInsert = pxIterator;
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	/* Do the block being inserted, and the block it is being inserted before
+	make a contiguous block of memory? */
+	puc = ( uint8_t * ) pxBlockToInsert;
+	if( ( puc + pxBlockToInsert->xBlockSize ) == ( uint8_t * ) pxIterator->pxNextFreeBlock )
+	{
+		if( pxIterator->pxNextFreeBlock != pxEnd )
+		{
+			/* Form one big block from the two blocks. */
+			pxBlockToInsert->xBlockSize += pxIterator->pxNextFreeBlock->xBlockSize;
+			pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock->pxNextFreeBlock;
+		}
+		else
+		{
+			pxBlockToInsert->pxNextFreeBlock = pxEnd;
+		}
+	}
+	else
+	{
+		pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock;
+	}
+
+	/* If the block being inserted plugged a gab, so was merged with the block
+	before and the block after, then it's pxNextFreeBlock pointer will have
+	already been set, and should not be set here as that would make it point
+	to itself. */
+	if( pxIterator != pxBlockToInsert )
+	{
+		pxIterator->pxNextFreeBlock = pxBlockToInsert;
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+}
+/*-----------------------------------------------------------*/
+
+void vPortDefineHeapRegions( const HeapRegion_t * const pxHeapRegions )
+{
+BlockLink_t *pxFirstFreeBlockInRegion = NULL, *pxPreviousFreeBlock;
+size_t xAlignedHeap;
+size_t xTotalRegionSize, xTotalHeapSize = 0;
+BaseType_t xDefinedRegions = 0;
+size_t xAddress;
+const HeapRegion_t *pxHeapRegion;
+
+	/* Can only call once! */
+	configASSERT( pxEnd == NULL );
+
+	pxHeapRegion = &( pxHeapRegions[ xDefinedRegions ] );
+
+	while( pxHeapRegion->xSizeInBytes > 0 )
+	{
+		xTotalRegionSize = pxHeapRegion->xSizeInBytes;
+
+		/* Ensure the heap region starts on a correctly aligned boundary. */
+		xAddress = ( size_t ) pxHeapRegion->pucStartAddress;
+		if( ( xAddress & portBYTE_ALIGNMENT_MASK ) != 0 )
+		{
+			xAddress += ( portBYTE_ALIGNMENT - 1 );
+			xAddress &= ~portBYTE_ALIGNMENT_MASK;
+
+			/* Adjust the size for the bytes lost to alignment. */
+			xTotalRegionSize -= xAddress - ( size_t ) pxHeapRegion->pucStartAddress;
+		}
+
+		xAlignedHeap = xAddress;
+
+		/* Set xStart if it has not already been set. */
+		if( xDefinedRegions == 0 )
+		{
+			/* xStart is used to hold a pointer to the first item in the list of
+			free blocks.  The void cast is used to prevent compiler warnings. */
+			xStart.pxNextFreeBlock = ( BlockLink_t * ) xAlignedHeap;
+			xStart.xBlockSize = ( size_t ) 0;
+		}
+		else
+		{
+			/* Should only get here if one region has already been added to the
+			heap. */
+			configASSERT( pxEnd != NULL );
+
+			/* Check blocks are passed in with increasing start addresses. */
+			configASSERT( xAddress > ( size_t ) pxEnd );
+		}
+
+		/* Remember the location of the end marker in the previous region, if
+		any. */
+		pxPreviousFreeBlock = pxEnd;
+
+		/* pxEnd is used to mark the end of the list of free blocks and is
+		inserted at the end of the region space. */
+		xAddress = xAlignedHeap + xTotalRegionSize;
+		xAddress -= xHeapStructSize;
+		xAddress &= ~portBYTE_ALIGNMENT_MASK;
+		pxEnd = ( BlockLink_t * ) xAddress;
+		pxEnd->xBlockSize = 0;
+		pxEnd->pxNextFreeBlock = NULL;
+
+		/* To start with there is a single free block in this region that is
+		sized to take up the entire heap region minus the space taken by the
+		free block structure. */
+		pxFirstFreeBlockInRegion = ( BlockLink_t * ) xAlignedHeap;
+		pxFirstFreeBlockInRegion->xBlockSize = xAddress - ( size_t ) pxFirstFreeBlockInRegion;
+		pxFirstFreeBlockInRegion->pxNextFreeBlock = pxEnd;
+
+		/* If this is not the first region that makes up the entire heap space
+		then link the previous region to this region. */
+		if( pxPreviousFreeBlock != NULL )
+		{
+			pxPreviousFreeBlock->pxNextFreeBlock = pxFirstFreeBlockInRegion;
+		}
+
+		xTotalHeapSize += pxFirstFreeBlockInRegion->xBlockSize;
+
+		/* Move onto the next HeapRegion_t structure. */
+		xDefinedRegions++;
+		pxHeapRegion = &( pxHeapRegions[ xDefinedRegions ] );
+	}
+
+	xMinimumEverFreeBytesRemaining = xTotalHeapSize;
+	xFreeBytesRemaining = xTotalHeapSize;
+
+	/* Check something was actually defined before it is accessed. */
+	configASSERT( xTotalHeapSize );
+
+	/* Work out the position of the top bit in a size_t variable. */
+	xBlockAllocatedBit = ( ( size_t ) 1 ) << ( ( sizeof( size_t ) * heapBITS_PER_BYTE ) - 1 );
+}
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/queue.c b/crazyflie-firmware-src/src/lib/FreeRTOS/queue.c
new file mode 100644
index 0000000000000000000000000000000000000000..c71ef50203f4213f53141b1312c603dc42695f31
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/queue.c
@@ -0,0 +1,2608 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+#include <stdlib.h>
+#include <string.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+
+#if ( configUSE_CO_ROUTINES == 1 )
+	#include "croutine.h"
+#endif
+
+/* Lint e961 and e750 are suppressed as a MISRA exception justified because the
+MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined for the
+header files above, but not in this file, in order to generate the correct
+privileged Vs unprivileged linkage and placement. */
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750. */
+
+
+/* Constants used with the xRxLock and xTxLock structure members. */
+#define queueUNLOCKED					( ( BaseType_t ) -1 )
+#define queueLOCKED_UNMODIFIED			( ( BaseType_t ) 0 )
+
+/* When the Queue_t structure is used to represent a base queue its pcHead and
+pcTail members are used as pointers into the queue storage area.  When the
+Queue_t structure is used to represent a mutex pcHead and pcTail pointers are
+not necessary, and the pcHead pointer is set to NULL to indicate that the
+pcTail pointer actually points to the mutex holder (if any).  Map alternative
+names to the pcHead and pcTail structure members to ensure the readability of
+the code is maintained despite this dual use of two structure members.  An
+alternative implementation would be to use a union, but use of a union is
+against the coding standard (although an exception to the standard has been
+permitted where the dual use also significantly changes the type of the
+structure member). */
+#define pxMutexHolder					pcTail
+#define uxQueueType						pcHead
+#define queueQUEUE_IS_MUTEX				NULL
+
+/* Semaphores do not actually store or copy data, so have an item size of
+zero. */
+#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( UBaseType_t ) 0 )
+#define queueMUTEX_GIVE_BLOCK_TIME		 ( ( TickType_t ) 0U )
+
+#if( configUSE_PREEMPTION == 0 )
+	/* If the cooperative scheduler is being used then a yield should not be
+	performed just because a higher priority task has been woken. */
+	#define queueYIELD_IF_USING_PREEMPTION()
+#else
+	#define queueYIELD_IF_USING_PREEMPTION() portYIELD_WITHIN_API()
+#endif
+
+/*
+ * Definition of the queue used by the scheduler.
+ * Items are queued by copy, not reference.  See the following link for the
+ * rationale: http://www.freertos.org/Embedded-RTOS-Queues.html
+ */
+typedef struct QueueDefinition
+{
+	int8_t *pcHead;					/*< Points to the beginning of the queue storage area. */
+	int8_t *pcTail;					/*< Points to the byte at the end of the queue storage area.  Once more byte is allocated than necessary to store the queue items, this is used as a marker. */
+	int8_t *pcWriteTo;				/*< Points to the free next place in the storage area. */
+
+	union							/* Use of a union is an exception to the coding standard to ensure two mutually exclusive structure members don't appear simultaneously (wasting RAM). */
+	{
+		int8_t *pcReadFrom;			/*< Points to the last place that a queued item was read from when the structure is used as a queue. */
+		UBaseType_t uxRecursiveCallCount;/*< Maintains a count of the number of times a recursive mutex has been recursively 'taken' when the structure is used as a mutex. */
+	} u;
+
+	List_t xTasksWaitingToSend;		/*< List of tasks that are blocked waiting to post onto this queue.  Stored in priority order. */
+	List_t xTasksWaitingToReceive;	/*< List of tasks that are blocked waiting to read from this queue.  Stored in priority order. */
+
+	volatile UBaseType_t uxMessagesWaiting;/*< The number of items currently in the queue. */
+	UBaseType_t uxLength;			/*< The length of the queue defined as the number of items it will hold, not the number of bytes. */
+	UBaseType_t uxItemSize;			/*< The size of each items that the queue will hold. */
+
+	volatile BaseType_t xRxLock;	/*< Stores the number of items received from the queue (removed from the queue) while the queue was locked.  Set to queueUNLOCKED when the queue is not locked. */
+	volatile BaseType_t xTxLock;	/*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked.  Set to queueUNLOCKED when the queue is not locked. */
+
+	#if ( configUSE_TRACE_FACILITY == 1 )
+		UBaseType_t uxQueueNumber;
+		uint8_t ucQueueType;
+	#endif
+
+	#if ( configUSE_QUEUE_SETS == 1 )
+		struct QueueDefinition *pxQueueSetContainer;
+	#endif
+
+} xQUEUE;
+
+/* The old xQUEUE name is maintained above then typedefed to the new Queue_t
+name below to enable the use of older kernel aware debuggers. */
+typedef xQUEUE Queue_t;
+
+/*-----------------------------------------------------------*/
+
+/*
+ * The queue registry is just a means for kernel aware debuggers to locate
+ * queue structures.  It has no other purpose so is an optional component.
+ */
+#if ( configQUEUE_REGISTRY_SIZE > 0 )
+
+	/* The type stored within the queue registry array.  This allows a name
+	to be assigned to each queue making kernel aware debugging a little
+	more user friendly. */
+	typedef struct QUEUE_REGISTRY_ITEM
+	{
+		const char *pcQueueName; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+		QueueHandle_t xHandle;
+	} xQueueRegistryItem;
+
+	/* The old xQueueRegistryItem name is maintained above then typedefed to the
+	new xQueueRegistryItem name below to enable the use of older kernel aware
+	debuggers. */
+	typedef xQueueRegistryItem QueueRegistryItem_t;
+
+	/* The queue registry is simply an array of QueueRegistryItem_t structures.
+	The pcQueueName member of a structure being NULL is indicative of the
+	array position being vacant. */
+	PRIVILEGED_DATA QueueRegistryItem_t xQueueRegistry[ configQUEUE_REGISTRY_SIZE ];
+
+#endif /* configQUEUE_REGISTRY_SIZE */
+
+/*
+ * Unlocks a queue locked by a call to prvLockQueue.  Locking a queue does not
+ * prevent an ISR from adding or removing items to the queue, but does prevent
+ * an ISR from removing tasks from the queue event lists.  If an ISR finds a
+ * queue is locked it will instead increment the appropriate queue lock count
+ * to indicate that a task may require unblocking.  When the queue in unlocked
+ * these lock counts are inspected, and the appropriate action taken.
+ */
+static void prvUnlockQueue( Queue_t * const pxQueue ) PRIVILEGED_FUNCTION;
+
+/*
+ * Uses a critical section to determine if there is any data in a queue.
+ *
+ * @return pdTRUE if the queue contains no items, otherwise pdFALSE.
+ */
+static BaseType_t prvIsQueueEmpty( const Queue_t *pxQueue ) PRIVILEGED_FUNCTION;
+
+/*
+ * Uses a critical section to determine if there is any space in a queue.
+ *
+ * @return pdTRUE if there is no space, otherwise pdFALSE;
+ */
+static BaseType_t prvIsQueueFull( const Queue_t *pxQueue ) PRIVILEGED_FUNCTION;
+
+/*
+ * Copies an item into the queue, either at the front of the queue or the
+ * back of the queue.
+ */
+static BaseType_t prvCopyDataToQueue( Queue_t * const pxQueue, const void *pvItemToQueue, const BaseType_t xPosition ) PRIVILEGED_FUNCTION;
+
+/*
+ * Copies an item out of a queue.
+ */
+static void prvCopyDataFromQueue( Queue_t * const pxQueue, void * const pvBuffer ) PRIVILEGED_FUNCTION;
+
+#if ( configUSE_QUEUE_SETS == 1 )
+	/*
+	 * Checks to see if a queue is a member of a queue set, and if so, notifies
+	 * the queue set that the queue contains data.
+	 */
+	static BaseType_t prvNotifyQueueSetContainer( const Queue_t * const pxQueue, const BaseType_t xCopyPosition ) PRIVILEGED_FUNCTION;
+#endif
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Macro to mark a queue as locked.  Locking a queue prevents an ISR from
+ * accessing the queue event lists.
+ */
+#define prvLockQueue( pxQueue )								\
+	taskENTER_CRITICAL();									\
+	{														\
+		if( ( pxQueue )->xRxLock == queueUNLOCKED )			\
+		{													\
+			( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED;	\
+		}													\
+		if( ( pxQueue )->xTxLock == queueUNLOCKED )			\
+		{													\
+			( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED;	\
+		}													\
+	}														\
+	taskEXIT_CRITICAL()
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueGenericReset( QueueHandle_t xQueue, BaseType_t xNewQueue )
+{
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	configASSERT( pxQueue );
+
+	taskENTER_CRITICAL();
+	{
+		pxQueue->pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize );
+		pxQueue->uxMessagesWaiting = ( UBaseType_t ) 0U;
+		pxQueue->pcWriteTo = pxQueue->pcHead;
+		pxQueue->u.pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - ( UBaseType_t ) 1U ) * pxQueue->uxItemSize );
+		pxQueue->xRxLock = queueUNLOCKED;
+		pxQueue->xTxLock = queueUNLOCKED;
+
+		if( xNewQueue == pdFALSE )
+		{
+			/* If there are tasks blocked waiting to read from the queue, then
+			the tasks will remain blocked as after this function exits the queue
+			will still be empty.  If there are tasks blocked waiting to write to
+			the queue, then one should be unblocked as after this function exits
+			it will be possible to write to it. */
+			if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE )
+			{
+				if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE )
+				{
+					queueYIELD_IF_USING_PREEMPTION();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			/* Ensure the event queues start in the correct state. */
+			vListInitialise( &( pxQueue->xTasksWaitingToSend ) );
+			vListInitialise( &( pxQueue->xTasksWaitingToReceive ) );
+		}
+	}
+	taskEXIT_CRITICAL();
+
+	/* A value is returned for calling semantic consistency with previous
+	versions. */
+	return pdPASS;
+}
+/*-----------------------------------------------------------*/
+
+QueueHandle_t xQueueGenericCreate( const UBaseType_t uxQueueLength, const UBaseType_t uxItemSize, const uint8_t ucQueueType )
+{
+Queue_t *pxNewQueue;
+size_t xQueueSizeInBytes;
+QueueHandle_t xReturn = NULL;
+
+	/* Remove compiler warnings about unused parameters should
+	configUSE_TRACE_FACILITY not be set to 1. */
+	( void ) ucQueueType;
+
+	configASSERT( uxQueueLength > ( UBaseType_t ) 0 );
+
+	if( uxItemSize == ( UBaseType_t ) 0 )
+	{
+		/* There is not going to be a queue storage area. */
+		xQueueSizeInBytes = ( size_t ) 0;
+	}
+	else
+	{
+		/* The queue is one byte longer than asked for to make wrap checking
+		easier/faster. */
+		xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+	}
+
+	/* Allocate the new queue structure and storage area. */
+	pxNewQueue = ( Queue_t * ) pvPortMalloc( sizeof( Queue_t ) + xQueueSizeInBytes );
+
+	if( pxNewQueue != NULL )
+	{
+		if( uxItemSize == ( UBaseType_t ) 0 )
+		{
+			/* No RAM was allocated for the queue storage area, but PC head
+			cannot be set to NULL because NULL is used as a key to say the queue
+			is used as a mutex.  Therefore just set pcHead to point to the queue
+			as a benign value that is known to be within the memory map. */
+			pxNewQueue->pcHead = ( int8_t * ) pxNewQueue;
+		}
+		else
+		{
+			/* Jump past the queue structure to find the location of the queue
+			storage area. */
+			pxNewQueue->pcHead = ( ( int8_t * ) pxNewQueue ) + sizeof( Queue_t );
+		}
+
+		/* Initialise the queue members as described above where the queue type
+		is defined. */
+		pxNewQueue->uxLength = uxQueueLength;
+		pxNewQueue->uxItemSize = uxItemSize;
+		( void ) xQueueGenericReset( pxNewQueue, pdTRUE );
+
+		#if ( configUSE_TRACE_FACILITY == 1 )
+		{
+			pxNewQueue->ucQueueType = ucQueueType;
+		}
+		#endif /* configUSE_TRACE_FACILITY */
+
+		#if( configUSE_QUEUE_SETS == 1 )
+		{
+			pxNewQueue->pxQueueSetContainer = NULL;
+		}
+		#endif /* configUSE_QUEUE_SETS */
+
+		traceQUEUE_CREATE( pxNewQueue );
+		xReturn = pxNewQueue;
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	configASSERT( xReturn );
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_MUTEXES == 1 )
+
+	QueueHandle_t xQueueCreateMutex( const uint8_t ucQueueType )
+	{
+	Queue_t *pxNewQueue;
+
+		/* Prevent compiler warnings about unused parameters if
+		configUSE_TRACE_FACILITY does not equal 1. */
+		( void ) ucQueueType;
+
+		/* Allocate the new queue structure. */
+		pxNewQueue = ( Queue_t * ) pvPortMalloc( sizeof( Queue_t ) );
+		if( pxNewQueue != NULL )
+		{
+			/* Information required for priority inheritance. */
+			pxNewQueue->pxMutexHolder = NULL;
+			pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX;
+
+			/* Queues used as a mutex no data is actually copied into or out
+			of the queue. */
+			pxNewQueue->pcWriteTo = NULL;
+			pxNewQueue->u.pcReadFrom = NULL;
+
+			/* Each mutex has a length of 1 (like a binary semaphore) and
+			an item size of 0 as nothing is actually copied into or out
+			of the mutex. */
+			pxNewQueue->uxMessagesWaiting = ( UBaseType_t ) 0U;
+			pxNewQueue->uxLength = ( UBaseType_t ) 1U;
+			pxNewQueue->uxItemSize = ( UBaseType_t ) 0U;
+			pxNewQueue->xRxLock = queueUNLOCKED;
+			pxNewQueue->xTxLock = queueUNLOCKED;
+
+			#if ( configUSE_TRACE_FACILITY == 1 )
+			{
+				pxNewQueue->ucQueueType = ucQueueType;
+			}
+			#endif
+
+			#if ( configUSE_QUEUE_SETS == 1 )
+			{
+				pxNewQueue->pxQueueSetContainer = NULL;
+			}
+			#endif
+
+			/* Ensure the event queues start with the correct state. */
+			vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) );
+			vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) );
+
+			traceCREATE_MUTEX( pxNewQueue );
+
+			/* Start with the semaphore in the expected state. */
+			( void ) xQueueGenericSend( pxNewQueue, NULL, ( TickType_t ) 0U, queueSEND_TO_BACK );
+		}
+		else
+		{
+			traceCREATE_MUTEX_FAILED();
+		}
+
+		return pxNewQueue;
+	}
+
+#endif /* configUSE_MUTEXES */
+/*-----------------------------------------------------------*/
+
+#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xSemaphoreGetMutexHolder == 1 ) )
+
+	void* xQueueGetMutexHolder( QueueHandle_t xSemaphore )
+	{
+	void *pxReturn;
+
+		/* This function is called by xSemaphoreGetMutexHolder(), and should not
+		be called directly.  Note:  This is a good way of determining if the
+		calling task is the mutex holder, but not a good way of determining the
+		identity of the mutex holder, as the holder may change between the
+		following critical section exiting and the function returning. */
+		taskENTER_CRITICAL();
+		{
+			if( ( ( Queue_t * ) xSemaphore )->uxQueueType == queueQUEUE_IS_MUTEX )
+			{
+				pxReturn = ( void * ) ( ( Queue_t * ) xSemaphore )->pxMutexHolder;
+			}
+			else
+			{
+				pxReturn = NULL;
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		return pxReturn;
+	} /*lint !e818 xSemaphore cannot be a pointer to const because it is a typedef. */
+
+#endif
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_RECURSIVE_MUTEXES == 1 )
+
+	BaseType_t xQueueGiveMutexRecursive( QueueHandle_t xMutex )
+	{
+	BaseType_t xReturn;
+	Queue_t * const pxMutex = ( Queue_t * ) xMutex;
+
+		configASSERT( pxMutex );
+
+		/* If this is the task that holds the mutex then pxMutexHolder will not
+		change outside of this task.  If this task does not hold the mutex then
+		pxMutexHolder can never coincidentally equal the tasks handle, and as
+		this is the only condition we are interested in it does not matter if
+		pxMutexHolder is accessed simultaneously by another task.  Therefore no
+		mutual exclusion is required to test the pxMutexHolder variable. */
+		if( pxMutex->pxMutexHolder == ( void * ) xTaskGetCurrentTaskHandle() ) /*lint !e961 Not a redundant cast as TaskHandle_t is a typedef. */
+		{
+			traceGIVE_MUTEX_RECURSIVE( pxMutex );
+
+			/* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to
+			the task handle, therefore no underflow check is required.  Also,
+			uxRecursiveCallCount is only modified by the mutex holder, and as
+			there can only be one, no mutual exclusion is required to modify the
+			uxRecursiveCallCount member. */
+			( pxMutex->u.uxRecursiveCallCount )--;
+
+			/* Have we unwound the call count? */
+			if( pxMutex->u.uxRecursiveCallCount == ( UBaseType_t ) 0 )
+			{
+				/* Return the mutex.  This will automatically unblock any other
+				task that might be waiting to access the mutex. */
+				( void ) xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			xReturn = pdPASS;
+		}
+		else
+		{
+			/* The mutex cannot be given because the calling task is not the
+			holder. */
+			xReturn = pdFAIL;
+
+			traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex );
+		}
+
+		return xReturn;
+	}
+
+#endif /* configUSE_RECURSIVE_MUTEXES */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_RECURSIVE_MUTEXES == 1 )
+
+	BaseType_t xQueueTakeMutexRecursive( QueueHandle_t xMutex, TickType_t xTicksToWait )
+	{
+	BaseType_t xReturn;
+	Queue_t * const pxMutex = ( Queue_t * ) xMutex;
+
+		configASSERT( pxMutex );
+
+		/* Comments regarding mutual exclusion as per those within
+		xQueueGiveMutexRecursive(). */
+
+		traceTAKE_MUTEX_RECURSIVE( pxMutex );
+
+		if( pxMutex->pxMutexHolder == ( void * ) xTaskGetCurrentTaskHandle() ) /*lint !e961 Cast is not redundant as TaskHandle_t is a typedef. */
+		{
+			( pxMutex->u.uxRecursiveCallCount )++;
+			xReturn = pdPASS;
+		}
+		else
+		{
+			xReturn = xQueueGenericReceive( pxMutex, NULL, xTicksToWait, pdFALSE );
+
+			/* pdPASS will only be returned if the mutex was successfully
+			obtained.  The calling task may have entered the Blocked state
+			before reaching here. */
+			if( xReturn == pdPASS )
+			{
+				( pxMutex->u.uxRecursiveCallCount )++;
+			}
+			else
+			{
+				traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex );
+			}
+		}
+
+		return xReturn;
+	}
+
+#endif /* configUSE_RECURSIVE_MUTEXES */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_COUNTING_SEMAPHORES == 1 )
+
+	QueueHandle_t xQueueCreateCountingSemaphore( const UBaseType_t uxMaxCount, const UBaseType_t uxInitialCount )
+	{
+	QueueHandle_t xHandle;
+
+		configASSERT( uxMaxCount != 0 );
+		configASSERT( uxInitialCount <= uxMaxCount );
+
+		xHandle = xQueueGenericCreate( uxMaxCount, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE );
+
+		if( xHandle != NULL )
+		{
+			( ( Queue_t * ) xHandle )->uxMessagesWaiting = uxInitialCount;
+
+			traceCREATE_COUNTING_SEMAPHORE();
+		}
+		else
+		{
+			traceCREATE_COUNTING_SEMAPHORE_FAILED();
+		}
+
+		configASSERT( xHandle );
+		return xHandle;
+	}
+
+#endif /* configUSE_COUNTING_SEMAPHORES */
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, const BaseType_t xCopyPosition )
+{
+BaseType_t xEntryTimeSet = pdFALSE, xYieldRequired;
+TimeOut_t xTimeOut;
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	configASSERT( pxQueue );
+	configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) );
+	configASSERT( !( ( xCopyPosition == queueOVERWRITE ) && ( pxQueue->uxLength != 1 ) ) );
+	#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) )
+	{
+		configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) );
+	}
+	#endif
+
+
+	/* This function relaxes the coding standard somewhat to allow return
+	statements within the function itself.  This is done in the interest
+	of execution time efficiency. */
+	for( ;; )
+	{
+		taskENTER_CRITICAL();
+		{
+			/* Is there room on the queue now?  The running task must be the
+			highest priority task wanting to access the queue.  If the head item
+			in the queue is to be overwritten then it does not matter if the
+			queue is full. */
+			if( ( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) || ( xCopyPosition == queueOVERWRITE ) )
+			{
+				traceQUEUE_SEND( pxQueue );
+				xYieldRequired = prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition );
+
+				#if ( configUSE_QUEUE_SETS == 1 )
+				{
+					if( pxQueue->pxQueueSetContainer != NULL )
+					{
+						if( prvNotifyQueueSetContainer( pxQueue, xCopyPosition ) == pdTRUE )
+						{
+							/* The queue is a member of a queue set, and posting
+							to the queue set caused a higher priority task to
+							unblock. A context switch is required. */
+							queueYIELD_IF_USING_PREEMPTION();
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						/* If there was a task waiting for data to arrive on the
+						queue then unblock it now. */
+						if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+						{
+							if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE )
+							{
+								/* The unblocked task has a priority higher than
+								our own so yield immediately.  Yes it is ok to
+								do this from within the critical section - the
+								kernel takes care of that. */
+								queueYIELD_IF_USING_PREEMPTION();
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else if( xYieldRequired != pdFALSE )
+						{
+							/* This path is a special case that will only get
+							executed if the task was holding multiple mutexes
+							and the mutexes were given back in an order that is
+							different to that in which they were taken. */
+							queueYIELD_IF_USING_PREEMPTION();
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+				}
+				#else /* configUSE_QUEUE_SETS */
+				{
+					/* If there was a task waiting for data to arrive on the
+					queue then unblock it now. */
+					if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+					{
+						if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE )
+						{
+							/* The unblocked task has a priority higher than
+							our own so yield immediately.  Yes it is ok to do
+							this from within the critical section - the kernel
+							takes care of that. */
+							queueYIELD_IF_USING_PREEMPTION();
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else if( xYieldRequired != pdFALSE )
+					{
+						/* This path is a special case that will only get
+						executed if the task was holding multiple mutexes and
+						the mutexes were given back in an order that is
+						different to that in which they were taken. */
+						queueYIELD_IF_USING_PREEMPTION();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				#endif /* configUSE_QUEUE_SETS */
+
+				taskEXIT_CRITICAL();
+				return pdPASS;
+			}
+			else
+			{
+				if( xTicksToWait == ( TickType_t ) 0 )
+				{
+					/* The queue was full and no block time is specified (or
+					the block time has expired) so leave now. */
+					taskEXIT_CRITICAL();
+
+					/* Return to the original privilege level before exiting
+					the function. */
+					traceQUEUE_SEND_FAILED( pxQueue );
+					return errQUEUE_FULL;
+				}
+				else if( xEntryTimeSet == pdFALSE )
+				{
+					/* The queue was full and a block time was specified so
+					configure the timeout structure. */
+					vTaskSetTimeOutState( &xTimeOut );
+					xEntryTimeSet = pdTRUE;
+				}
+				else
+				{
+					/* Entry time was already set. */
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		/* Interrupts and other tasks can send to and receive from the queue
+		now the critical section has been exited. */
+
+		vTaskSuspendAll();
+		prvLockQueue( pxQueue );
+
+		/* Update the timeout state to see if it has expired yet. */
+		if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE )
+		{
+			if( prvIsQueueFull( pxQueue ) != pdFALSE )
+			{
+				traceBLOCKING_ON_QUEUE_SEND( pxQueue );
+				vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait );
+
+				/* Unlocking the queue means queue events can effect the
+				event list.  It is possible	that interrupts occurring now
+				remove this task from the event	list again - but as the
+				scheduler is suspended the task will go onto the pending
+				ready last instead of the actual ready list. */
+				prvUnlockQueue( pxQueue );
+
+				/* Resuming the scheduler will move tasks from the pending
+				ready list into the ready list - so it is feasible that this
+				task is already in a ready list before it yields - in which
+				case the yield will not cause a context switch unless there
+				is also a higher priority task in the pending ready list. */
+				if( xTaskResumeAll() == pdFALSE )
+				{
+					portYIELD_WITHIN_API();
+				}
+			}
+			else
+			{
+				/* Try again. */
+				prvUnlockQueue( pxQueue );
+				( void ) xTaskResumeAll();
+			}
+		}
+		else
+		{
+			/* The timeout has expired. */
+			prvUnlockQueue( pxQueue );
+			( void ) xTaskResumeAll();
+
+			/* Return to the original privilege level before exiting the
+			function. */
+			traceQUEUE_SEND_FAILED( pxQueue );
+			return errQUEUE_FULL;
+		}
+	}
+}
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_ALTERNATIVE_API == 1 )
+
+	BaseType_t xQueueAltGenericSend( QueueHandle_t xQueue, const void * const pvItemToQueue, TickType_t xTicksToWait, BaseType_t xCopyPosition )
+	{
+	BaseType_t xEntryTimeSet = pdFALSE;
+	TimeOut_t xTimeOut;
+	Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+		configASSERT( pxQueue );
+		configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) );
+
+		for( ;; )
+		{
+			taskENTER_CRITICAL();
+			{
+				/* Is there room on the queue now?  To be running we must be
+				the highest priority task wanting to access the queue. */
+				if( pxQueue->uxMessagesWaiting < pxQueue->uxLength )
+				{
+					traceQUEUE_SEND( pxQueue );
+					prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition );
+
+					/* If there was a task waiting for data to arrive on the
+					queue then unblock it now. */
+					if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+					{
+						if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE )
+						{
+							/* The unblocked task has a priority higher than
+							our own so yield immediately. */
+							portYIELD_WITHIN_API();
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					taskEXIT_CRITICAL();
+					return pdPASS;
+				}
+				else
+				{
+					if( xTicksToWait == ( TickType_t ) 0 )
+					{
+						taskEXIT_CRITICAL();
+						return errQUEUE_FULL;
+					}
+					else if( xEntryTimeSet == pdFALSE )
+					{
+						vTaskSetTimeOutState( &xTimeOut );
+						xEntryTimeSet = pdTRUE;
+					}
+				}
+			}
+			taskEXIT_CRITICAL();
+
+			taskENTER_CRITICAL();
+			{
+				if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE )
+				{
+					if( prvIsQueueFull( pxQueue ) != pdFALSE )
+					{
+						traceBLOCKING_ON_QUEUE_SEND( pxQueue );
+						vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait );
+						portYIELD_WITHIN_API();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					taskEXIT_CRITICAL();
+					traceQUEUE_SEND_FAILED( pxQueue );
+					return errQUEUE_FULL;
+				}
+			}
+			taskEXIT_CRITICAL();
+		}
+	}
+
+#endif /* configUSE_ALTERNATIVE_API */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_ALTERNATIVE_API == 1 )
+
+	BaseType_t xQueueAltGenericReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait, BaseType_t xJustPeeking )
+	{
+	BaseType_t xEntryTimeSet = pdFALSE;
+	TimeOut_t xTimeOut;
+	int8_t *pcOriginalReadPosition;
+	Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+		configASSERT( pxQueue );
+		configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) );
+
+		for( ;; )
+		{
+			taskENTER_CRITICAL();
+			{
+				if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 )
+				{
+					/* Remember our read position in case we are just peeking. */
+					pcOriginalReadPosition = pxQueue->u.pcReadFrom;
+
+					prvCopyDataFromQueue( pxQueue, pvBuffer );
+
+					if( xJustPeeking == pdFALSE )
+					{
+						traceQUEUE_RECEIVE( pxQueue );
+
+						/* Data is actually being removed (not just peeked). */
+						--( pxQueue->uxMessagesWaiting );
+
+						#if ( configUSE_MUTEXES == 1 )
+						{
+							if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX )
+							{
+								/* Record the information required to implement
+								priority inheritance should it become necessary. */
+								pxQueue->pxMutexHolder = ( int8_t * ) xTaskGetCurrentTaskHandle();
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						#endif
+
+						if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE )
+						{
+							if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE )
+							{
+								portYIELD_WITHIN_API();
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+					}
+					else
+					{
+						traceQUEUE_PEEK( pxQueue );
+
+						/* The data is not being removed, so reset our read
+						pointer. */
+						pxQueue->u.pcReadFrom = pcOriginalReadPosition;
+
+						/* The data is being left in the queue, so see if there are
+						any other tasks waiting for the data. */
+						if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+						{
+							/* Tasks that are removed from the event list will get added to
+							the pending ready list as the scheduler is still suspended. */
+							if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+							{
+								/* The task waiting has a higher priority than this task. */
+								portYIELD_WITHIN_API();
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+
+					taskEXIT_CRITICAL();
+					return pdPASS;
+				}
+				else
+				{
+					if( xTicksToWait == ( TickType_t ) 0 )
+					{
+						taskEXIT_CRITICAL();
+						traceQUEUE_RECEIVE_FAILED( pxQueue );
+						return errQUEUE_EMPTY;
+					}
+					else if( xEntryTimeSet == pdFALSE )
+					{
+						vTaskSetTimeOutState( &xTimeOut );
+						xEntryTimeSet = pdTRUE;
+					}
+				}
+			}
+			taskEXIT_CRITICAL();
+
+			taskENTER_CRITICAL();
+			{
+				if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE )
+				{
+					if( prvIsQueueEmpty( pxQueue ) != pdFALSE )
+					{
+						traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue );
+
+						#if ( configUSE_MUTEXES == 1 )
+						{
+							if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX )
+							{
+								taskENTER_CRITICAL();
+								{
+									vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder );
+								}
+								taskEXIT_CRITICAL();
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						#endif
+
+						vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait );
+						portYIELD_WITHIN_API();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					taskEXIT_CRITICAL();
+					traceQUEUE_RECEIVE_FAILED( pxQueue );
+					return errQUEUE_EMPTY;
+				}
+			}
+			taskEXIT_CRITICAL();
+		}
+	}
+
+
+#endif /* configUSE_ALTERNATIVE_API */
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueGenericSendFromISR( QueueHandle_t xQueue, const void * const pvItemToQueue, BaseType_t * const pxHigherPriorityTaskWoken, const BaseType_t xCopyPosition )
+{
+BaseType_t xReturn;
+UBaseType_t uxSavedInterruptStatus;
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	configASSERT( pxQueue );
+	configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) );
+	configASSERT( !( ( xCopyPosition == queueOVERWRITE ) && ( pxQueue->uxLength != 1 ) ) );
+
+	/* RTOS ports that support interrupt nesting have the concept of a maximum
+	system call (or maximum API call) interrupt priority.  Interrupts that are
+	above the maximum system call priority are kept permanently enabled, even
+	when the RTOS kernel is in a critical section, but cannot make any calls to
+	FreeRTOS API functions.  If configASSERT() is defined in FreeRTOSConfig.h
+	then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+	failure if a FreeRTOS API function is called from an interrupt that has been
+	assigned a priority above the configured maximum system call priority.
+	Only FreeRTOS functions that end in FromISR can be called from interrupts
+	that have been assigned a priority at or (logically) below the maximum
+	system call	interrupt priority.  FreeRTOS maintains a separate interrupt
+	safe API to ensure interrupt entry is as fast and as simple as possible.
+	More information (albeit Cortex-M specific) is provided on the following
+	link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+	portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+	/* Similar to xQueueGenericSend, except without blocking if there is no room
+	in the queue.  Also don't directly wake a task that was blocked on a queue
+	read, instead return a flag to say whether a context switch is required or
+	not (i.e. has a task with a higher priority than us been woken by this
+	post). */
+	uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		if( ( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) || ( xCopyPosition == queueOVERWRITE ) )
+		{
+			traceQUEUE_SEND_FROM_ISR( pxQueue );
+
+			/* Semaphores use xQueueGiveFromISR(), so pxQueue will not be a
+			semaphore or mutex.  That means prvCopyDataToQueue() cannot result
+			in a task disinheriting a priority and prvCopyDataToQueue() can be
+			called here even though the disinherit function does not check if
+			the scheduler is suspended before accessing the ready lists. */
+			( void ) prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition );
+
+			/* The event list is not altered if the queue is locked.  This will
+			be done when the queue is unlocked later. */
+			if( pxQueue->xTxLock == queueUNLOCKED )
+			{
+				#if ( configUSE_QUEUE_SETS == 1 )
+				{
+					if( pxQueue->pxQueueSetContainer != NULL )
+					{
+						if( prvNotifyQueueSetContainer( pxQueue, xCopyPosition ) == pdTRUE )
+						{
+							/* The queue is a member of a queue set, and posting
+							to the queue set caused a higher priority task to
+							unblock.  A context switch is required. */
+							if( pxHigherPriorityTaskWoken != NULL )
+							{
+								*pxHigherPriorityTaskWoken = pdTRUE;
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+						{
+							if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+							{
+								/* The task waiting has a higher priority so
+								record that a context switch is required. */
+								if( pxHigherPriorityTaskWoken != NULL )
+								{
+									*pxHigherPriorityTaskWoken = pdTRUE;
+								}
+								else
+								{
+									mtCOVERAGE_TEST_MARKER();
+								}
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+				}
+				#else /* configUSE_QUEUE_SETS */
+				{
+					if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+					{
+						if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+						{
+							/* The task waiting has a higher priority so record that a
+							context	switch is required. */
+							if( pxHigherPriorityTaskWoken != NULL )
+							{
+								*pxHigherPriorityTaskWoken = pdTRUE;
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				#endif /* configUSE_QUEUE_SETS */
+			}
+			else
+			{
+				/* Increment the lock count so the task that unlocks the queue
+				knows that data was posted while it was locked. */
+				++( pxQueue->xTxLock );
+			}
+
+			xReturn = pdPASS;
+		}
+		else
+		{
+			traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue );
+			xReturn = errQUEUE_FULL;
+		}
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueGiveFromISR( QueueHandle_t xQueue, BaseType_t * const pxHigherPriorityTaskWoken )
+{
+BaseType_t xReturn;
+UBaseType_t uxSavedInterruptStatus;
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	/* Similar to xQueueGenericSendFromISR() but used with semaphores where the
+	item size is 0.  Don't directly wake a task that was blocked on a queue
+	read, instead return a flag to say whether a context switch is required or
+	not (i.e. has a task with a higher priority than us been woken by this
+	post). */
+
+	configASSERT( pxQueue );
+
+	/* xQueueGenericSendFromISR() should be used instead of xQueueGiveFromISR()
+	if the item size is not 0. */
+	configASSERT( pxQueue->uxItemSize == 0 );
+
+	/* Normally a mutex would not be given from an interrupt, especially if
+	there is a mutex holder, as priority inheritance makes no sense for an
+	interrupts, only tasks. */
+	configASSERT( !( ( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) && ( pxQueue->pxMutexHolder != NULL ) ) );
+
+	/* RTOS ports that support interrupt nesting have the concept of a maximum
+	system call (or maximum API call) interrupt priority.  Interrupts that are
+	above the maximum system call priority are kept permanently enabled, even
+	when the RTOS kernel is in a critical section, but cannot make any calls to
+	FreeRTOS API functions.  If configASSERT() is defined in FreeRTOSConfig.h
+	then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+	failure if a FreeRTOS API function is called from an interrupt that has been
+	assigned a priority above the configured maximum system call priority.
+	Only FreeRTOS functions that end in FromISR can be called from interrupts
+	that have been assigned a priority at or (logically) below the maximum
+	system call	interrupt priority.  FreeRTOS maintains a separate interrupt
+	safe API to ensure interrupt entry is as fast and as simple as possible.
+	More information (albeit Cortex-M specific) is provided on the following
+	link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+	portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+	uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		/* When the queue is used to implement a semaphore no data is ever
+		moved through the queue but it is still valid to see if the queue 'has
+		space'. */
+		if( pxQueue->uxMessagesWaiting < pxQueue->uxLength )
+		{
+			traceQUEUE_SEND_FROM_ISR( pxQueue );
+
+			/* A task can only have an inherited priority if it is a mutex
+			holder - and if there is a mutex holder then the mutex cannot be
+			given from an ISR.  As this is the ISR version of the function it
+			can be assumed there is no mutex holder and no need to determine if
+			priority disinheritance is needed.  Simply increase the count of
+			messages (semaphores) available. */
+			++( pxQueue->uxMessagesWaiting );
+
+			/* The event list is not altered if the queue is locked.  This will
+			be done when the queue is unlocked later. */
+			if( pxQueue->xTxLock == queueUNLOCKED )
+			{
+				#if ( configUSE_QUEUE_SETS == 1 )
+				{
+					if( pxQueue->pxQueueSetContainer != NULL )
+					{
+						if( prvNotifyQueueSetContainer( pxQueue, queueSEND_TO_BACK ) == pdTRUE )
+						{
+							/* The semaphore is a member of a queue set, and
+							posting	to the queue set caused a higher priority
+							task to	unblock.  A context switch is required. */
+							if( pxHigherPriorityTaskWoken != NULL )
+							{
+								*pxHigherPriorityTaskWoken = pdTRUE;
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+						{
+							if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+							{
+								/* The task waiting has a higher priority so
+								record that a context switch is required. */
+								if( pxHigherPriorityTaskWoken != NULL )
+								{
+									*pxHigherPriorityTaskWoken = pdTRUE;
+								}
+								else
+								{
+									mtCOVERAGE_TEST_MARKER();
+								}
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+				}
+				#else /* configUSE_QUEUE_SETS */
+				{
+					if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+					{
+						if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+						{
+							/* The task waiting has a higher priority so record that a
+							context	switch is required. */
+							if( pxHigherPriorityTaskWoken != NULL )
+							{
+								*pxHigherPriorityTaskWoken = pdTRUE;
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				#endif /* configUSE_QUEUE_SETS */
+			}
+			else
+			{
+				/* Increment the lock count so the task that unlocks the queue
+				knows that data was posted while it was locked. */
+				++( pxQueue->xTxLock );
+			}
+
+			xReturn = pdPASS;
+		}
+		else
+		{
+			traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue );
+			xReturn = errQUEUE_FULL;
+		}
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueGenericReceive( QueueHandle_t xQueue, void * const pvBuffer, TickType_t xTicksToWait, const BaseType_t xJustPeeking )
+{
+BaseType_t xEntryTimeSet = pdFALSE;
+TimeOut_t xTimeOut;
+int8_t *pcOriginalReadPosition;
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	configASSERT( pxQueue );
+	configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) );
+	#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) )
+	{
+		configASSERT( !( ( xTaskGetSchedulerState() == taskSCHEDULER_SUSPENDED ) && ( xTicksToWait != 0 ) ) );
+	}
+	#endif
+
+	/* This function relaxes the coding standard somewhat to allow return
+	statements within the function itself.  This is done in the interest
+	of execution time efficiency. */
+
+	for( ;; )
+	{
+		taskENTER_CRITICAL();
+		{
+			/* Is there data in the queue now?  To be running the calling task
+			must be	the highest priority task wanting to access the queue. */
+			if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 )
+			{
+				/* Remember the read position in case the queue is only being
+				peeked. */
+				pcOriginalReadPosition = pxQueue->u.pcReadFrom;
+
+				prvCopyDataFromQueue( pxQueue, pvBuffer );
+
+				if( xJustPeeking == pdFALSE )
+				{
+					traceQUEUE_RECEIVE( pxQueue );
+
+					/* Actually removing data, not just peeking. */
+					--( pxQueue->uxMessagesWaiting );
+
+					#if ( configUSE_MUTEXES == 1 )
+					{
+						if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX )
+						{
+							/* Record the information required to implement
+							priority inheritance should it become necessary. */
+							pxQueue->pxMutexHolder = ( int8_t * ) pvTaskIncrementMutexHeldCount(); /*lint !e961 Cast is not redundant as TaskHandle_t is a typedef. */
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					#endif /* configUSE_MUTEXES */
+
+					if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE )
+					{
+						if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE )
+						{
+							queueYIELD_IF_USING_PREEMPTION();
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					traceQUEUE_PEEK( pxQueue );
+
+					/* The data is not being removed, so reset the read
+					pointer. */
+					pxQueue->u.pcReadFrom = pcOriginalReadPosition;
+
+					/* The data is being left in the queue, so see if there are
+					any other tasks waiting for the data. */
+					if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+					{
+						if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+						{
+							/* The task waiting has a higher priority than this task. */
+							queueYIELD_IF_USING_PREEMPTION();
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+
+				taskEXIT_CRITICAL();
+				return pdPASS;
+			}
+			else
+			{
+				if( xTicksToWait == ( TickType_t ) 0 )
+				{
+					/* The queue was empty and no block time is specified (or
+					the block time has expired) so leave now. */
+					taskEXIT_CRITICAL();
+					traceQUEUE_RECEIVE_FAILED( pxQueue );
+					return errQUEUE_EMPTY;
+				}
+				else if( xEntryTimeSet == pdFALSE )
+				{
+					/* The queue was empty and a block time was specified so
+					configure the timeout structure. */
+					vTaskSetTimeOutState( &xTimeOut );
+					xEntryTimeSet = pdTRUE;
+				}
+				else
+				{
+					/* Entry time was already set. */
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		/* Interrupts and other tasks can send to and receive from the queue
+		now the critical section has been exited. */
+
+		vTaskSuspendAll();
+		prvLockQueue( pxQueue );
+
+		/* Update the timeout state to see if it has expired yet. */
+		if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE )
+		{
+			if( prvIsQueueEmpty( pxQueue ) != pdFALSE )
+			{
+				traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue );
+
+				#if ( configUSE_MUTEXES == 1 )
+				{
+					if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX )
+					{
+						taskENTER_CRITICAL();
+						{
+							vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder );
+						}
+						taskEXIT_CRITICAL();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				#endif
+
+				vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait );
+				prvUnlockQueue( pxQueue );
+				if( xTaskResumeAll() == pdFALSE )
+				{
+					portYIELD_WITHIN_API();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				/* Try again. */
+				prvUnlockQueue( pxQueue );
+				( void ) xTaskResumeAll();
+			}
+		}
+		else
+		{
+			prvUnlockQueue( pxQueue );
+			( void ) xTaskResumeAll();
+			traceQUEUE_RECEIVE_FAILED( pxQueue );
+			return errQUEUE_EMPTY;
+		}
+	}
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueReceiveFromISR( QueueHandle_t xQueue, void * const pvBuffer, BaseType_t * const pxHigherPriorityTaskWoken )
+{
+BaseType_t xReturn;
+UBaseType_t uxSavedInterruptStatus;
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	configASSERT( pxQueue );
+	configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) );
+
+	/* RTOS ports that support interrupt nesting have the concept of a maximum
+	system call (or maximum API call) interrupt priority.  Interrupts that are
+	above the maximum system call priority are kept permanently enabled, even
+	when the RTOS kernel is in a critical section, but cannot make any calls to
+	FreeRTOS API functions.  If configASSERT() is defined in FreeRTOSConfig.h
+	then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+	failure if a FreeRTOS API function is called from an interrupt that has been
+	assigned a priority above the configured maximum system call priority.
+	Only FreeRTOS functions that end in FromISR can be called from interrupts
+	that have been assigned a priority at or (logically) below the maximum
+	system call	interrupt priority.  FreeRTOS maintains a separate interrupt
+	safe API to ensure interrupt entry is as fast and as simple as possible.
+	More information (albeit Cortex-M specific) is provided on the following
+	link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+	portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+	uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		/* Cannot block in an ISR, so check there is data available. */
+		if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 )
+		{
+			traceQUEUE_RECEIVE_FROM_ISR( pxQueue );
+
+			prvCopyDataFromQueue( pxQueue, pvBuffer );
+			--( pxQueue->uxMessagesWaiting );
+
+			/* If the queue is locked the event list will not be modified.
+			Instead update the lock count so the task that unlocks the queue
+			will know that an ISR has removed data while the queue was
+			locked. */
+			if( pxQueue->xRxLock == queueUNLOCKED )
+			{
+				if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE )
+				{
+					if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE )
+					{
+						/* The task waiting has a higher priority than us so
+						force a context switch. */
+						if( pxHigherPriorityTaskWoken != NULL )
+						{
+							*pxHigherPriorityTaskWoken = pdTRUE;
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				/* Increment the lock count so the task that unlocks the queue
+				knows that data was removed while it was locked. */
+				++( pxQueue->xRxLock );
+			}
+
+			xReturn = pdPASS;
+		}
+		else
+		{
+			xReturn = pdFAIL;
+			traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue );
+		}
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueuePeekFromISR( QueueHandle_t xQueue,  void * const pvBuffer )
+{
+BaseType_t xReturn;
+UBaseType_t uxSavedInterruptStatus;
+int8_t *pcOriginalReadPosition;
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	configASSERT( pxQueue );
+	configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( UBaseType_t ) 0U ) ) );
+	configASSERT( pxQueue->uxItemSize != 0 ); /* Can't peek a semaphore. */
+
+	/* RTOS ports that support interrupt nesting have the concept of a maximum
+	system call (or maximum API call) interrupt priority.  Interrupts that are
+	above the maximum system call priority are kept permanently enabled, even
+	when the RTOS kernel is in a critical section, but cannot make any calls to
+	FreeRTOS API functions.  If configASSERT() is defined in FreeRTOSConfig.h
+	then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+	failure if a FreeRTOS API function is called from an interrupt that has been
+	assigned a priority above the configured maximum system call priority.
+	Only FreeRTOS functions that end in FromISR can be called from interrupts
+	that have been assigned a priority at or (logically) below the maximum
+	system call	interrupt priority.  FreeRTOS maintains a separate interrupt
+	safe API to ensure interrupt entry is as fast and as simple as possible.
+	More information (albeit Cortex-M specific) is provided on the following
+	link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+	portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+	uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		/* Cannot block in an ISR, so check there is data available. */
+		if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 )
+		{
+			traceQUEUE_PEEK_FROM_ISR( pxQueue );
+
+			/* Remember the read position so it can be reset as nothing is
+			actually being removed from the queue. */
+			pcOriginalReadPosition = pxQueue->u.pcReadFrom;
+			prvCopyDataFromQueue( pxQueue, pvBuffer );
+			pxQueue->u.pcReadFrom = pcOriginalReadPosition;
+
+			xReturn = pdPASS;
+		}
+		else
+		{
+			xReturn = pdFAIL;
+			traceQUEUE_PEEK_FROM_ISR_FAILED( pxQueue );
+		}
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+UBaseType_t uxQueueMessagesWaiting( const QueueHandle_t xQueue )
+{
+UBaseType_t uxReturn;
+
+	configASSERT( xQueue );
+
+	taskENTER_CRITICAL();
+	{
+		uxReturn = ( ( Queue_t * ) xQueue )->uxMessagesWaiting;
+	}
+	taskEXIT_CRITICAL();
+
+	return uxReturn;
+} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */
+/*-----------------------------------------------------------*/
+
+UBaseType_t uxQueueSpacesAvailable( const QueueHandle_t xQueue )
+{
+UBaseType_t uxReturn;
+Queue_t *pxQueue;
+
+	pxQueue = ( Queue_t * ) xQueue;
+	configASSERT( pxQueue );
+
+	taskENTER_CRITICAL();
+	{
+		uxReturn = pxQueue->uxLength - pxQueue->uxMessagesWaiting;
+	}
+	taskEXIT_CRITICAL();
+
+	return uxReturn;
+} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */
+/*-----------------------------------------------------------*/
+
+UBaseType_t uxQueueMessagesWaitingFromISR( const QueueHandle_t xQueue )
+{
+UBaseType_t uxReturn;
+
+	configASSERT( xQueue );
+
+	uxReturn = ( ( Queue_t * ) xQueue )->uxMessagesWaiting;
+
+	return uxReturn;
+} /*lint !e818 Pointer cannot be declared const as xQueue is a typedef not pointer. */
+/*-----------------------------------------------------------*/
+
+void vQueueDelete( QueueHandle_t xQueue )
+{
+Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+	configASSERT( pxQueue );
+
+	traceQUEUE_DELETE( pxQueue );
+	#if ( configQUEUE_REGISTRY_SIZE > 0 )
+	{
+		vQueueUnregisterQueue( pxQueue );
+	}
+	#endif
+	vPortFree( pxQueue );
+}
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	UBaseType_t uxQueueGetQueueNumber( QueueHandle_t xQueue )
+	{
+		return ( ( Queue_t * ) xQueue )->uxQueueNumber;
+	}
+
+#endif /* configUSE_TRACE_FACILITY */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	void vQueueSetQueueNumber( QueueHandle_t xQueue, UBaseType_t uxQueueNumber )
+	{
+		( ( Queue_t * ) xQueue )->uxQueueNumber = uxQueueNumber;
+	}
+
+#endif /* configUSE_TRACE_FACILITY */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	uint8_t ucQueueGetQueueType( QueueHandle_t xQueue )
+	{
+		return ( ( Queue_t * ) xQueue )->ucQueueType;
+	}
+
+#endif /* configUSE_TRACE_FACILITY */
+/*-----------------------------------------------------------*/
+
+static BaseType_t prvCopyDataToQueue( Queue_t * const pxQueue, const void *pvItemToQueue, const BaseType_t xPosition )
+{
+BaseType_t xReturn = pdFALSE;
+
+	if( pxQueue->uxItemSize == ( UBaseType_t ) 0 )
+	{
+		#if ( configUSE_MUTEXES == 1 )
+		{
+			if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX )
+			{
+				/* The mutex is no longer being held. */
+				xReturn = xTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder );
+				pxQueue->pxMutexHolder = NULL;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		#endif /* configUSE_MUTEXES */
+	}
+	else if( xPosition == queueSEND_TO_BACK )
+	{
+		( void ) memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e418 MISRA exception as the casts are only redundant for some ports, plus previous logic ensures a null pointer can only be passed to memcpy() if the copy size is 0. */
+		pxQueue->pcWriteTo += pxQueue->uxItemSize;
+		if( pxQueue->pcWriteTo >= pxQueue->pcTail ) /*lint !e946 MISRA exception justified as comparison of pointers is the cleanest solution. */
+		{
+			pxQueue->pcWriteTo = pxQueue->pcHead;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	else
+	{
+		( void ) memcpy( ( void * ) pxQueue->u.pcReadFrom, pvItemToQueue, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+		pxQueue->u.pcReadFrom -= pxQueue->uxItemSize;
+		if( pxQueue->u.pcReadFrom < pxQueue->pcHead ) /*lint !e946 MISRA exception justified as comparison of pointers is the cleanest solution. */
+		{
+			pxQueue->u.pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize );
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		if( xPosition == queueOVERWRITE )
+		{
+			if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 )
+			{
+				/* An item is not being added but overwritten, so subtract
+				one from the recorded number of items in the queue so when
+				one is added again below the number of recorded items remains
+				correct. */
+				--( pxQueue->uxMessagesWaiting );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+	++( pxQueue->uxMessagesWaiting );
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+static void prvCopyDataFromQueue( Queue_t * const pxQueue, void * const pvBuffer )
+{
+	if( pxQueue->uxItemSize != ( UBaseType_t ) 0 )
+	{
+		pxQueue->u.pcReadFrom += pxQueue->uxItemSize;
+		if( pxQueue->u.pcReadFrom >= pxQueue->pcTail ) /*lint !e946 MISRA exception justified as use of the relational operator is the cleanest solutions. */
+		{
+			pxQueue->u.pcReadFrom = pxQueue->pcHead;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+		( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.pcReadFrom, ( size_t ) pxQueue->uxItemSize ); /*lint !e961 !e418 MISRA exception as the casts are only redundant for some ports.  Also previous logic ensures a null pointer can only be passed to memcpy() when the count is 0. */
+	}
+}
+/*-----------------------------------------------------------*/
+
+static void prvUnlockQueue( Queue_t * const pxQueue )
+{
+	/* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */
+
+	/* The lock counts contains the number of extra data items placed or
+	removed from the queue while the queue was locked.  When a queue is
+	locked items can be added or removed, but the event lists cannot be
+	updated. */
+	taskENTER_CRITICAL();
+	{
+		/* See if data was added to the queue while it was locked. */
+		while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED )
+		{
+			/* Data was posted while the queue was locked.  Are any tasks
+			blocked waiting for data to become available? */
+			#if ( configUSE_QUEUE_SETS == 1 )
+			{
+				if( pxQueue->pxQueueSetContainer != NULL )
+				{
+					if( prvNotifyQueueSetContainer( pxQueue, queueSEND_TO_BACK ) == pdTRUE )
+					{
+						/* The queue is a member of a queue set, and posting to
+						the queue set caused a higher priority task to unblock.
+						A context switch is required. */
+						vTaskMissedYield();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					/* Tasks that are removed from the event list will get added to
+					the pending ready list as the scheduler is still suspended. */
+					if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+					{
+						if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+						{
+							/* The task waiting has a higher priority so record that a
+							context	switch is required. */
+							vTaskMissedYield();
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						break;
+					}
+				}
+			}
+			#else /* configUSE_QUEUE_SETS */
+			{
+				/* Tasks that are removed from the event list will get added to
+				the pending ready list as the scheduler is still suspended. */
+				if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+				{
+					if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+					{
+						/* The task waiting has a higher priority so record that a
+						context	switch is required. */
+						vTaskMissedYield();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					break;
+				}
+			}
+			#endif /* configUSE_QUEUE_SETS */
+
+			--( pxQueue->xTxLock );
+		}
+
+		pxQueue->xTxLock = queueUNLOCKED;
+	}
+	taskEXIT_CRITICAL();
+
+	/* Do the same for the Rx lock. */
+	taskENTER_CRITICAL();
+	{
+		while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED )
+		{
+			if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE )
+			{
+				if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE )
+				{
+					vTaskMissedYield();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				--( pxQueue->xRxLock );
+			}
+			else
+			{
+				break;
+			}
+		}
+
+		pxQueue->xRxLock = queueUNLOCKED;
+	}
+	taskEXIT_CRITICAL();
+}
+/*-----------------------------------------------------------*/
+
+static BaseType_t prvIsQueueEmpty( const Queue_t *pxQueue )
+{
+BaseType_t xReturn;
+
+	taskENTER_CRITICAL();
+	{
+		if( pxQueue->uxMessagesWaiting == ( UBaseType_t )  0 )
+		{
+			xReturn = pdTRUE;
+		}
+		else
+		{
+			xReturn = pdFALSE;
+		}
+	}
+	taskEXIT_CRITICAL();
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueIsQueueEmptyFromISR( const QueueHandle_t xQueue )
+{
+BaseType_t xReturn;
+
+	configASSERT( xQueue );
+	if( ( ( Queue_t * ) xQueue )->uxMessagesWaiting == ( UBaseType_t ) 0 )
+	{
+		xReturn = pdTRUE;
+	}
+	else
+	{
+		xReturn = pdFALSE;
+	}
+
+	return xReturn;
+} /*lint !e818 xQueue could not be pointer to const because it is a typedef. */
+/*-----------------------------------------------------------*/
+
+static BaseType_t prvIsQueueFull( const Queue_t *pxQueue )
+{
+BaseType_t xReturn;
+
+	taskENTER_CRITICAL();
+	{
+		if( pxQueue->uxMessagesWaiting == pxQueue->uxLength )
+		{
+			xReturn = pdTRUE;
+		}
+		else
+		{
+			xReturn = pdFALSE;
+		}
+	}
+	taskEXIT_CRITICAL();
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xQueueIsQueueFullFromISR( const QueueHandle_t xQueue )
+{
+BaseType_t xReturn;
+
+	configASSERT( xQueue );
+	if( ( ( Queue_t * ) xQueue )->uxMessagesWaiting == ( ( Queue_t * ) xQueue )->uxLength )
+	{
+		xReturn = pdTRUE;
+	}
+	else
+	{
+		xReturn = pdFALSE;
+	}
+
+	return xReturn;
+} /*lint !e818 xQueue could not be pointer to const because it is a typedef. */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_CO_ROUTINES == 1 )
+
+	BaseType_t xQueueCRSend( QueueHandle_t xQueue, const void *pvItemToQueue, TickType_t xTicksToWait )
+	{
+	BaseType_t xReturn;
+	Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+		/* If the queue is already full we may have to block.  A critical section
+		is required to prevent an interrupt removing something from the queue
+		between the check to see if the queue is full and blocking on the queue. */
+		portDISABLE_INTERRUPTS();
+		{
+			if( prvIsQueueFull( pxQueue ) != pdFALSE )
+			{
+				/* The queue is full - do we want to block or just leave without
+				posting? */
+				if( xTicksToWait > ( TickType_t ) 0 )
+				{
+					/* As this is called from a coroutine we cannot block directly, but
+					return indicating that we need to block. */
+					vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) );
+					portENABLE_INTERRUPTS();
+					return errQUEUE_BLOCKED;
+				}
+				else
+				{
+					portENABLE_INTERRUPTS();
+					return errQUEUE_FULL;
+				}
+			}
+		}
+		portENABLE_INTERRUPTS();
+
+		portDISABLE_INTERRUPTS();
+		{
+			if( pxQueue->uxMessagesWaiting < pxQueue->uxLength )
+			{
+				/* There is room in the queue, copy the data into the queue. */
+				prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK );
+				xReturn = pdPASS;
+
+				/* Were any co-routines waiting for data to become available? */
+				if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+				{
+					/* In this instance the co-routine could be placed directly
+					into the ready list as we are within a critical section.
+					Instead the same pending ready list mechanism is used as if
+					the event were caused from within an interrupt. */
+					if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+					{
+						/* The co-routine waiting has a higher priority so record
+						that a yield might be appropriate. */
+						xReturn = errQUEUE_YIELD;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				xReturn = errQUEUE_FULL;
+			}
+		}
+		portENABLE_INTERRUPTS();
+
+		return xReturn;
+	}
+
+#endif /* configUSE_CO_ROUTINES */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_CO_ROUTINES == 1 )
+
+	BaseType_t xQueueCRReceive( QueueHandle_t xQueue, void *pvBuffer, TickType_t xTicksToWait )
+	{
+	BaseType_t xReturn;
+	Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+		/* If the queue is already empty we may have to block.  A critical section
+		is required to prevent an interrupt adding something to the queue
+		between the check to see if the queue is empty and blocking on the queue. */
+		portDISABLE_INTERRUPTS();
+		{
+			if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0 )
+			{
+				/* There are no messages in the queue, do we want to block or just
+				leave with nothing? */
+				if( xTicksToWait > ( TickType_t ) 0 )
+				{
+					/* As this is a co-routine we cannot block directly, but return
+					indicating that we need to block. */
+					vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) );
+					portENABLE_INTERRUPTS();
+					return errQUEUE_BLOCKED;
+				}
+				else
+				{
+					portENABLE_INTERRUPTS();
+					return errQUEUE_FULL;
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		portENABLE_INTERRUPTS();
+
+		portDISABLE_INTERRUPTS();
+		{
+			if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 )
+			{
+				/* Data is available from the queue. */
+				pxQueue->u.pcReadFrom += pxQueue->uxItemSize;
+				if( pxQueue->u.pcReadFrom >= pxQueue->pcTail )
+				{
+					pxQueue->u.pcReadFrom = pxQueue->pcHead;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+				--( pxQueue->uxMessagesWaiting );
+				( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.pcReadFrom, ( unsigned ) pxQueue->uxItemSize );
+
+				xReturn = pdPASS;
+
+				/* Were any co-routines waiting for space to become available? */
+				if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE )
+				{
+					/* In this instance the co-routine could be placed directly
+					into the ready list as we are within a critical section.
+					Instead the same pending ready list mechanism is used as if
+					the event were caused from within an interrupt. */
+					if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE )
+					{
+						xReturn = errQUEUE_YIELD;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				xReturn = pdFAIL;
+			}
+		}
+		portENABLE_INTERRUPTS();
+
+		return xReturn;
+	}
+
+#endif /* configUSE_CO_ROUTINES */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_CO_ROUTINES == 1 )
+
+	BaseType_t xQueueCRSendFromISR( QueueHandle_t xQueue, const void *pvItemToQueue, BaseType_t xCoRoutinePreviouslyWoken )
+	{
+	Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+		/* Cannot block within an ISR so if there is no space on the queue then
+		exit without doing anything. */
+		if( pxQueue->uxMessagesWaiting < pxQueue->uxLength )
+		{
+			prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK );
+
+			/* We only want to wake one co-routine per ISR, so check that a
+			co-routine has not already been woken. */
+			if( xCoRoutinePreviouslyWoken == pdFALSE )
+			{
+				if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE )
+				{
+					if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE )
+					{
+						return pdTRUE;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		return xCoRoutinePreviouslyWoken;
+	}
+
+#endif /* configUSE_CO_ROUTINES */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_CO_ROUTINES == 1 )
+
+	BaseType_t xQueueCRReceiveFromISR( QueueHandle_t xQueue, void *pvBuffer, BaseType_t *pxCoRoutineWoken )
+	{
+	BaseType_t xReturn;
+	Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+		/* We cannot block from an ISR, so check there is data available. If
+		not then just leave without doing anything. */
+		if( pxQueue->uxMessagesWaiting > ( UBaseType_t ) 0 )
+		{
+			/* Copy the data from the queue. */
+			pxQueue->u.pcReadFrom += pxQueue->uxItemSize;
+			if( pxQueue->u.pcReadFrom >= pxQueue->pcTail )
+			{
+				pxQueue->u.pcReadFrom = pxQueue->pcHead;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+			--( pxQueue->uxMessagesWaiting );
+			( void ) memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->u.pcReadFrom, ( unsigned ) pxQueue->uxItemSize );
+
+			if( ( *pxCoRoutineWoken ) == pdFALSE )
+			{
+				if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE )
+				{
+					if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE )
+					{
+						*pxCoRoutineWoken = pdTRUE;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			xReturn = pdPASS;
+		}
+		else
+		{
+			xReturn = pdFAIL;
+		}
+
+		return xReturn;
+	}
+
+#endif /* configUSE_CO_ROUTINES */
+/*-----------------------------------------------------------*/
+
+#if ( configQUEUE_REGISTRY_SIZE > 0 )
+
+	void vQueueAddToRegistry( QueueHandle_t xQueue, const char *pcQueueName ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+	{
+	UBaseType_t ux;
+
+		/* See if there is an empty space in the registry.  A NULL name denotes
+		a free slot. */
+		for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ )
+		{
+			if( xQueueRegistry[ ux ].pcQueueName == NULL )
+			{
+				/* Store the information on this queue. */
+				xQueueRegistry[ ux ].pcQueueName = pcQueueName;
+				xQueueRegistry[ ux ].xHandle = xQueue;
+
+				traceQUEUE_REGISTRY_ADD( xQueue, pcQueueName );
+				break;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+	}
+
+#endif /* configQUEUE_REGISTRY_SIZE */
+/*-----------------------------------------------------------*/
+
+#if ( configQUEUE_REGISTRY_SIZE > 0 )
+
+	void vQueueUnregisterQueue( QueueHandle_t xQueue )
+	{
+	UBaseType_t ux;
+
+		/* See if the handle of the queue being unregistered in actually in the
+		registry. */
+		for( ux = ( UBaseType_t ) 0U; ux < ( UBaseType_t ) configQUEUE_REGISTRY_SIZE; ux++ )
+		{
+			if( xQueueRegistry[ ux ].xHandle == xQueue )
+			{
+				/* Set the name to NULL to show that this slot if free again. */
+				xQueueRegistry[ ux ].pcQueueName = NULL;
+				break;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+
+	} /*lint !e818 xQueue could not be pointer to const because it is a typedef. */
+
+#endif /* configQUEUE_REGISTRY_SIZE */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TIMERS == 1 )
+
+	void vQueueWaitForMessageRestricted( QueueHandle_t xQueue, TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely )
+	{
+	Queue_t * const pxQueue = ( Queue_t * ) xQueue;
+
+		/* This function should not be called by application code hence the
+		'Restricted' in its name.  It is not part of the public API.  It is
+		designed for use by kernel code, and has special calling requirements.
+		It can result in vListInsert() being called on a list that can only
+		possibly ever have one item in it, so the list will be fast, but even
+		so it should be called with the scheduler locked and not from a critical
+		section. */
+
+		/* Only do anything if there are no messages in the queue.  This function
+		will not actually cause the task to block, just place it on a blocked
+		list.  It will not block until the scheduler is unlocked - at which
+		time a yield will be performed.  If an item is added to the queue while
+		the queue is locked, and the calling task blocks on the queue, then the
+		calling task will be immediately unblocked when the queue is unlocked. */
+		prvLockQueue( pxQueue );
+		if( pxQueue->uxMessagesWaiting == ( UBaseType_t ) 0U )
+		{
+			/* There is nothing in the queue, block for the specified period. */
+			vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait, xWaitIndefinitely );
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+		prvUnlockQueue( pxQueue );
+	}
+
+#endif /* configUSE_TIMERS */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_QUEUE_SETS == 1 )
+
+	QueueSetHandle_t xQueueCreateSet( const UBaseType_t uxEventQueueLength )
+	{
+	QueueSetHandle_t pxQueue;
+
+		pxQueue = xQueueGenericCreate( uxEventQueueLength, sizeof( Queue_t * ), queueQUEUE_TYPE_SET );
+
+		return pxQueue;
+	}
+
+#endif /* configUSE_QUEUE_SETS */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_QUEUE_SETS == 1 )
+
+	BaseType_t xQueueAddToSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet )
+	{
+	BaseType_t xReturn;
+
+		taskENTER_CRITICAL();
+		{
+			if( ( ( Queue_t * ) xQueueOrSemaphore )->pxQueueSetContainer != NULL )
+			{
+				/* Cannot add a queue/semaphore to more than one queue set. */
+				xReturn = pdFAIL;
+			}
+			else if( ( ( Queue_t * ) xQueueOrSemaphore )->uxMessagesWaiting != ( UBaseType_t ) 0 )
+			{
+				/* Cannot add a queue/semaphore to a queue set if there are already
+				items in the queue/semaphore. */
+				xReturn = pdFAIL;
+			}
+			else
+			{
+				( ( Queue_t * ) xQueueOrSemaphore )->pxQueueSetContainer = xQueueSet;
+				xReturn = pdPASS;
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		return xReturn;
+	}
+
+#endif /* configUSE_QUEUE_SETS */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_QUEUE_SETS == 1 )
+
+	BaseType_t xQueueRemoveFromSet( QueueSetMemberHandle_t xQueueOrSemaphore, QueueSetHandle_t xQueueSet )
+	{
+	BaseType_t xReturn;
+	Queue_t * const pxQueueOrSemaphore = ( Queue_t * ) xQueueOrSemaphore;
+
+		if( pxQueueOrSemaphore->pxQueueSetContainer != xQueueSet )
+		{
+			/* The queue was not a member of the set. */
+			xReturn = pdFAIL;
+		}
+		else if( pxQueueOrSemaphore->uxMessagesWaiting != ( UBaseType_t ) 0 )
+		{
+			/* It is dangerous to remove a queue from a set when the queue is
+			not empty because the queue set will still hold pending events for
+			the queue. */
+			xReturn = pdFAIL;
+		}
+		else
+		{
+			taskENTER_CRITICAL();
+			{
+				/* The queue is no longer contained in the set. */
+				pxQueueOrSemaphore->pxQueueSetContainer = NULL;
+			}
+			taskEXIT_CRITICAL();
+			xReturn = pdPASS;
+		}
+
+		return xReturn;
+	} /*lint !e818 xQueueSet could not be declared as pointing to const as it is a typedef. */
+
+#endif /* configUSE_QUEUE_SETS */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_QUEUE_SETS == 1 )
+
+	QueueSetMemberHandle_t xQueueSelectFromSet( QueueSetHandle_t xQueueSet, TickType_t const xTicksToWait )
+	{
+	QueueSetMemberHandle_t xReturn = NULL;
+
+		( void ) xQueueGenericReceive( ( QueueHandle_t ) xQueueSet, &xReturn, xTicksToWait, pdFALSE ); /*lint !e961 Casting from one typedef to another is not redundant. */
+		return xReturn;
+	}
+
+#endif /* configUSE_QUEUE_SETS */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_QUEUE_SETS == 1 )
+
+	QueueSetMemberHandle_t xQueueSelectFromSetFromISR( QueueSetHandle_t xQueueSet )
+	{
+	QueueSetMemberHandle_t xReturn = NULL;
+
+		( void ) xQueueReceiveFromISR( ( QueueHandle_t ) xQueueSet, &xReturn, NULL ); /*lint !e961 Casting from one typedef to another is not redundant. */
+		return xReturn;
+	}
+
+#endif /* configUSE_QUEUE_SETS */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_QUEUE_SETS == 1 )
+
+	static BaseType_t prvNotifyQueueSetContainer( const Queue_t * const pxQueue, const BaseType_t xCopyPosition )
+	{
+	Queue_t *pxQueueSetContainer = pxQueue->pxQueueSetContainer;
+	BaseType_t xReturn = pdFALSE;
+
+		/* This function must be called form a critical section. */
+
+		configASSERT( pxQueueSetContainer );
+		configASSERT( pxQueueSetContainer->uxMessagesWaiting < pxQueueSetContainer->uxLength );
+
+		if( pxQueueSetContainer->uxMessagesWaiting < pxQueueSetContainer->uxLength )
+		{
+			traceQUEUE_SEND( pxQueueSetContainer );
+
+			/* The data copied is the handle of the queue that contains data. */
+			xReturn = prvCopyDataToQueue( pxQueueSetContainer, &pxQueue, xCopyPosition );
+
+			if( pxQueueSetContainer->xTxLock == queueUNLOCKED )
+			{
+				if( listLIST_IS_EMPTY( &( pxQueueSetContainer->xTasksWaitingToReceive ) ) == pdFALSE )
+				{
+					if( xTaskRemoveFromEventList( &( pxQueueSetContainer->xTasksWaitingToReceive ) ) != pdFALSE )
+					{
+						/* The task waiting has a higher priority. */
+						xReturn = pdTRUE;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				( pxQueueSetContainer->xTxLock )++;
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		return xReturn;
+	}
+
+#endif /* configUSE_QUEUE_SETS */
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/tasks.c b/crazyflie-firmware-src/src/lib/FreeRTOS/tasks.c
new file mode 100644
index 0000000000000000000000000000000000000000..11ca0e976b9a5c5d697802e271a5cbe460c04194
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/tasks.c
@@ -0,0 +1,4477 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/* Standard includes. */
+#include <stdlib.h>
+#include <string.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+/* FreeRTOS includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "timers.h"
+#include "StackMacros.h"
+
+/* Lint e961 and e750 are suppressed as a MISRA exception justified because the
+MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined for the
+header files above, but not in this file, in order to generate the correct
+privileged Vs unprivileged linkage and placement. */
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750. */
+
+/* Set configUSE_STATS_FORMATTING_FUNCTIONS to 2 to include the stats formatting
+functions but without including stdio.h here. */
+#if ( configUSE_STATS_FORMATTING_FUNCTIONS == 1 )
+	/* At the bottom of this file are two optional functions that can be used
+	to generate human readable text from the raw data generated by the
+	uxTaskGetSystemState() function.  Note the formatting functions are provided
+	for convenience only, and are NOT considered part of the kernel. */
+	#include <stdio.h>
+#endif /* configUSE_STATS_FORMATTING_FUNCTIONS == 1 ) */
+
+/* Sanity check the configuration. */
+#if( configUSE_TICKLESS_IDLE != 0 )
+	#if( INCLUDE_vTaskSuspend != 1 )
+		#error INCLUDE_vTaskSuspend must be set to 1 if configUSE_TICKLESS_IDLE is not set to 0
+	#endif /* INCLUDE_vTaskSuspend */
+#endif /* configUSE_TICKLESS_IDLE */
+
+/*
+ * Defines the size, in words, of the stack allocated to the idle task.
+ */
+#define tskIDLE_STACK_SIZE	configMINIMAL_STACK_SIZE
+
+#if( configUSE_PREEMPTION == 0 )
+	/* If the cooperative scheduler is being used then a yield should not be
+	performed just because a higher priority task has been woken. */
+	#define taskYIELD_IF_USING_PREEMPTION()
+#else
+	#define taskYIELD_IF_USING_PREEMPTION() portYIELD_WITHIN_API()
+#endif
+
+/* Value that can be assigned to the eNotifyState member of the TCB. */
+typedef enum
+{
+	eNotWaitingNotification = 0,
+	eWaitingNotification,
+	eNotified
+} eNotifyValue;
+
+/*
+ * Task control block.  A task control block (TCB) is allocated for each task,
+ * and stores task state information, including a pointer to the task's context
+ * (the task's run time environment, including register values)
+ */
+typedef struct tskTaskControlBlock
+{
+	volatile StackType_t	*pxTopOfStack;	/*< Points to the location of the last item placed on the tasks stack.  THIS MUST BE THE FIRST MEMBER OF THE TCB STRUCT. */
+
+	#if ( portUSING_MPU_WRAPPERS == 1 )
+		xMPU_SETTINGS	xMPUSettings;		/*< The MPU settings are defined as part of the port layer.  THIS MUST BE THE SECOND MEMBER OF THE TCB STRUCT. */
+		BaseType_t		xUsingStaticallyAllocatedStack; /* Set to pdTRUE if the stack is a statically allocated array, and pdFALSE if the stack is dynamically allocated. */
+	#endif
+
+	ListItem_t			xGenericListItem;	/*< The list that the state list item of a task is reference from denotes the state of that task (Ready, Blocked, Suspended ). */
+	ListItem_t			xEventListItem;		/*< Used to reference a task from an event list. */
+	UBaseType_t			uxPriority;			/*< The priority of the task.  0 is the lowest priority. */
+	StackType_t			*pxStack;			/*< Points to the start of the stack. */
+	char				pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created.  Facilitates debugging only. */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+	#if ( portSTACK_GROWTH > 0 )
+		StackType_t		*pxEndOfStack;		/*< Points to the end of the stack on architectures where the stack grows up from low memory. */
+	#endif
+
+	#if ( portCRITICAL_NESTING_IN_TCB == 1 )
+		UBaseType_t 	uxCriticalNesting; 	/*< Holds the critical section nesting depth for ports that do not maintain their own count in the port layer. */
+	#endif
+
+	#if ( configUSE_TRACE_FACILITY == 1 )
+		UBaseType_t		uxTCBNumber;		/*< Stores a number that increments each time a TCB is created.  It allows debuggers to determine when a task has been deleted and then recreated. */
+		UBaseType_t  	uxTaskNumber;		/*< Stores a number specifically for use by third party trace code. */
+	#endif
+
+	#if ( configUSE_MUTEXES == 1 )
+		UBaseType_t 	uxBasePriority;		/*< The priority last assigned to the task - used by the priority inheritance mechanism. */
+		UBaseType_t 	uxMutexesHeld;
+	#endif
+
+	#if ( configUSE_APPLICATION_TASK_TAG == 1 )
+		TaskHookFunction_t pxTaskTag;
+	#endif
+
+	#if( configNUM_THREAD_LOCAL_STORAGE_POINTERS > 0 )
+		void *pvThreadLocalStoragePointers[ configNUM_THREAD_LOCAL_STORAGE_POINTERS ];
+	#endif
+
+	#if ( configGENERATE_RUN_TIME_STATS == 1 )
+		uint32_t		ulRunTimeCounter;	/*< Stores the amount of time the task has spent in the Running state. */
+	#endif
+
+	#if ( configUSE_NEWLIB_REENTRANT == 1 )
+		/* Allocate a Newlib reent structure that is specific to this task.
+		Note Newlib support has been included by popular demand, but is not
+		used by the FreeRTOS maintainers themselves.  FreeRTOS is not
+		responsible for resulting newlib operation.  User must be familiar with
+		newlib and must provide system-wide implementations of the necessary
+		stubs. Be warned that (at the time of writing) the current newlib design
+		implements a system-wide malloc() that must be provided with locks. */
+		struct 	_reent xNewLib_reent;
+	#endif
+
+	#if ( configUSE_TASK_NOTIFICATIONS == 1 )
+		volatile uint32_t ulNotifiedValue;
+		volatile eNotifyValue eNotifyState;
+	#endif
+
+} tskTCB;
+
+/* The old tskTCB name is maintained above then typedefed to the new TCB_t name
+below to enable the use of older kernel aware debuggers. */
+typedef tskTCB TCB_t;
+
+/*
+ * Some kernel aware debuggers require the data the debugger needs access to to
+ * be global, rather than file scope.
+ */
+#ifdef portREMOVE_STATIC_QUALIFIER
+	#define static
+#endif
+
+/*lint -e956 A manual analysis and inspection has been used to determine which
+static variables must be declared volatile. */
+
+PRIVILEGED_DATA TCB_t * volatile pxCurrentTCB = NULL;
+
+/* Lists for ready and blocked tasks. --------------------*/
+PRIVILEGED_DATA static List_t pxReadyTasksLists[ configMAX_PRIORITIES ];/*< Prioritised ready tasks. */
+PRIVILEGED_DATA static List_t xDelayedTaskList1;						/*< Delayed tasks. */
+PRIVILEGED_DATA static List_t xDelayedTaskList2;						/*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */
+PRIVILEGED_DATA static List_t * volatile pxDelayedTaskList;				/*< Points to the delayed task list currently being used. */
+PRIVILEGED_DATA static List_t * volatile pxOverflowDelayedTaskList;		/*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */
+PRIVILEGED_DATA static List_t xPendingReadyList;						/*< Tasks that have been readied while the scheduler was suspended.  They will be moved to the ready list when the scheduler is resumed. */
+
+#if ( INCLUDE_vTaskDelete == 1 )
+
+	PRIVILEGED_DATA static List_t xTasksWaitingTermination;				/*< Tasks that have been deleted - but their memory not yet freed. */
+	PRIVILEGED_DATA static volatile UBaseType_t uxTasksDeleted = ( UBaseType_t ) 0U;
+
+#endif
+
+#if ( INCLUDE_vTaskSuspend == 1 )
+
+	PRIVILEGED_DATA static List_t xSuspendedTaskList;					/*< Tasks that are currently suspended. */
+
+#endif
+
+#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 )
+
+	PRIVILEGED_DATA static TaskHandle_t xIdleTaskHandle = NULL;			/*< Holds the handle of the idle task.  The idle task is created automatically when the scheduler is started. */
+
+#endif
+
+/* Other file private variables. --------------------------------*/
+PRIVILEGED_DATA static volatile UBaseType_t uxCurrentNumberOfTasks 	= ( UBaseType_t ) 0U;
+PRIVILEGED_DATA static volatile TickType_t xTickCount 				= ( TickType_t ) 0U;
+PRIVILEGED_DATA static volatile UBaseType_t uxTopReadyPriority 		= tskIDLE_PRIORITY;
+PRIVILEGED_DATA static volatile BaseType_t xSchedulerRunning 		= pdFALSE;
+PRIVILEGED_DATA static volatile UBaseType_t uxPendedTicks 			= ( UBaseType_t ) 0U;
+PRIVILEGED_DATA static volatile BaseType_t xYieldPending 			= pdFALSE;
+PRIVILEGED_DATA static volatile BaseType_t xNumOfOverflows 			= ( BaseType_t ) 0;
+PRIVILEGED_DATA static UBaseType_t uxTaskNumber 					= ( UBaseType_t ) 0U;
+PRIVILEGED_DATA static volatile TickType_t xNextTaskUnblockTime		= ( TickType_t ) 0U; /* Initialised to portMAX_DELAY before the scheduler starts. */
+
+/* Context switches are held pending while the scheduler is suspended.  Also,
+interrupts must not manipulate the xGenericListItem of a TCB, or any of the
+lists the xGenericListItem can be referenced from, if the scheduler is suspended.
+If an interrupt needs to unblock a task while the scheduler is suspended then it
+moves the task's event list item into the xPendingReadyList, ready for the
+kernel to move the task from the pending ready list into the real ready list
+when the scheduler is unsuspended.  The pending ready list itself can only be
+accessed from a critical section. */
+PRIVILEGED_DATA static volatile UBaseType_t uxSchedulerSuspended	= ( UBaseType_t ) pdFALSE;
+
+#if ( configGENERATE_RUN_TIME_STATS == 1 )
+
+	PRIVILEGED_DATA static uint32_t ulTaskSwitchedInTime = 0UL;	/*< Holds the value of a timer/counter the last time a task was switched in. */
+	PRIVILEGED_DATA static uint32_t ulTotalRunTime = 0UL;		/*< Holds the total amount of execution time as defined by the run time counter clock. */
+
+#endif
+
+/*lint +e956 */
+
+/* Debugging and trace facilities private variables and macros. ------------*/
+
+/*
+ * The value used to fill the stack of a task when the task is created.  This
+ * is used purely for checking the high water mark for tasks.
+ */
+#define tskSTACK_FILL_BYTE	( 0xa5U )
+
+/*
+ * Macros used by vListTask to indicate which state a task is in.
+ */
+#define tskBLOCKED_CHAR		( 'B' )
+#define tskREADY_CHAR		( 'R' )
+#define tskDELETED_CHAR		( 'D' )
+#define tskSUSPENDED_CHAR	( 'S' )
+
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_PORT_OPTIMISED_TASK_SELECTION == 0 )
+
+	/* If configUSE_PORT_OPTIMISED_TASK_SELECTION is 0 then task selection is
+	performed in a generic way that is not optimised to any particular
+	microcontroller architecture. */
+
+	/* uxTopReadyPriority holds the priority of the highest priority ready
+	state task. */
+	#define taskRECORD_READY_PRIORITY( uxPriority )														\
+	{																									\
+		if( ( uxPriority ) > uxTopReadyPriority )														\
+		{																								\
+			uxTopReadyPriority = ( uxPriority );														\
+		}																								\
+	} /* taskRECORD_READY_PRIORITY */
+
+	/*-----------------------------------------------------------*/
+
+	#define taskSELECT_HIGHEST_PRIORITY_TASK()															\
+	{																									\
+		/* Find the highest priority queue that contains ready tasks. */								\
+		while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) )						\
+		{																								\
+			configASSERT( uxTopReadyPriority );															\
+			--uxTopReadyPriority;																		\
+		}																								\
+																										\
+		/* listGET_OWNER_OF_NEXT_ENTRY indexes through the list, so the tasks of						\
+		the	same priority get an equal share of the processor time. */									\
+		listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) );		\
+	} /* taskSELECT_HIGHEST_PRIORITY_TASK */
+
+	/*-----------------------------------------------------------*/
+
+	/* Define away taskRESET_READY_PRIORITY() and portRESET_READY_PRIORITY() as
+	they are only required when a port optimised method of task selection is
+	being used. */
+	#define taskRESET_READY_PRIORITY( uxPriority )
+	#define portRESET_READY_PRIORITY( uxPriority, uxTopReadyPriority )
+
+#else /* configUSE_PORT_OPTIMISED_TASK_SELECTION */
+
+	/* If configUSE_PORT_OPTIMISED_TASK_SELECTION is 1 then task selection is
+	performed in a way that is tailored to the particular microcontroller
+	architecture being used. */
+
+	/* A port optimised version is provided.  Call the port defined macros. */
+	#define taskRECORD_READY_PRIORITY( uxPriority )	portRECORD_READY_PRIORITY( uxPriority, uxTopReadyPriority )
+
+	/*-----------------------------------------------------------*/
+
+	#define taskSELECT_HIGHEST_PRIORITY_TASK()														\
+	{																								\
+	UBaseType_t uxTopPriority;																		\
+																									\
+		/* Find the highest priority queue that contains ready tasks. */							\
+		portGET_HIGHEST_PRIORITY( uxTopPriority, uxTopReadyPriority );								\
+		configASSERT( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ uxTopPriority ] ) ) > 0 );		\
+		listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopPriority ] ) );		\
+	} /* taskSELECT_HIGHEST_PRIORITY_TASK() */
+
+	/*-----------------------------------------------------------*/
+
+	/* A port optimised version is provided, call it only if the TCB being reset
+	is being referenced from a ready list.  If it is referenced from a delayed
+	or suspended list then it won't be in a ready list. */
+	#define taskRESET_READY_PRIORITY( uxPriority )														\
+	{																									\
+		if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ ( uxPriority ) ] ) ) == ( UBaseType_t ) 0 )	\
+		{																								\
+			portRESET_READY_PRIORITY( ( uxPriority ), ( uxTopReadyPriority ) );							\
+		}																								\
+	}
+
+#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */
+
+/*-----------------------------------------------------------*/
+
+/* pxDelayedTaskList and pxOverflowDelayedTaskList are switched when the tick
+count overflows. */
+#define taskSWITCH_DELAYED_LISTS()																	\
+{																									\
+	List_t *pxTemp;																					\
+																									\
+	/* The delayed tasks list should be empty when the lists are switched. */						\
+	configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) );										\
+																									\
+	pxTemp = pxDelayedTaskList;																		\
+	pxDelayedTaskList = pxOverflowDelayedTaskList;													\
+	pxOverflowDelayedTaskList = pxTemp;																\
+	xNumOfOverflows++;																				\
+	prvResetNextTaskUnblockTime();																	\
+}
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Place the task represented by pxTCB into the appropriate ready list for
+ * the task.  It is inserted at the end of the list.
+ */
+#define prvAddTaskToReadyList( pxTCB )																\
+	traceMOVED_TASK_TO_READY_STATE( pxTCB );														\
+	taskRECORD_READY_PRIORITY( ( pxTCB )->uxPriority );												\
+	vListInsertEnd( &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) )
+/*-----------------------------------------------------------*/
+
+/*
+ * Several functions take an TaskHandle_t parameter that can optionally be NULL,
+ * where NULL is used to indicate that the handle of the currently executing
+ * task should be used in place of the parameter.  This macro simply checks to
+ * see if the parameter is NULL and returns a pointer to the appropriate TCB.
+ */
+#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( TCB_t * ) pxCurrentTCB : ( TCB_t * ) ( pxHandle ) )
+
+/* The item value of the event list item is normally used to hold the priority
+of the task to which it belongs (coded to allow it to be held in reverse
+priority order).  However, it is occasionally borrowed for other purposes.  It
+is important its value is not updated due to a task priority change while it is
+being used for another purpose.  The following bit definition is used to inform
+the scheduler that the value should not be changed - in which case it is the
+responsibility of whichever module is using the value to ensure it gets set back
+to its original value when it is released. */
+#if configUSE_16_BIT_TICKS == 1
+	#define taskEVENT_LIST_ITEM_VALUE_IN_USE	0x8000U
+#else
+	#define taskEVENT_LIST_ITEM_VALUE_IN_USE	0x80000000UL
+#endif
+
+/* Callback function prototypes. --------------------------*/
+#if configCHECK_FOR_STACK_OVERFLOW > 0
+	extern void vApplicationStackOverflowHook( TaskHandle_t xTask, char *pcTaskName );
+#endif
+
+#if configUSE_TICK_HOOK > 0
+	extern void vApplicationTickHook( void );
+#endif
+
+/* File private functions. --------------------------------*/
+
+/*
+ * Utility to ready a TCB for a given task.  Mainly just copies the parameters
+ * into the TCB structure.
+ */
+static void prvInitialiseTCBVariables( TCB_t * const pxTCB, const char * const pcName, UBaseType_t uxPriority, const MemoryRegion_t * const xRegions, const uint16_t usStackDepth ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+
+/**
+ * Utility task that simply returns pdTRUE if the task referenced by xTask is
+ * currently in the Suspended state, or pdFALSE if the task referenced by xTask
+ * is in any other state.
+ */
+#if ( INCLUDE_vTaskSuspend == 1 )
+	static BaseType_t prvTaskIsTaskSuspended( const TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
+#endif /* INCLUDE_vTaskSuspend */
+
+/*
+ * Utility to ready all the lists used by the scheduler.  This is called
+ * automatically upon the creation of the first task.
+ */
+static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * The idle task, which as all tasks is implemented as a never ending loop.
+ * The idle task is automatically created and added to the ready lists upon
+ * creation of the first user task.
+ *
+ * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific
+ * language extensions.  The equivalent prototype for this function is:
+ *
+ * void prvIdleTask( void *pvParameters );
+ *
+ */
+static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters );
+
+/*
+ * Utility to free all memory allocated by the scheduler to hold a TCB,
+ * including the stack pointed to by the TCB.
+ *
+ * This does not free memory allocated by the task itself (i.e. memory
+ * allocated by calls to pvPortMalloc from within the tasks application code).
+ */
+#if ( INCLUDE_vTaskDelete == 1 )
+
+	static void prvDeleteTCB( TCB_t *pxTCB ) PRIVILEGED_FUNCTION;
+
+#endif
+
+/*
+ * Used only by the idle task.  This checks to see if anything has been placed
+ * in the list of tasks waiting to be deleted.  If so the task is cleaned up
+ * and its TCB deleted.
+ */
+static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * The currently executing task is entering the Blocked state.  Add the task to
+ * either the current or the overflow delayed task list.
+ */
+static void prvAddCurrentTaskToDelayedList( const TickType_t xTimeToWake ) PRIVILEGED_FUNCTION;
+
+/*
+ * Allocates memory from the heap for a TCB and associated stack.  Checks the
+ * allocation was successful.
+ */
+static TCB_t *prvAllocateTCBAndStack( const uint16_t usStackDepth, StackType_t * const puxStackBuffer ) PRIVILEGED_FUNCTION;
+
+/*
+ * Fills an TaskStatus_t structure with information on each task that is
+ * referenced from the pxList list (which may be a ready list, a delayed list,
+ * a suspended list, etc.).
+ *
+ * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM
+ * NORMAL APPLICATION CODE.
+ */
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	static UBaseType_t prvListTaskWithinSingleList( TaskStatus_t *pxTaskStatusArray, List_t *pxList, eTaskState eState ) PRIVILEGED_FUNCTION;
+
+#endif
+
+/*
+ * When a task is created, the stack of the task is filled with a known value.
+ * This function determines the 'high water mark' of the task stack by
+ * determining how much of the stack remains at the original preset value.
+ */
+#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) )
+
+	static uint16_t prvTaskCheckFreeStackSpace( const uint8_t * pucStackByte ) PRIVILEGED_FUNCTION;
+
+#endif
+
+/*
+ * Return the amount of time, in ticks, that will pass before the kernel will
+ * next move a task from the Blocked state to the Running state.
+ *
+ * This conditional compilation should use inequality to 0, not equality to 1.
+ * This is to ensure portSUPPRESS_TICKS_AND_SLEEP() can be called when user
+ * defined low power mode implementations require configUSE_TICKLESS_IDLE to be
+ * set to a value other than 1.
+ */
+#if ( configUSE_TICKLESS_IDLE != 0 )
+
+	static TickType_t prvGetExpectedIdleTime( void ) PRIVILEGED_FUNCTION;
+
+#endif
+
+/*
+ * Set xNextTaskUnblockTime to the time at which the next Blocked state task
+ * will exit the Blocked state.
+ */
+static void prvResetNextTaskUnblockTime( void );
+
+#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) )
+
+	/*
+	 * Helper function used to pad task names with spaces when printing out
+	 * human readable tables of task information.
+	 */
+	static char *prvWriteNameToBuffer( char *pcBuffer, const char *pcTaskName );
+
+#endif
+/*-----------------------------------------------------------*/
+
+BaseType_t xTaskGenericCreate( TaskFunction_t pxTaskCode, const char * const pcName, const uint16_t usStackDepth, void * const pvParameters, UBaseType_t uxPriority, TaskHandle_t * const pxCreatedTask, StackType_t * const puxStackBuffer, const MemoryRegion_t * const xRegions ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+{
+BaseType_t xReturn;
+TCB_t * pxNewTCB;
+StackType_t *pxTopOfStack;
+
+	configASSERT( pxTaskCode );
+	configASSERT( ( ( uxPriority & ( UBaseType_t ) ( ~portPRIVILEGE_BIT ) ) < ( UBaseType_t ) configMAX_PRIORITIES ) );
+
+	/* Allocate the memory required by the TCB and stack for the new task,
+	checking that the allocation was successful. */
+	pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer );
+
+	if( pxNewTCB != NULL )
+	{
+		#if( portUSING_MPU_WRAPPERS == 1 )
+			/* Should the task be created in privileged mode? */
+			BaseType_t xRunPrivileged;
+			if( ( uxPriority & portPRIVILEGE_BIT ) != 0U )
+			{
+				xRunPrivileged = pdTRUE;
+			}
+			else
+			{
+				xRunPrivileged = pdFALSE;
+			}
+			uxPriority &= ~portPRIVILEGE_BIT;
+
+			if( puxStackBuffer != NULL )
+			{
+				/* The application provided its own stack.  Note this so no
+				attempt is made to delete the stack should that task be
+				deleted. */
+				pxNewTCB->xUsingStaticallyAllocatedStack = pdTRUE;
+			}
+			else
+			{
+				/* The stack was allocated dynamically.  Note this so it can be
+				deleted again if the task is deleted. */
+				pxNewTCB->xUsingStaticallyAllocatedStack = pdFALSE;
+			}
+		#endif /* portUSING_MPU_WRAPPERS == 1 */
+
+		/* Calculate the top of stack address.  This depends on whether the
+		stack grows from high memory to low (as per the 80x86) or vice versa.
+		portSTACK_GROWTH is used to make the result positive or negative as
+		required by the port. */
+		#if( portSTACK_GROWTH < 0 )
+		{
+			pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( uint16_t ) 1 );
+			pxTopOfStack = ( StackType_t * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ~( ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) ) ); /*lint !e923 MISRA exception.  Avoiding casts between pointers and integers is not practical.  Size differences accounted for using portPOINTER_SIZE_TYPE type. */
+
+			/* Check the alignment of the calculated top of stack is correct. */
+			configASSERT( ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack & ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) == 0UL ) );
+		}
+		#else /* portSTACK_GROWTH */
+		{
+			pxTopOfStack = pxNewTCB->pxStack;
+
+			/* Check the alignment of the stack buffer is correct. */
+			configASSERT( ( ( ( portPOINTER_SIZE_TYPE ) pxNewTCB->pxStack & ( portPOINTER_SIZE_TYPE ) portBYTE_ALIGNMENT_MASK ) == 0UL ) );
+
+			/* If we want to use stack checking on architectures that use
+			a positive stack growth direction then we also need to store the
+			other extreme of the stack space. */
+			pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 );
+		}
+		#endif /* portSTACK_GROWTH */
+
+		/* Setup the newly allocated TCB with the initial state of the task. */
+		prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth );
+
+		/* Initialize the TCB stack to look as if the task was already running,
+		but had been interrupted by the scheduler.  The return address is set
+		to the start of the task function. Once the stack has been initialised
+		the	top of stack variable is updated. */
+		#if( portUSING_MPU_WRAPPERS == 1 )
+		{
+			pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged );
+		}
+		#else /* portUSING_MPU_WRAPPERS */
+		{
+			pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters );
+		}
+		#endif /* portUSING_MPU_WRAPPERS */
+
+		if( ( void * ) pxCreatedTask != NULL )
+		{
+			/* Pass the TCB out - in an anonymous way.  The calling function/
+			task can use this as a handle to delete the task later if
+			required.*/
+			*pxCreatedTask = ( TaskHandle_t ) pxNewTCB;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		/* Ensure interrupts don't access the task lists while they are being
+		updated. */
+		taskENTER_CRITICAL();
+		{
+			uxCurrentNumberOfTasks++;
+			if( pxCurrentTCB == NULL )
+			{
+				/* There are no other tasks, or all the other tasks are in
+				the suspended state - make this the current task. */
+				pxCurrentTCB =  pxNewTCB;
+
+				if( uxCurrentNumberOfTasks == ( UBaseType_t ) 1 )
+				{
+					/* This is the first task to be created so do the preliminary
+					initialisation required.  We will not recover if this call
+					fails, but we will report the failure. */
+					prvInitialiseTaskLists();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				/* If the scheduler is not already running, make this task the
+				current task if it is the highest priority task to be created
+				so far. */
+				if( xSchedulerRunning == pdFALSE )
+				{
+					if( pxCurrentTCB->uxPriority <= uxPriority )
+					{
+						pxCurrentTCB = pxNewTCB;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+
+			uxTaskNumber++;
+
+			#if ( configUSE_TRACE_FACILITY == 1 )
+			{
+				/* Add a counter into the TCB for tracing only. */
+				pxNewTCB->uxTCBNumber = uxTaskNumber;
+			}
+			#endif /* configUSE_TRACE_FACILITY */
+			traceTASK_CREATE( pxNewTCB );
+
+			prvAddTaskToReadyList( pxNewTCB );
+
+			xReturn = pdPASS;
+			portSETUP_TCB( pxNewTCB );
+		}
+		taskEXIT_CRITICAL();
+	}
+	else
+	{
+		xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY;
+		traceTASK_CREATE_FAILED();
+	}
+
+	if( xReturn == pdPASS )
+	{
+		if( xSchedulerRunning != pdFALSE )
+		{
+			/* If the created task is of a higher priority than the current task
+			then it should run now. */
+			if( pxCurrentTCB->uxPriority < uxPriority )
+			{
+				taskYIELD_IF_USING_PREEMPTION();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskDelete == 1 )
+
+	void vTaskDelete( TaskHandle_t xTaskToDelete )
+	{
+	TCB_t *pxTCB;
+
+		taskENTER_CRITICAL();
+		{
+			/* If null is passed in here then it is the calling task that is
+			being deleted. */
+			pxTCB = prvGetTCBFromHandle( xTaskToDelete );
+
+			/* Remove task from the ready list and place in the	termination list.
+			This will stop the task from be scheduled.  The idle task will check
+			the termination list and free up any memory allocated by the
+			scheduler for the TCB and stack. */
+			if( uxListRemove( &( pxTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+			{
+				taskRESET_READY_PRIORITY( pxTCB->uxPriority );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			/* Is the task waiting on an event also? */
+			if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL )
+			{
+				( void ) uxListRemove( &( pxTCB->xEventListItem ) );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			vListInsertEnd( &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) );
+
+			/* Increment the ucTasksDeleted variable so the idle task knows
+			there is a task that has been deleted and that it should therefore
+			check the xTasksWaitingTermination list. */
+			++uxTasksDeleted;
+
+			/* Increment the uxTaskNumberVariable also so kernel aware debuggers
+			can detect that the task lists need re-generating. */
+			uxTaskNumber++;
+
+			traceTASK_DELETE( pxTCB );
+		}
+		taskEXIT_CRITICAL();
+
+		/* Force a reschedule if it is the currently running task that has just
+		been deleted. */
+		if( xSchedulerRunning != pdFALSE )
+		{
+			if( pxTCB == pxCurrentTCB )
+			{
+				configASSERT( uxSchedulerSuspended == 0 );
+
+				/* The pre-delete hook is primarily for the Windows simulator,
+				in which Windows specific clean up operations are performed,
+				after which it is not possible to yield away from this task -
+				hence xYieldPending is used to latch that a context switch is
+				required. */
+				portPRE_TASK_DELETE_HOOK( pxTCB, &xYieldPending );
+				portYIELD_WITHIN_API();
+			}
+			else
+			{
+				/* Reset the next expected unblock time in case it referred to
+				the task that has just been deleted. */
+				taskENTER_CRITICAL();
+				{
+					prvResetNextTaskUnblockTime();
+				}
+				taskEXIT_CRITICAL();
+			}
+		}
+	}
+
+#endif /* INCLUDE_vTaskDelete */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskDelayUntil == 1 )
+
+	void vTaskDelayUntil( TickType_t * const pxPreviousWakeTime, const TickType_t xTimeIncrement )
+	{
+	TickType_t xTimeToWake;
+	BaseType_t xAlreadyYielded, xShouldDelay = pdFALSE;
+
+		configASSERT( pxPreviousWakeTime );
+		configASSERT( ( xTimeIncrement > 0U ) );
+		configASSERT( uxSchedulerSuspended == 0 );
+
+		vTaskSuspendAll();
+		{
+			/* Minor optimisation.  The tick count cannot change in this
+			block. */
+			const TickType_t xConstTickCount = xTickCount;
+
+			/* Generate the tick time at which the task wants to wake. */
+			xTimeToWake = *pxPreviousWakeTime + xTimeIncrement;
+
+			if( xConstTickCount < *pxPreviousWakeTime )
+			{
+				/* The tick count has overflowed since this function was
+				lasted called.  In this case the only time we should ever
+				actually delay is if the wake time has also	overflowed,
+				and the wake time is greater than the tick time.  When this
+				is the case it is as if neither time had overflowed. */
+				if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xConstTickCount ) )
+				{
+					xShouldDelay = pdTRUE;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				/* The tick time has not overflowed.  In this case we will
+				delay if either the wake time has overflowed, and/or the
+				tick time is less than the wake time. */
+				if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xConstTickCount ) )
+				{
+					xShouldDelay = pdTRUE;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+
+			/* Update the wake time ready for the next call. */
+			*pxPreviousWakeTime = xTimeToWake;
+
+			if( xShouldDelay != pdFALSE )
+			{
+				traceTASK_DELAY_UNTIL();
+
+				/* Remove the task from the ready list before adding it to the
+				blocked list as the same list item is used for both lists. */
+				if( uxListRemove( &( pxCurrentTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+				{
+					/* The current task must be in a ready list, so there is
+					no need to check, and the port reset macro can be called
+					directly. */
+					portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority );
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				prvAddCurrentTaskToDelayedList( xTimeToWake );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		xAlreadyYielded = xTaskResumeAll();
+
+		/* Force a reschedule if xTaskResumeAll has not already done so, we may
+		have put ourselves to sleep. */
+		if( xAlreadyYielded == pdFALSE )
+		{
+			portYIELD_WITHIN_API();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* INCLUDE_vTaskDelayUntil */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskDelay == 1 )
+
+	void vTaskDelay( const TickType_t xTicksToDelay )
+	{
+	TickType_t xTimeToWake;
+	BaseType_t xAlreadyYielded = pdFALSE;
+
+
+		/* A delay time of zero just forces a reschedule. */
+		if( xTicksToDelay > ( TickType_t ) 0U )
+		{
+			configASSERT( uxSchedulerSuspended == 0 );
+			vTaskSuspendAll();
+			{
+				traceTASK_DELAY();
+
+				/* A task that is removed from the event list while the
+				scheduler is suspended will not get placed in the ready
+				list or removed from the blocked list until the scheduler
+				is resumed.
+
+				This task cannot be in an event list as it is the currently
+				executing task. */
+
+				/* Calculate the time to wake - this may overflow but this is
+				not a problem. */
+				xTimeToWake = xTickCount + xTicksToDelay;
+
+				/* We must remove ourselves from the ready list before adding
+				ourselves to the blocked list as the same list item is used for
+				both lists. */
+				if( uxListRemove( &( pxCurrentTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+				{
+					/* The current task must be in a ready list, so there is
+					no need to check, and the port reset macro can be called
+					directly. */
+					portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority );
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+				prvAddCurrentTaskToDelayedList( xTimeToWake );
+			}
+			xAlreadyYielded = xTaskResumeAll();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		/* Force a reschedule if xTaskResumeAll has not already done so, we may
+		have put ourselves to sleep. */
+		if( xAlreadyYielded == pdFALSE )
+		{
+			portYIELD_WITHIN_API();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* INCLUDE_vTaskDelay */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_eTaskGetState == 1 )
+
+	eTaskState eTaskGetState( TaskHandle_t xTask )
+	{
+	eTaskState eReturn;
+	List_t *pxStateList;
+	const TCB_t * const pxTCB = ( TCB_t * ) xTask;
+
+		configASSERT( pxTCB );
+
+		if( pxTCB == pxCurrentTCB )
+		{
+			/* The task calling this function is querying its own state. */
+			eReturn = eRunning;
+		}
+		else
+		{
+			taskENTER_CRITICAL();
+			{
+				pxStateList = ( List_t * ) listLIST_ITEM_CONTAINER( &( pxTCB->xGenericListItem ) );
+			}
+			taskEXIT_CRITICAL();
+
+			if( ( pxStateList == pxDelayedTaskList ) || ( pxStateList == pxOverflowDelayedTaskList ) )
+			{
+				/* The task being queried is referenced from one of the Blocked
+				lists. */
+				eReturn = eBlocked;
+			}
+
+			#if ( INCLUDE_vTaskSuspend == 1 )
+				else if( pxStateList == &xSuspendedTaskList )
+				{
+					/* The task being queried is referenced from the suspended
+					list.  Is it genuinely suspended or is it block
+					indefinitely? */
+					if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL )
+					{
+						eReturn = eSuspended;
+					}
+					else
+					{
+						eReturn = eBlocked;
+					}
+				}
+			#endif
+
+			#if ( INCLUDE_vTaskDelete == 1 )
+				else if( pxStateList == &xTasksWaitingTermination )
+				{
+					/* The task being queried is referenced from the deleted
+					tasks list. */
+					eReturn = eDeleted;
+				}
+			#endif
+
+			else /*lint !e525 Negative indentation is intended to make use of pre-processor clearer. */
+			{
+				/* If the task is not in any other state, it must be in the
+				Ready (including pending ready) state. */
+				eReturn = eReady;
+			}
+		}
+
+		return eReturn;
+	} /*lint !e818 xTask cannot be a pointer to const because it is a typedef. */
+
+#endif /* INCLUDE_eTaskGetState */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_uxTaskPriorityGet == 1 )
+
+	UBaseType_t uxTaskPriorityGet( TaskHandle_t xTask )
+	{
+	TCB_t *pxTCB;
+	UBaseType_t uxReturn;
+
+		taskENTER_CRITICAL();
+		{
+			/* If null is passed in here then it is the priority of the that
+			called uxTaskPriorityGet() that is being queried. */
+			pxTCB = prvGetTCBFromHandle( xTask );
+			uxReturn = pxTCB->uxPriority;
+		}
+		taskEXIT_CRITICAL();
+
+		return uxReturn;
+	}
+
+#endif /* INCLUDE_uxTaskPriorityGet */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_uxTaskPriorityGet == 1 )
+
+	UBaseType_t uxTaskPriorityGetFromISR( TaskHandle_t xTask )
+	{
+	TCB_t *pxTCB;
+	UBaseType_t uxReturn, uxSavedInterruptState;
+
+		/* RTOS ports that support interrupt nesting have the concept of a
+		maximum	system call (or maximum API call) interrupt priority.
+		Interrupts that are	above the maximum system call priority are keep
+		permanently enabled, even when the RTOS kernel is in a critical section,
+		but cannot make any calls to FreeRTOS API functions.  If configASSERT()
+		is defined in FreeRTOSConfig.h then
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+		failure if a FreeRTOS API function is called from an interrupt that has
+		been assigned a priority above the configured maximum system call
+		priority.  Only FreeRTOS functions that end in FromISR can be called
+		from interrupts	that have been assigned a priority at or (logically)
+		below the maximum system call interrupt priority.  FreeRTOS maintains a
+		separate interrupt safe API to ensure interrupt entry is as fast and as
+		simple as possible.  More information (albeit Cortex-M specific) is
+		provided on the following link:
+		http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+		uxSavedInterruptState = portSET_INTERRUPT_MASK_FROM_ISR();
+		{
+			/* If null is passed in here then it is the priority of the calling
+			task that is being queried. */
+			pxTCB = prvGetTCBFromHandle( xTask );
+			uxReturn = pxTCB->uxPriority;
+		}
+		portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptState );
+
+		return uxReturn;
+	}
+
+#endif /* INCLUDE_uxTaskPriorityGet */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskPrioritySet == 1 )
+
+	void vTaskPrioritySet( TaskHandle_t xTask, UBaseType_t uxNewPriority )
+	{
+	TCB_t *pxTCB;
+	UBaseType_t uxCurrentBasePriority, uxPriorityUsedOnEntry;
+	BaseType_t xYieldRequired = pdFALSE;
+
+		configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) );
+
+		/* Ensure the new priority is valid. */
+		if( uxNewPriority >= ( UBaseType_t ) configMAX_PRIORITIES )
+		{
+			uxNewPriority = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) 1U;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		taskENTER_CRITICAL();
+		{
+			/* If null is passed in here then it is the priority of the calling
+			task that is being changed. */
+			pxTCB = prvGetTCBFromHandle( xTask );
+
+			traceTASK_PRIORITY_SET( pxTCB, uxNewPriority );
+
+			#if ( configUSE_MUTEXES == 1 )
+			{
+				uxCurrentBasePriority = pxTCB->uxBasePriority;
+			}
+			#else
+			{
+				uxCurrentBasePriority = pxTCB->uxPriority;
+			}
+			#endif
+
+			if( uxCurrentBasePriority != uxNewPriority )
+			{
+				/* The priority change may have readied a task of higher
+				priority than the calling task. */
+				if( uxNewPriority > uxCurrentBasePriority )
+				{
+					if( pxTCB != pxCurrentTCB )
+					{
+						/* The priority of a task other than the currently
+						running task is being raised.  Is the priority being
+						raised above that of the running task? */
+						if( uxNewPriority >= pxCurrentTCB->uxPriority )
+						{
+							xYieldRequired = pdTRUE;
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						/* The priority of the running task is being raised,
+						but the running task must already be the highest
+						priority task able to run so no yield is required. */
+					}
+				}
+				else if( pxTCB == pxCurrentTCB )
+				{
+					/* Setting the priority of the running task down means
+					there may now be another task of higher priority that
+					is ready to execute. */
+					xYieldRequired = pdTRUE;
+				}
+				else
+				{
+					/* Setting the priority of any other task down does not
+					require a yield as the running task must be above the
+					new priority of the task being modified. */
+				}
+
+				/* Remember the ready list the task might be referenced from
+				before its uxPriority member is changed so the
+				taskRESET_READY_PRIORITY() macro can function correctly. */
+				uxPriorityUsedOnEntry = pxTCB->uxPriority;
+
+				#if ( configUSE_MUTEXES == 1 )
+				{
+					/* Only change the priority being used if the task is not
+					currently using an inherited priority. */
+					if( pxTCB->uxBasePriority == pxTCB->uxPriority )
+					{
+						pxTCB->uxPriority = uxNewPriority;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					/* The base priority gets set whatever. */
+					pxTCB->uxBasePriority = uxNewPriority;
+				}
+				#else
+				{
+					pxTCB->uxPriority = uxNewPriority;
+				}
+				#endif
+
+				/* Only reset the event list item value if the value is not
+				being used for anything else. */
+				if( ( listGET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL )
+				{
+					listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxNewPriority ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				/* If the task is in the blocked or suspended list we need do
+				nothing more than change it's priority variable. However, if
+				the task is in a ready list it needs to be removed and placed
+				in the list appropriate to its new priority. */
+				if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxPriorityUsedOnEntry ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE )
+				{
+					/* The task is currently in its ready list - remove before adding
+					it to it's new ready list.  As we are in a critical section we
+					can do this even if the scheduler is suspended. */
+					if( uxListRemove( &( pxTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+					{
+						/* It is known that the task is in its ready list so
+						there is no need to check again and the port level
+						reset macro can be called directly. */
+						portRESET_READY_PRIORITY( uxPriorityUsedOnEntry, uxTopReadyPriority );
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+					prvAddTaskToReadyList( pxTCB );
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				if( xYieldRequired == pdTRUE )
+				{
+					taskYIELD_IF_USING_PREEMPTION();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				/* Remove compiler warning about unused variables when the port
+				optimised task selection is not being used. */
+				( void ) uxPriorityUsedOnEntry;
+			}
+		}
+		taskEXIT_CRITICAL();
+	}
+
+#endif /* INCLUDE_vTaskPrioritySet */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskSuspend == 1 )
+
+	void vTaskSuspend( TaskHandle_t xTaskToSuspend )
+	{
+	TCB_t *pxTCB;
+
+		taskENTER_CRITICAL();
+		{
+			/* If null is passed in here then it is the running task that is
+			being suspended. */
+			pxTCB = prvGetTCBFromHandle( xTaskToSuspend );
+
+			traceTASK_SUSPEND( pxTCB );
+
+			/* Remove task from the ready/delayed list and place in the
+			suspended list. */
+			if( uxListRemove( &( pxTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+			{
+				taskRESET_READY_PRIORITY( pxTCB->uxPriority );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			/* Is the task waiting on an event also? */
+			if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL )
+			{
+				( void ) uxListRemove( &( pxTCB->xEventListItem ) );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			vListInsertEnd( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) );
+		}
+		taskEXIT_CRITICAL();
+
+		if( pxTCB == pxCurrentTCB )
+		{
+			if( xSchedulerRunning != pdFALSE )
+			{
+				/* The current task has just been suspended. */
+				configASSERT( uxSchedulerSuspended == 0 );
+				portYIELD_WITHIN_API();
+			}
+			else
+			{
+				/* The scheduler is not running, but the task that was pointed
+				to by pxCurrentTCB has just been suspended and pxCurrentTCB
+				must be adjusted to point to a different task. */
+				if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks )
+				{
+					/* No other tasks are ready, so set pxCurrentTCB back to
+					NULL so when the next task is created pxCurrentTCB will
+					be set to point to it no matter what its relative priority
+					is. */
+					pxCurrentTCB = NULL;
+				}
+				else
+				{
+					vTaskSwitchContext();
+				}
+			}
+		}
+		else
+		{
+			if( xSchedulerRunning != pdFALSE )
+			{
+				/* A task other than the currently running task was suspended,
+				reset the next expected unblock time in case it referred to the
+				task that is now in the Suspended state. */
+				taskENTER_CRITICAL();
+				{
+					prvResetNextTaskUnblockTime();
+				}
+				taskEXIT_CRITICAL();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+	}
+
+#endif /* INCLUDE_vTaskSuspend */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskSuspend == 1 )
+
+	static BaseType_t prvTaskIsTaskSuspended( const TaskHandle_t xTask )
+	{
+	BaseType_t xReturn = pdFALSE;
+	const TCB_t * const pxTCB = ( TCB_t * ) xTask;
+
+		/* Accesses xPendingReadyList so must be called from a critical
+		section. */
+
+		/* It does not make sense to check if the calling task is suspended. */
+		configASSERT( xTask );
+
+		/* Is the task being resumed actually in the suspended list? */
+		if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE )
+		{
+			/* Has the task already been resumed from within an ISR? */
+			if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) == pdFALSE )
+			{
+				/* Is it in the suspended list because it is in the	Suspended
+				state, or because is is blocked with no timeout? */
+				if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) != pdFALSE )
+				{
+					xReturn = pdTRUE;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		return xReturn;
+	} /*lint !e818 xTask cannot be a pointer to const because it is a typedef. */
+
+#endif /* INCLUDE_vTaskSuspend */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskSuspend == 1 )
+
+	void vTaskResume( TaskHandle_t xTaskToResume )
+	{
+	TCB_t * const pxTCB = ( TCB_t * ) xTaskToResume;
+
+		/* It does not make sense to resume the calling task. */
+		configASSERT( xTaskToResume );
+
+		/* The parameter cannot be NULL as it is impossible to resume the
+		currently executing task. */
+		if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) )
+		{
+			taskENTER_CRITICAL();
+			{
+				if( prvTaskIsTaskSuspended( pxTCB ) == pdTRUE )
+				{
+					traceTASK_RESUME( pxTCB );
+
+					/* As we are in a critical section we can access the ready
+					lists even if the scheduler is suspended. */
+					( void ) uxListRemove(  &( pxTCB->xGenericListItem ) );
+					prvAddTaskToReadyList( pxTCB );
+
+					/* We may have just resumed a higher priority task. */
+					if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority )
+					{
+						/* This yield may not cause the task just resumed to run,
+						but will leave the lists in the correct state for the
+						next yield. */
+						taskYIELD_IF_USING_PREEMPTION();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			taskEXIT_CRITICAL();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* INCLUDE_vTaskSuspend */
+
+/*-----------------------------------------------------------*/
+
+#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) )
+
+	BaseType_t xTaskResumeFromISR( TaskHandle_t xTaskToResume )
+	{
+	BaseType_t xYieldRequired = pdFALSE;
+	TCB_t * const pxTCB = ( TCB_t * ) xTaskToResume;
+	UBaseType_t uxSavedInterruptStatus;
+
+		configASSERT( xTaskToResume );
+
+		/* RTOS ports that support interrupt nesting have the concept of a
+		maximum	system call (or maximum API call) interrupt priority.
+		Interrupts that are	above the maximum system call priority are keep
+		permanently enabled, even when the RTOS kernel is in a critical section,
+		but cannot make any calls to FreeRTOS API functions.  If configASSERT()
+		is defined in FreeRTOSConfig.h then
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+		failure if a FreeRTOS API function is called from an interrupt that has
+		been assigned a priority above the configured maximum system call
+		priority.  Only FreeRTOS functions that end in FromISR can be called
+		from interrupts	that have been assigned a priority at or (logically)
+		below the maximum system call interrupt priority.  FreeRTOS maintains a
+		separate interrupt safe API to ensure interrupt entry is as fast and as
+		simple as possible.  More information (albeit Cortex-M specific) is
+		provided on the following link:
+		http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+		uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+		{
+			if( prvTaskIsTaskSuspended( pxTCB ) == pdTRUE )
+			{
+				traceTASK_RESUME_FROM_ISR( pxTCB );
+
+				/* Check the ready lists can be accessed. */
+				if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE )
+				{
+					/* Ready lists can be accessed so move the task from the
+					suspended list to the ready list directly. */
+					if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority )
+					{
+						xYieldRequired = pdTRUE;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					( void ) uxListRemove(  &( pxTCB->xGenericListItem ) );
+					prvAddTaskToReadyList( pxTCB );
+				}
+				else
+				{
+					/* The delayed or ready lists cannot be accessed so the task
+					is held in the pending ready list until the scheduler is
+					unsuspended. */
+					vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) );
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+		return xYieldRequired;
+	}
+
+#endif /* ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) */
+/*-----------------------------------------------------------*/
+
+void vTaskStartScheduler( void )
+{
+BaseType_t xReturn;
+
+	/* Add the idle task at the lowest priority. */
+	#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 )
+	{
+		/* Create the idle task, storing its handle in xIdleTaskHandle so it can
+		be returned by the xTaskGetIdleTaskHandle() function. */
+		xReturn = xTaskCreate( prvIdleTask, "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); /*lint !e961 MISRA exception, justified as it is not a redundant explicit cast to all supported compilers. */
+	}
+	#else
+	{
+		/* Create the idle task without storing its handle. */
+		xReturn = xTaskCreate( prvIdleTask, "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL );  /*lint !e961 MISRA exception, justified as it is not a redundant explicit cast to all supported compilers. */
+	}
+	#endif /* INCLUDE_xTaskGetIdleTaskHandle */
+
+	#if ( configUSE_TIMERS == 1 )
+	{
+		if( xReturn == pdPASS )
+		{
+			xReturn = xTimerCreateTimerTask();
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	#endif /* configUSE_TIMERS */
+
+	if( xReturn == pdPASS )
+	{
+		/* Interrupts are turned off here, to ensure a tick does not occur
+		before or during the call to xPortStartScheduler().  The stacks of
+		the created tasks contain a status word with interrupts switched on
+		so interrupts will automatically get re-enabled when the first task
+		starts to run. */
+		portDISABLE_INTERRUPTS();
+
+		#if ( configUSE_NEWLIB_REENTRANT == 1 )
+		{
+			/* Switch Newlib's _impure_ptr variable to point to the _reent
+			structure specific to the task that will run first. */
+			_impure_ptr = &( pxCurrentTCB->xNewLib_reent );
+		}
+		#endif /* configUSE_NEWLIB_REENTRANT */
+
+		xNextTaskUnblockTime = portMAX_DELAY;
+		xSchedulerRunning = pdTRUE;
+		xTickCount = ( TickType_t ) 0U;
+
+		/* If configGENERATE_RUN_TIME_STATS is defined then the following
+		macro must be defined to configure the timer/counter used to generate
+		the run time counter time base. */
+		portCONFIGURE_TIMER_FOR_RUN_TIME_STATS();
+
+		/* Setting up the timer tick is hardware specific and thus in the
+		portable interface. */
+		if( xPortStartScheduler() != pdFALSE )
+		{
+			/* Should not reach here as if the scheduler is running the
+			function will not return. */
+		}
+		else
+		{
+			/* Should only reach here if a task calls xTaskEndScheduler(). */
+		}
+	}
+	else
+	{
+		/* This line will only be reached if the kernel could not be started,
+		because there was not enough FreeRTOS heap to create the idle task
+		or the timer task. */
+		configASSERT( xReturn );
+	}
+}
+/*-----------------------------------------------------------*/
+
+void vTaskEndScheduler( void )
+{
+	/* Stop the scheduler interrupts and call the portable scheduler end
+	routine so the original ISRs can be restored if necessary.  The port
+	layer must ensure interrupts enable	bit is left in the correct state. */
+	portDISABLE_INTERRUPTS();
+	xSchedulerRunning = pdFALSE;
+	vPortEndScheduler();
+}
+/*----------------------------------------------------------*/
+
+void vTaskSuspendAll( void )
+{
+	/* A critical section is not required as the variable is of type
+	BaseType_t.  Please read Richard Barry's reply in the following link to a
+	post in the FreeRTOS support forum before reporting this as a bug! -
+	http://goo.gl/wu4acr */
+	++uxSchedulerSuspended;
+}
+/*----------------------------------------------------------*/
+
+#if ( configUSE_TICKLESS_IDLE != 0 )
+
+	static TickType_t prvGetExpectedIdleTime( void )
+	{
+	TickType_t xReturn;
+
+		if( pxCurrentTCB->uxPriority > tskIDLE_PRIORITY )
+		{
+			xReturn = 0;
+		}
+		else if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > 1 )
+		{
+			/* There are other idle priority tasks in the ready state.  If
+			time slicing is used then the very next tick interrupt must be
+			processed. */
+			xReturn = 0;
+		}
+		else
+		{
+			xReturn = xNextTaskUnblockTime - xTickCount;
+		}
+
+		return xReturn;
+	}
+
+#endif /* configUSE_TICKLESS_IDLE */
+/*----------------------------------------------------------*/
+
+BaseType_t xTaskResumeAll( void )
+{
+TCB_t *pxTCB;
+BaseType_t xAlreadyYielded = pdFALSE;
+
+	/* If uxSchedulerSuspended is zero then this function does not match a
+	previous call to vTaskSuspendAll(). */
+	configASSERT( uxSchedulerSuspended );
+
+	/* It is possible that an ISR caused a task to be removed from an event
+	list while the scheduler was suspended.  If this was the case then the
+	removed task will have been added to the xPendingReadyList.  Once the
+	scheduler has been resumed it is safe to move all the pending ready
+	tasks from this list into their appropriate ready list. */
+	taskENTER_CRITICAL();
+	{
+		--uxSchedulerSuspended;
+
+		if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE )
+		{
+			if( uxCurrentNumberOfTasks > ( UBaseType_t ) 0U )
+			{
+				/* Move any readied tasks from the pending list into the
+				appropriate ready list. */
+				while( listLIST_IS_EMPTY( &xPendingReadyList ) == pdFALSE )
+				{
+					pxTCB = ( TCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( ( &xPendingReadyList ) );
+					( void ) uxListRemove( &( pxTCB->xEventListItem ) );
+					( void ) uxListRemove( &( pxTCB->xGenericListItem ) );
+					prvAddTaskToReadyList( pxTCB );
+
+					/* If the moved task has a priority higher than the current
+					task then a yield must be performed. */
+					if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority )
+					{
+						xYieldPending = pdTRUE;
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+
+				/* If any ticks occurred while the scheduler was suspended then
+				they should be processed now.  This ensures the tick count does
+				not	slip, and that any delayed tasks are resumed at the correct
+				time. */
+				if( uxPendedTicks > ( UBaseType_t ) 0U )
+				{
+					while( uxPendedTicks > ( UBaseType_t ) 0U )
+					{
+						if( xTaskIncrementTick() != pdFALSE )
+						{
+							xYieldPending = pdTRUE;
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+						--uxPendedTicks;
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				if( xYieldPending == pdTRUE )
+				{
+					#if( configUSE_PREEMPTION != 0 )
+					{
+						xAlreadyYielded = pdTRUE;
+					}
+					#endif
+					taskYIELD_IF_USING_PREEMPTION();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	taskEXIT_CRITICAL();
+
+	return xAlreadyYielded;
+}
+/*-----------------------------------------------------------*/
+
+TickType_t xTaskGetTickCount( void )
+{
+TickType_t xTicks;
+
+	/* Critical section required if running on a 16 bit processor. */
+	portTICK_TYPE_ENTER_CRITICAL();
+	{
+		xTicks = xTickCount;
+	}
+	portTICK_TYPE_EXIT_CRITICAL();
+
+	return xTicks;
+}
+/*-----------------------------------------------------------*/
+
+TickType_t xTaskGetTickCountFromISR( void )
+{
+TickType_t xReturn;
+UBaseType_t uxSavedInterruptStatus;
+
+	/* RTOS ports that support interrupt nesting have the concept of a maximum
+	system call (or maximum API call) interrupt priority.  Interrupts that are
+	above the maximum system call priority are kept permanently enabled, even
+	when the RTOS kernel is in a critical section, but cannot make any calls to
+	FreeRTOS API functions.  If configASSERT() is defined in FreeRTOSConfig.h
+	then portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+	failure if a FreeRTOS API function is called from an interrupt that has been
+	assigned a priority above the configured maximum system call priority.
+	Only FreeRTOS functions that end in FromISR can be called from interrupts
+	that have been assigned a priority at or (logically) below the maximum
+	system call	interrupt priority.  FreeRTOS maintains a separate interrupt
+	safe API to ensure interrupt entry is as fast and as simple as possible.
+	More information (albeit Cortex-M specific) is provided on the following
+	link: http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+	portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+	uxSavedInterruptStatus = portTICK_TYPE_SET_INTERRUPT_MASK_FROM_ISR();
+	{
+		xReturn = xTickCount;
+	}
+	portTICK_TYPE_CLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+UBaseType_t uxTaskGetNumberOfTasks( void )
+{
+	/* A critical section is not required because the variables are of type
+	BaseType_t. */
+	return uxCurrentNumberOfTasks;
+}
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_pcTaskGetTaskName == 1 )
+
+	char *pcTaskGetTaskName( TaskHandle_t xTaskToQuery ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+	{
+	TCB_t *pxTCB;
+
+		/* If null is passed in here then the name of the calling task is being queried. */
+		pxTCB = prvGetTCBFromHandle( xTaskToQuery );
+		configASSERT( pxTCB );
+		return &( pxTCB->pcTaskName[ 0 ] );
+	}
+
+#endif /* INCLUDE_pcTaskGetTaskName */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	UBaseType_t uxTaskGetSystemState( TaskStatus_t * const pxTaskStatusArray, const UBaseType_t uxArraySize, uint32_t * const pulTotalRunTime )
+	{
+	UBaseType_t uxTask = 0, uxQueue = configMAX_PRIORITIES;
+
+		vTaskSuspendAll();
+		{
+			/* Is there a space in the array for each task in the system? */
+			if( uxArraySize >= uxCurrentNumberOfTasks )
+			{
+				/* Fill in an TaskStatus_t structure with information on each
+				task in the Ready state. */
+				do
+				{
+					uxQueue--;
+					uxTask += prvListTaskWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &( pxReadyTasksLists[ uxQueue ] ), eReady );
+
+				} while( uxQueue > ( UBaseType_t ) tskIDLE_PRIORITY ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+
+				/* Fill in an TaskStatus_t structure with information on each
+				task in the Blocked state. */
+				uxTask += prvListTaskWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), ( List_t * ) pxDelayedTaskList, eBlocked );
+				uxTask += prvListTaskWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), ( List_t * ) pxOverflowDelayedTaskList, eBlocked );
+
+				#if( INCLUDE_vTaskDelete == 1 )
+				{
+					/* Fill in an TaskStatus_t structure with information on
+					each task that has been deleted but not yet cleaned up. */
+					uxTask += prvListTaskWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &xTasksWaitingTermination, eDeleted );
+				}
+				#endif
+
+				#if ( INCLUDE_vTaskSuspend == 1 )
+				{
+					/* Fill in an TaskStatus_t structure with information on
+					each task in the Suspended state. */
+					uxTask += prvListTaskWithinSingleList( &( pxTaskStatusArray[ uxTask ] ), &xSuspendedTaskList, eSuspended );
+				}
+				#endif
+
+				#if ( configGENERATE_RUN_TIME_STATS == 1)
+				{
+					if( pulTotalRunTime != NULL )
+					{
+						#ifdef portALT_GET_RUN_TIME_COUNTER_VALUE
+							portALT_GET_RUN_TIME_COUNTER_VALUE( ( *pulTotalRunTime ) );
+						#else
+							*pulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE();
+						#endif
+					}
+				}
+				#else
+				{
+					if( pulTotalRunTime != NULL )
+					{
+						*pulTotalRunTime = 0;
+					}
+				}
+				#endif
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		( void ) xTaskResumeAll();
+
+		return uxTask;
+	}
+
+#endif /* configUSE_TRACE_FACILITY */
+/*----------------------------------------------------------*/
+
+#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 )
+
+	TaskHandle_t xTaskGetIdleTaskHandle( void )
+	{
+		/* If xTaskGetIdleTaskHandle() is called before the scheduler has been
+		started, then xIdleTaskHandle will be NULL. */
+		configASSERT( ( xIdleTaskHandle != NULL ) );
+		return xIdleTaskHandle;
+	}
+
+#endif /* INCLUDE_xTaskGetIdleTaskHandle */
+/*----------------------------------------------------------*/
+
+/* This conditional compilation should use inequality to 0, not equality to 1.
+This is to ensure vTaskStepTick() is available when user defined low power mode
+implementations require configUSE_TICKLESS_IDLE to be set to a value other than
+1. */
+#if ( configUSE_TICKLESS_IDLE != 0 )
+
+	void vTaskStepTick( const TickType_t xTicksToJump )
+	{
+		/* Correct the tick count value after a period during which the tick
+		was suppressed.  Note this does *not* call the tick hook function for
+		each stepped tick. */
+		configASSERT( ( xTickCount + xTicksToJump ) <= xNextTaskUnblockTime );
+		xTickCount += xTicksToJump;
+		traceINCREASE_TICK_COUNT( xTicksToJump );
+	}
+
+#endif /* configUSE_TICKLESS_IDLE */
+/*----------------------------------------------------------*/
+
+BaseType_t xTaskIncrementTick( void )
+{
+TCB_t * pxTCB;
+TickType_t xItemValue;
+BaseType_t xSwitchRequired = pdFALSE;
+
+	/* Called by the portable layer each time a tick interrupt occurs.
+	Increments the tick then checks to see if the new tick value will cause any
+	tasks to be unblocked. */
+	traceTASK_INCREMENT_TICK( xTickCount );
+	if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE )
+	{
+		/* Increment the RTOS tick, switching the delayed and overflowed
+		delayed lists if it wraps to 0. */
+		++xTickCount;
+
+		{
+			/* Minor optimisation.  The tick count cannot change in this
+			block. */
+			const TickType_t xConstTickCount = xTickCount;
+
+			if( xConstTickCount == ( TickType_t ) 0U )
+			{
+				taskSWITCH_DELAYED_LISTS();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			/* See if this tick has made a timeout expire.  Tasks are stored in
+			the	queue in the order of their wake time - meaning once one task
+			has been found whose block time has not expired there is no need to
+			look any further down the list. */
+			if( xConstTickCount >= xNextTaskUnblockTime )
+			{
+				for( ;; )
+				{
+					if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE )
+					{
+						/* The delayed list is empty.  Set xNextTaskUnblockTime
+						to the maximum possible value so it is extremely
+						unlikely that the
+						if( xTickCount >= xNextTaskUnblockTime ) test will pass
+						next time through. */
+						xNextTaskUnblockTime = portMAX_DELAY;
+						break;
+					}
+					else
+					{
+						/* The delayed list is not empty, get the value of the
+						item at the head of the delayed list.  This is the time
+						at which the task at the head of the delayed list must
+						be removed from the Blocked state. */
+						pxTCB = ( TCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList );
+						xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) );
+
+						if( xConstTickCount < xItemValue )
+						{
+							/* It is not time to unblock this item yet, but the
+							item value is the time at which the task at the head
+							of the blocked list must be removed from the Blocked
+							state -	so record the item value in
+							xNextTaskUnblockTime. */
+							xNextTaskUnblockTime = xItemValue;
+							break;
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+
+						/* It is time to remove the item from the Blocked state. */
+						( void ) uxListRemove( &( pxTCB->xGenericListItem ) );
+
+						/* Is the task waiting on an event also?  If so remove
+						it from the event list. */
+						if( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) != NULL )
+						{
+							( void ) uxListRemove( &( pxTCB->xEventListItem ) );
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+
+						/* Place the unblocked task into the appropriate ready
+						list. */
+						prvAddTaskToReadyList( pxTCB );
+
+						/* A task being unblocked cannot cause an immediate
+						context switch if preemption is turned off. */
+						#if (  configUSE_PREEMPTION == 1 )
+						{
+							/* Preemption is on, but a context switch should
+							only be performed if the unblocked task has a
+							priority that is equal to or higher than the
+							currently executing task. */
+							if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority )
+							{
+								xSwitchRequired = pdTRUE;
+							}
+							else
+							{
+								mtCOVERAGE_TEST_MARKER();
+							}
+						}
+						#endif /* configUSE_PREEMPTION */
+					}
+				}
+			}
+		}
+
+		/* Tasks of equal priority to the currently running task will share
+		processing time (time slice) if preemption is on, and the application
+		writer has not explicitly turned time slicing off. */
+		#if ( ( configUSE_PREEMPTION == 1 ) && ( configUSE_TIME_SLICING == 1 ) )
+		{
+			if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ pxCurrentTCB->uxPriority ] ) ) > ( UBaseType_t ) 1 )
+			{
+				xSwitchRequired = pdTRUE;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		#endif /* ( ( configUSE_PREEMPTION == 1 ) && ( configUSE_TIME_SLICING == 1 ) ) */
+
+		#if ( configUSE_TICK_HOOK == 1 )
+		{
+			/* Guard against the tick hook being called when the pended tick
+			count is being unwound (when the scheduler is being unlocked). */
+			if( uxPendedTicks == ( UBaseType_t ) 0U )
+			{
+				vApplicationTickHook();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		#endif /* configUSE_TICK_HOOK */
+	}
+	else
+	{
+		++uxPendedTicks;
+
+		/* The tick hook gets called at regular intervals, even if the
+		scheduler is locked. */
+		#if ( configUSE_TICK_HOOK == 1 )
+		{
+			vApplicationTickHook();
+		}
+		#endif
+	}
+
+	#if ( configUSE_PREEMPTION == 1 )
+	{
+		if( xYieldPending != pdFALSE )
+		{
+			xSwitchRequired = pdTRUE;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	#endif /* configUSE_PREEMPTION */
+
+	return xSwitchRequired;
+}
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_APPLICATION_TASK_TAG == 1 )
+
+	void vTaskSetApplicationTaskTag( TaskHandle_t xTask, TaskHookFunction_t pxHookFunction )
+	{
+	TCB_t *xTCB;
+
+		/* If xTask is NULL then it is the task hook of the calling task that is
+		getting set. */
+		if( xTask == NULL )
+		{
+			xTCB = ( TCB_t * ) pxCurrentTCB;
+		}
+		else
+		{
+			xTCB = ( TCB_t * ) xTask;
+		}
+
+		/* Save the hook function in the TCB.  A critical section is required as
+		the value can be accessed from an interrupt. */
+		taskENTER_CRITICAL();
+			xTCB->pxTaskTag = pxHookFunction;
+		taskEXIT_CRITICAL();
+	}
+
+#endif /* configUSE_APPLICATION_TASK_TAG */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_APPLICATION_TASK_TAG == 1 )
+
+	TaskHookFunction_t xTaskGetApplicationTaskTag( TaskHandle_t xTask )
+	{
+	TCB_t *xTCB;
+	TaskHookFunction_t xReturn;
+
+		/* If xTask is NULL then we are setting our own task hook. */
+		if( xTask == NULL )
+		{
+			xTCB = ( TCB_t * ) pxCurrentTCB;
+		}
+		else
+		{
+			xTCB = ( TCB_t * ) xTask;
+		}
+
+		/* Save the hook function in the TCB.  A critical section is required as
+		the value can be accessed from an interrupt. */
+		taskENTER_CRITICAL();
+		{
+			xReturn = xTCB->pxTaskTag;
+		}
+		taskEXIT_CRITICAL();
+
+		return xReturn;
+	}
+
+#endif /* configUSE_APPLICATION_TASK_TAG */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_APPLICATION_TASK_TAG == 1 )
+
+	BaseType_t xTaskCallApplicationTaskHook( TaskHandle_t xTask, void *pvParameter )
+	{
+	TCB_t *xTCB;
+	BaseType_t xReturn;
+
+		/* If xTask is NULL then we are calling our own task hook. */
+		if( xTask == NULL )
+		{
+			xTCB = ( TCB_t * ) pxCurrentTCB;
+		}
+		else
+		{
+			xTCB = ( TCB_t * ) xTask;
+		}
+
+		if( xTCB->pxTaskTag != NULL )
+		{
+			xReturn = xTCB->pxTaskTag( pvParameter );
+		}
+		else
+		{
+			xReturn = pdFAIL;
+		}
+
+		return xReturn;
+	}
+
+#endif /* configUSE_APPLICATION_TASK_TAG */
+/*-----------------------------------------------------------*/
+
+void vTaskSwitchContext( void )
+{
+	if( uxSchedulerSuspended != ( UBaseType_t ) pdFALSE )
+	{
+		/* The scheduler is currently suspended - do not allow a context
+		switch. */
+		xYieldPending = pdTRUE;
+	}
+	else
+	{
+		xYieldPending = pdFALSE;
+		traceTASK_SWITCHED_OUT();
+
+		#if ( configGENERATE_RUN_TIME_STATS == 1 )
+		{
+				#ifdef portALT_GET_RUN_TIME_COUNTER_VALUE
+					portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime );
+				#else
+					ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE();
+				#endif
+
+				/* Add the amount of time the task has been running to the
+				accumulated	time so far.  The time the task started running was
+				stored in ulTaskSwitchedInTime.  Note that there is no overflow
+				protection here	so count values are only valid until the timer
+				overflows.  The guard against negative values is to protect
+				against suspect run time stat counter implementations - which
+				are provided by the application, not the kernel. */
+				if( ulTotalRunTime > ulTaskSwitchedInTime )
+				{
+					pxCurrentTCB->ulRunTimeCounter += ( ulTotalRunTime - ulTaskSwitchedInTime );
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+				ulTaskSwitchedInTime = ulTotalRunTime;
+		}
+		#endif /* configGENERATE_RUN_TIME_STATS */
+
+		/* Check for stack overflow, if configured. */
+		taskCHECK_FOR_STACK_OVERFLOW();
+
+		/* Select a new task to run using either the generic C or port
+		optimised asm code. */
+		taskSELECT_HIGHEST_PRIORITY_TASK();
+		traceTASK_SWITCHED_IN();
+
+		#if ( configUSE_NEWLIB_REENTRANT == 1 )
+		{
+			/* Switch Newlib's _impure_ptr variable to point to the _reent
+			structure specific to this task. */
+			_impure_ptr = &( pxCurrentTCB->xNewLib_reent );
+		}
+		#endif /* configUSE_NEWLIB_REENTRANT */
+	}
+}
+/*-----------------------------------------------------------*/
+
+void vTaskPlaceOnEventList( List_t * const pxEventList, const TickType_t xTicksToWait )
+{
+TickType_t xTimeToWake;
+
+	configASSERT( pxEventList );
+
+	/* THIS FUNCTION MUST BE CALLED WITH EITHER INTERRUPTS DISABLED OR THE
+	SCHEDULER SUSPENDED AND THE QUEUE BEING ACCESSED LOCKED. */
+
+	/* Place the event list item of the TCB in the appropriate event list.
+	This is placed in the list in priority order so the highest priority task
+	is the first to be woken by the event.  The queue that contains the event
+	list is locked, preventing simultaneous access from interrupts. */
+	vListInsert( pxEventList, &( pxCurrentTCB->xEventListItem ) );
+
+	/* The task must be removed from from the ready list before it is added to
+	the blocked list as the same list item is used for both lists.  Exclusive
+	access to the ready lists guaranteed because the scheduler is locked. */
+	if( uxListRemove( &( pxCurrentTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+	{
+		/* The current task must be in a ready list, so there is no need to
+		check, and the port reset macro can be called directly. */
+		portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority );
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	#if ( INCLUDE_vTaskSuspend == 1 )
+	{
+		if( xTicksToWait == portMAX_DELAY )
+		{
+			/* Add the task to the suspended task list instead of a delayed task
+			list to ensure the task is not woken by a timing event.  It will
+			block indefinitely. */
+			vListInsertEnd( &xSuspendedTaskList, &( pxCurrentTCB->xGenericListItem ) );
+		}
+		else
+		{
+			/* Calculate the time at which the task should be woken if the event
+			does not occur.  This may overflow but this doesn't matter, the
+			scheduler will handle it. */
+			xTimeToWake = xTickCount + xTicksToWait;
+			prvAddCurrentTaskToDelayedList( xTimeToWake );
+		}
+	}
+	#else /* INCLUDE_vTaskSuspend */
+	{
+			/* Calculate the time at which the task should be woken if the event does
+			not occur.  This may overflow but this doesn't matter, the scheduler
+			will handle it. */
+			xTimeToWake = xTickCount + xTicksToWait;
+			prvAddCurrentTaskToDelayedList( xTimeToWake );
+	}
+	#endif /* INCLUDE_vTaskSuspend */
+}
+/*-----------------------------------------------------------*/
+
+void vTaskPlaceOnUnorderedEventList( List_t * pxEventList, const TickType_t xItemValue, const TickType_t xTicksToWait )
+{
+TickType_t xTimeToWake;
+
+	configASSERT( pxEventList );
+
+	/* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED.  It is used by
+	the event groups implementation. */
+	configASSERT( uxSchedulerSuspended != 0 );
+
+	/* Store the item value in the event list item.  It is safe to access the
+	event list item here as interrupts won't access the event list item of a
+	task that is not in the Blocked state. */
+	listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ), xItemValue | taskEVENT_LIST_ITEM_VALUE_IN_USE );
+
+	/* Place the event list item of the TCB at the end of the appropriate event
+	list.  It is safe to access the event list here because it is part of an
+	event group implementation - and interrupts don't access event groups
+	directly (instead they access them indirectly by pending function calls to
+	the task level). */
+	vListInsertEnd( pxEventList, &( pxCurrentTCB->xEventListItem ) );
+
+	/* The task must be removed from the ready list before it is added to the
+	blocked list.  Exclusive access can be assured to the ready list as the
+	scheduler is locked. */
+	if( uxListRemove( &( pxCurrentTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+	{
+		/* The current task must be in a ready list, so there is no need to
+		check, and the port reset macro can be called directly. */
+		portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority );
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	#if ( INCLUDE_vTaskSuspend == 1 )
+	{
+		if( xTicksToWait == portMAX_DELAY )
+		{
+			/* Add the task to the suspended task list instead of a delayed task
+			list to ensure it is not woken by a timing event.  It will block
+			indefinitely. */
+			vListInsertEnd( &xSuspendedTaskList, &( pxCurrentTCB->xGenericListItem ) );
+		}
+		else
+		{
+			/* Calculate the time at which the task should be woken if the event
+			does not occur.  This may overflow but this doesn't matter, the
+			kernel will manage it correctly. */
+			xTimeToWake = xTickCount + xTicksToWait;
+			prvAddCurrentTaskToDelayedList( xTimeToWake );
+		}
+	}
+	#else /* INCLUDE_vTaskSuspend */
+	{
+			/* Calculate the time at which the task should be woken if the event does
+			not occur.  This may overflow but this doesn't matter, the kernel
+			will manage it correctly. */
+			xTimeToWake = xTickCount + xTicksToWait;
+			prvAddCurrentTaskToDelayedList( xTimeToWake );
+	}
+	#endif /* INCLUDE_vTaskSuspend */
+}
+/*-----------------------------------------------------------*/
+
+#if configUSE_TIMERS == 1
+
+	void vTaskPlaceOnEventListRestricted( List_t * const pxEventList, const TickType_t xTicksToWait, const BaseType_t xWaitIndefinitely )
+	{
+	TickType_t xTimeToWake;
+
+		configASSERT( pxEventList );
+
+		/* This function should not be called by application code hence the
+		'Restricted' in its name.  It is not part of the public API.  It is
+		designed for use by kernel code, and has special calling requirements -
+		it should be called with the scheduler suspended. */
+
+
+		/* Place the event list item of the TCB in the appropriate event list.
+		In this case it is assume that this is the only task that is going to
+		be waiting on this event list, so the faster vListInsertEnd() function
+		can be used in place of vListInsert. */
+		vListInsertEnd( pxEventList, &( pxCurrentTCB->xEventListItem ) );
+
+		/* We must remove this task from the ready list before adding it to the
+		blocked list as the same list item is used for both lists.  This
+		function is called with the scheduler locked so interrupts will not
+		access the lists at the same time. */
+		if( uxListRemove( &( pxCurrentTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+		{
+			/* The current task must be in a ready list, so there is no need to
+			check, and the port reset macro can be called directly. */
+			portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority );
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		/* If vTaskSuspend() is available then the suspended task list is also
+		available and a task that is blocking indefinitely can enter the
+		suspended state (it is not really suspended as it will re-enter the
+		Ready state when the event it is waiting indefinitely for occurs).
+		Blocking indefinitely is useful when using tickless idle mode as when
+		all tasks are blocked indefinitely all timers can be turned off. */
+		#if( INCLUDE_vTaskSuspend == 1 )
+		{
+			if( xWaitIndefinitely == pdTRUE )
+			{
+				/* Add the task to the suspended task list instead of a delayed
+				task list to ensure the task is not woken by a timing event.  It
+				will block indefinitely. */
+				vListInsertEnd( &xSuspendedTaskList, &( pxCurrentTCB->xGenericListItem ) );
+			}
+			else
+			{
+				/* Calculate the time at which the task should be woken if the
+				event does not occur.  This may overflow but this doesn't
+				matter. */
+				xTimeToWake = xTickCount + xTicksToWait;
+				traceTASK_DELAY_UNTIL();
+				prvAddCurrentTaskToDelayedList( xTimeToWake );
+			}
+		}
+		#else
+		{
+			/* Calculate the time at which the task should be woken if the event
+			does not occur.  This may overflow but this doesn't matter. */
+			xTimeToWake = xTickCount + xTicksToWait;
+			traceTASK_DELAY_UNTIL();
+			prvAddCurrentTaskToDelayedList( xTimeToWake );
+
+			/* Remove compiler warnings when INCLUDE_vTaskSuspend() is not
+			defined. */
+			( void ) xWaitIndefinitely;
+		}
+		#endif
+	}
+
+#endif /* configUSE_TIMERS */
+/*-----------------------------------------------------------*/
+
+BaseType_t xTaskRemoveFromEventList( const List_t * const pxEventList )
+{
+TCB_t *pxUnblockedTCB;
+BaseType_t xReturn;
+
+	/* THIS FUNCTION MUST BE CALLED FROM A CRITICAL SECTION.  It can also be
+	called from a critical section within an ISR. */
+
+	/* The event list is sorted in priority order, so the first in the list can
+	be removed as it is known to be the highest priority.  Remove the TCB from
+	the delayed list, and add it to the ready list.
+
+	If an event is for a queue that is locked then this function will never
+	get called - the lock count on the queue will get modified instead.  This
+	means exclusive access to the event list is guaranteed here.
+
+	This function assumes that a check has already been made to ensure that
+	pxEventList is not empty. */
+	pxUnblockedTCB = ( TCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList );
+	configASSERT( pxUnblockedTCB );
+	( void ) uxListRemove( &( pxUnblockedTCB->xEventListItem ) );
+
+	if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE )
+	{
+		( void ) uxListRemove( &( pxUnblockedTCB->xGenericListItem ) );
+		prvAddTaskToReadyList( pxUnblockedTCB );
+	}
+	else
+	{
+		/* The delayed and ready lists cannot be accessed, so hold this task
+		pending until the scheduler is resumed. */
+		vListInsertEnd( &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) );
+	}
+
+	if( pxUnblockedTCB->uxPriority > pxCurrentTCB->uxPriority )
+	{
+		/* Return true if the task removed from the event list has a higher
+		priority than the calling task.  This allows the calling task to know if
+		it should force a context switch now. */
+		xReturn = pdTRUE;
+
+		/* Mark that a yield is pending in case the user is not using the
+		"xHigherPriorityTaskWoken" parameter to an ISR safe FreeRTOS function. */
+		xYieldPending = pdTRUE;
+	}
+	else
+	{
+		xReturn = pdFALSE;
+	}
+
+	#if( configUSE_TICKLESS_IDLE != 0 )
+	{
+		/* If a task is blocked on a kernel object then xNextTaskUnblockTime
+		might be set to the blocked task's time out time.  If the task is
+		unblocked for a reason other than a timeout xNextTaskUnblockTime is
+		normally left unchanged, because it is automatically reset to a new
+		value when the tick count equals xNextTaskUnblockTime.  However if
+		tickless idling is used it might be more important to enter sleep mode
+		at the earliest possible time - so reset xNextTaskUnblockTime here to
+		ensure it is updated at the earliest possible time. */
+		prvResetNextTaskUnblockTime();
+	}
+	#endif
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xTaskRemoveFromUnorderedEventList( ListItem_t * pxEventListItem, const TickType_t xItemValue )
+{
+TCB_t *pxUnblockedTCB;
+BaseType_t xReturn;
+
+	/* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED.  It is used by
+	the event flags implementation. */
+	configASSERT( uxSchedulerSuspended != pdFALSE );
+
+	/* Store the new item value in the event list. */
+	listSET_LIST_ITEM_VALUE( pxEventListItem, xItemValue | taskEVENT_LIST_ITEM_VALUE_IN_USE );
+
+	/* Remove the event list form the event flag.  Interrupts do not access
+	event flags. */
+	pxUnblockedTCB = ( TCB_t * ) listGET_LIST_ITEM_OWNER( pxEventListItem );
+	configASSERT( pxUnblockedTCB );
+	( void ) uxListRemove( pxEventListItem );
+
+	/* Remove the task from the delayed list and add it to the ready list.  The
+	scheduler is suspended so interrupts will not be accessing the ready
+	lists. */
+	( void ) uxListRemove( &( pxUnblockedTCB->xGenericListItem ) );
+	prvAddTaskToReadyList( pxUnblockedTCB );
+
+	if( pxUnblockedTCB->uxPriority > pxCurrentTCB->uxPriority )
+	{
+		/* Return true if the task removed from the event list has
+		a higher priority than the calling task.  This allows
+		the calling task to know if it should force a context
+		switch now. */
+		xReturn = pdTRUE;
+
+		/* Mark that a yield is pending in case the user is not using the
+		"xHigherPriorityTaskWoken" parameter to an ISR safe FreeRTOS function. */
+		xYieldPending = pdTRUE;
+	}
+	else
+	{
+		xReturn = pdFALSE;
+	}
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vTaskSetTimeOutState( TimeOut_t * const pxTimeOut )
+{
+	configASSERT( pxTimeOut );
+	pxTimeOut->xOverflowCount = xNumOfOverflows;
+	pxTimeOut->xTimeOnEntering = xTickCount;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xTaskCheckForTimeOut( TimeOut_t * const pxTimeOut, TickType_t * const pxTicksToWait )
+{
+BaseType_t xReturn;
+
+	configASSERT( pxTimeOut );
+	configASSERT( pxTicksToWait );
+
+	taskENTER_CRITICAL();
+	{
+		/* Minor optimisation.  The tick count cannot change in this block. */
+		const TickType_t xConstTickCount = xTickCount;
+
+		#if ( INCLUDE_vTaskSuspend == 1 )
+			/* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is
+			the maximum block time then the task should block indefinitely, and
+			therefore never time out. */
+			if( *pxTicksToWait == portMAX_DELAY )
+			{
+				xReturn = pdFALSE;
+			}
+			else /* We are not blocking indefinitely, perform the checks below. */
+		#endif
+
+		if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( xConstTickCount >= pxTimeOut->xTimeOnEntering ) ) /*lint !e525 Indentation preferred as is to make code within pre-processor directives clearer. */
+		{
+			/* The tick count is greater than the time at which vTaskSetTimeout()
+			was called, but has also overflowed since vTaskSetTimeOut() was called.
+			It must have wrapped all the way around and gone past us again. This
+			passed since vTaskSetTimeout() was called. */
+			xReturn = pdTRUE;
+		}
+		else if( ( xConstTickCount - pxTimeOut->xTimeOnEntering ) < *pxTicksToWait )
+		{
+			/* Not a genuine timeout. Adjust parameters for time remaining. */
+			*pxTicksToWait -= ( xConstTickCount -  pxTimeOut->xTimeOnEntering );
+			vTaskSetTimeOutState( pxTimeOut );
+			xReturn = pdFALSE;
+		}
+		else
+		{
+			xReturn = pdTRUE;
+		}
+	}
+	taskEXIT_CRITICAL();
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vTaskMissedYield( void )
+{
+	xYieldPending = pdTRUE;
+}
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	UBaseType_t uxTaskGetTaskNumber( TaskHandle_t xTask )
+	{
+	UBaseType_t uxReturn;
+	TCB_t *pxTCB;
+
+		if( xTask != NULL )
+		{
+			pxTCB = ( TCB_t * ) xTask;
+			uxReturn = pxTCB->uxTaskNumber;
+		}
+		else
+		{
+			uxReturn = 0U;
+		}
+
+		return uxReturn;
+	}
+
+#endif /* configUSE_TRACE_FACILITY */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	void vTaskSetTaskNumber( TaskHandle_t xTask, const UBaseType_t uxHandle )
+	{
+	TCB_t *pxTCB;
+
+		if( xTask != NULL )
+		{
+			pxTCB = ( TCB_t * ) xTask;
+			pxTCB->uxTaskNumber = uxHandle;
+		}
+	}
+
+#endif /* configUSE_TRACE_FACILITY */
+
+/*
+ * -----------------------------------------------------------
+ * The Idle task.
+ * ----------------------------------------------------------
+ *
+ * The portTASK_FUNCTION() macro is used to allow port/compiler specific
+ * language extensions.  The equivalent prototype for this function is:
+ *
+ * void prvIdleTask( void *pvParameters );
+ *
+ */
+static portTASK_FUNCTION( prvIdleTask, pvParameters )
+{
+	/* Stop warnings. */
+	( void ) pvParameters;
+
+	for( ;; )
+	{
+		/* See if any tasks have been deleted. */
+		prvCheckTasksWaitingTermination();
+
+		#if ( configUSE_PREEMPTION == 0 )
+		{
+			/* If we are not using preemption we keep forcing a task switch to
+			see if any other task has become available.  If we are using
+			preemption we don't need to do this as any task becoming available
+			will automatically get the processor anyway. */
+			taskYIELD();
+		}
+		#endif /* configUSE_PREEMPTION */
+
+		#if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) )
+		{
+			/* When using preemption tasks of equal priority will be
+			timesliced.  If a task that is sharing the idle priority is ready
+			to run then the idle task should yield before the end of the
+			timeslice.
+
+			A critical region is not required here as we are just reading from
+			the list, and an occasional incorrect value will not matter.  If
+			the ready list at the idle priority contains more than one task
+			then a task other than the idle task is ready to execute. */
+			if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( UBaseType_t ) 1 )
+			{
+				taskYIELD();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		#endif /* ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) */
+
+		#if ( configUSE_IDLE_HOOK == 1 )
+		{
+			extern void vApplicationIdleHook( void );
+
+			/* Call the user defined function from within the idle task.  This
+			allows the application designer to add background functionality
+			without the overhead of a separate task.
+			NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES,
+			CALL A FUNCTION THAT MIGHT BLOCK. */
+			vApplicationIdleHook();
+		}
+		#endif /* configUSE_IDLE_HOOK */
+
+		/* This conditional compilation should use inequality to 0, not equality
+		to 1.  This is to ensure portSUPPRESS_TICKS_AND_SLEEP() is called when
+		user defined low power mode	implementations require
+		configUSE_TICKLESS_IDLE to be set to a value other than 1. */
+		#if ( configUSE_TICKLESS_IDLE != 0 )
+		{
+		TickType_t xExpectedIdleTime;
+
+			/* It is not desirable to suspend then resume the scheduler on
+			each iteration of the idle task.  Therefore, a preliminary
+			test of the expected idle time is performed without the
+			scheduler suspended.  The result here is not necessarily
+			valid. */
+			xExpectedIdleTime = prvGetExpectedIdleTime();
+
+			if( xExpectedIdleTime >= configEXPECTED_IDLE_TIME_BEFORE_SLEEP )
+			{
+				vTaskSuspendAll();
+				{
+					/* Now the scheduler is suspended, the expected idle
+					time can be sampled again, and this time its value can
+					be used. */
+					configASSERT( xNextTaskUnblockTime >= xTickCount );
+					xExpectedIdleTime = prvGetExpectedIdleTime();
+
+					if( xExpectedIdleTime >= configEXPECTED_IDLE_TIME_BEFORE_SLEEP )
+					{
+						traceLOW_POWER_IDLE_BEGIN();
+						portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime );
+						traceLOW_POWER_IDLE_END();
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+				}
+				( void ) xTaskResumeAll();
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		#endif /* configUSE_TICKLESS_IDLE */
+	}
+}
+/*-----------------------------------------------------------*/
+
+#if( configUSE_TICKLESS_IDLE != 0 )
+
+	eSleepModeStatus eTaskConfirmSleepModeStatus( void )
+	{
+	/* The idle task exists in addition to the application tasks. */
+	const UBaseType_t uxNonApplicationTasks = 1;
+	eSleepModeStatus eReturn = eStandardSleep;
+
+		if( listCURRENT_LIST_LENGTH( &xPendingReadyList ) != 0 )
+		{
+			/* A task was made ready while the scheduler was suspended. */
+			eReturn = eAbortSleep;
+		}
+		else if( xYieldPending != pdFALSE )
+		{
+			/* A yield was pended while the scheduler was suspended. */
+			eReturn = eAbortSleep;
+		}
+		else
+		{
+			/* If all the tasks are in the suspended list (which might mean they
+			have an infinite block time rather than actually being suspended)
+			then it is safe to turn all clocks off and just wait for external
+			interrupts. */
+			if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == ( uxCurrentNumberOfTasks - uxNonApplicationTasks ) )
+			{
+				eReturn = eNoTasksWaitingTimeout;
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+
+		return eReturn;
+	}
+
+#endif /* configUSE_TICKLESS_IDLE */
+/*-----------------------------------------------------------*/
+
+static void prvInitialiseTCBVariables( TCB_t * const pxTCB, const char * const pcName, UBaseType_t uxPriority, const MemoryRegion_t * const xRegions, const uint16_t usStackDepth ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+{
+UBaseType_t x;
+
+	/* Store the task name in the TCB. */
+	for( x = ( UBaseType_t ) 0; x < ( UBaseType_t ) configMAX_TASK_NAME_LEN; x++ )
+	{
+		pxTCB->pcTaskName[ x ] = pcName[ x ];
+
+		/* Don't copy all configMAX_TASK_NAME_LEN if the string is shorter than
+		configMAX_TASK_NAME_LEN characters just in case the memory after the
+		string is not accessible (extremely unlikely). */
+		if( pcName[ x ] == 0x00 )
+		{
+			break;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+	/* Ensure the name string is terminated in the case that the string length
+	was greater or equal to configMAX_TASK_NAME_LEN. */
+	pxTCB->pcTaskName[ configMAX_TASK_NAME_LEN - 1 ] = '\0';
+
+	/* This is used as an array index so must ensure it's not too large.  First
+	remove the privilege bit if one is present. */
+	if( uxPriority >= ( UBaseType_t ) configMAX_PRIORITIES )
+	{
+		uxPriority = ( UBaseType_t ) configMAX_PRIORITIES - ( UBaseType_t ) 1U;
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	pxTCB->uxPriority = uxPriority;
+	#if ( configUSE_MUTEXES == 1 )
+	{
+		pxTCB->uxBasePriority = uxPriority;
+		pxTCB->uxMutexesHeld = 0;
+	}
+	#endif /* configUSE_MUTEXES */
+
+	vListInitialiseItem( &( pxTCB->xGenericListItem ) );
+	vListInitialiseItem( &( pxTCB->xEventListItem ) );
+
+	/* Set the pxTCB as a link back from the ListItem_t.  This is so we can get
+	back to	the containing TCB from a generic item in a list. */
+	listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB );
+
+	/* Event lists are always in priority order. */
+	listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+	listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB );
+
+	#if ( portCRITICAL_NESTING_IN_TCB == 1 )
+	{
+		pxTCB->uxCriticalNesting = ( UBaseType_t ) 0U;
+	}
+	#endif /* portCRITICAL_NESTING_IN_TCB */
+
+	#if ( configUSE_APPLICATION_TASK_TAG == 1 )
+	{
+		pxTCB->pxTaskTag = NULL;
+	}
+	#endif /* configUSE_APPLICATION_TASK_TAG */
+
+	#if ( configGENERATE_RUN_TIME_STATS == 1 )
+	{
+		pxTCB->ulRunTimeCounter = 0UL;
+	}
+	#endif /* configGENERATE_RUN_TIME_STATS */
+
+	#if ( portUSING_MPU_WRAPPERS == 1 )
+	{
+		vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth );
+	}
+	#else /* portUSING_MPU_WRAPPERS */
+	{
+		( void ) xRegions;
+		( void ) usStackDepth;
+	}
+	#endif /* portUSING_MPU_WRAPPERS */
+
+	#if( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 )
+	{
+		for( x = 0; x < ( UBaseType_t ) configNUM_THREAD_LOCAL_STORAGE_POINTERS; x++ )
+		{
+			pxTCB->pvThreadLocalStoragePointers[ x ] = NULL;
+		}
+	}
+	#endif
+
+	#if ( configUSE_TASK_NOTIFICATIONS == 1 )
+	{
+		pxTCB->ulNotifiedValue = 0;
+		pxTCB->eNotifyState = eNotWaitingNotification;
+	}
+	#endif
+
+	#if ( configUSE_NEWLIB_REENTRANT == 1 )
+	{
+		/* Initialise this task's Newlib reent structure. */
+		_REENT_INIT_PTR( ( &( pxTCB->xNewLib_reent ) ) );
+	}
+	#endif /* configUSE_NEWLIB_REENTRANT */
+}
+/*-----------------------------------------------------------*/
+
+#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 )
+
+	void vTaskSetThreadLocalStoragePointer( TaskHandle_t xTaskToSet, BaseType_t xIndex, void *pvValue )
+	{
+	TCB_t *pxTCB;
+
+		if( xIndex < configNUM_THREAD_LOCAL_STORAGE_POINTERS )
+		{
+			pxTCB = prvGetTCBFromHandle( xTaskToSet );
+			pxTCB->pvThreadLocalStoragePointers[ xIndex ] = pvValue;
+		}
+	}
+
+#endif /* configNUM_THREAD_LOCAL_STORAGE_POINTERS */
+/*-----------------------------------------------------------*/
+
+#if ( configNUM_THREAD_LOCAL_STORAGE_POINTERS != 0 )
+
+	void *pvTaskGetThreadLocalStoragePointer( TaskHandle_t xTaskToQuery, BaseType_t xIndex )
+	{
+	void *pvReturn = NULL;
+	TCB_t *pxTCB;
+
+		if( xIndex < configNUM_THREAD_LOCAL_STORAGE_POINTERS )
+		{
+			pxTCB = prvGetTCBFromHandle( xTaskToQuery );
+			pvReturn = pxTCB->pvThreadLocalStoragePointers[ xIndex ];
+		}
+		else
+		{
+			pvReturn = NULL;
+		}
+
+		return pvReturn;
+	}
+
+#endif /* configNUM_THREAD_LOCAL_STORAGE_POINTERS */
+/*-----------------------------------------------------------*/
+
+#if ( portUSING_MPU_WRAPPERS == 1 )
+
+	void vTaskAllocateMPURegions( TaskHandle_t xTaskToModify, const MemoryRegion_t * const xRegions )
+	{
+	TCB_t *pxTCB;
+
+		/* If null is passed in here then we are modifying the MPU settings of
+		the calling task. */
+		pxTCB = prvGetTCBFromHandle( xTaskToModify );
+
+        vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 );
+	}
+
+#endif /* portUSING_MPU_WRAPPERS */
+/*-----------------------------------------------------------*/
+
+static void prvInitialiseTaskLists( void )
+{
+UBaseType_t uxPriority;
+
+	for( uxPriority = ( UBaseType_t ) 0U; uxPriority < ( UBaseType_t ) configMAX_PRIORITIES; uxPriority++ )
+	{
+		vListInitialise( &( pxReadyTasksLists[ uxPriority ] ) );
+	}
+
+	vListInitialise( &xDelayedTaskList1 );
+	vListInitialise( &xDelayedTaskList2 );
+	vListInitialise( &xPendingReadyList );
+
+	#if ( INCLUDE_vTaskDelete == 1 )
+	{
+		vListInitialise( &xTasksWaitingTermination );
+	}
+	#endif /* INCLUDE_vTaskDelete */
+
+	#if ( INCLUDE_vTaskSuspend == 1 )
+	{
+		vListInitialise( &xSuspendedTaskList );
+	}
+	#endif /* INCLUDE_vTaskSuspend */
+
+	/* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList
+	using list2. */
+	pxDelayedTaskList = &xDelayedTaskList1;
+	pxOverflowDelayedTaskList = &xDelayedTaskList2;
+}
+/*-----------------------------------------------------------*/
+
+static void prvCheckTasksWaitingTermination( void )
+{
+	#if ( INCLUDE_vTaskDelete == 1 )
+	{
+		BaseType_t xListIsEmpty;
+
+		/* ucTasksDeleted is used to prevent vTaskSuspendAll() being called
+		too often in the idle task. */
+		while( uxTasksDeleted > ( UBaseType_t ) 0U )
+		{
+			vTaskSuspendAll();
+			{
+				xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination );
+			}
+			( void ) xTaskResumeAll();
+
+			if( xListIsEmpty == pdFALSE )
+			{
+				TCB_t *pxTCB;
+
+				taskENTER_CRITICAL();
+				{
+					pxTCB = ( TCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( ( &xTasksWaitingTermination ) );
+					( void ) uxListRemove( &( pxTCB->xGenericListItem ) );
+					--uxCurrentNumberOfTasks;
+					--uxTasksDeleted;
+				}
+				taskEXIT_CRITICAL();
+
+				prvDeleteTCB( pxTCB );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+	}
+	#endif /* vTaskDelete */
+}
+/*-----------------------------------------------------------*/
+
+static void prvAddCurrentTaskToDelayedList( const TickType_t xTimeToWake )
+{
+	/* The list item will be inserted in wake time order. */
+	listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake );
+
+	if( xTimeToWake < xTickCount )
+	{
+		/* Wake time has overflowed.  Place this item in the overflow list. */
+		vListInsert( pxOverflowDelayedTaskList, &( pxCurrentTCB->xGenericListItem ) );
+	}
+	else
+	{
+		/* The wake time has not overflowed, so the current block list is used. */
+		vListInsert( pxDelayedTaskList, &( pxCurrentTCB->xGenericListItem ) );
+
+		/* If the task entering the blocked state was placed at the head of the
+		list of blocked tasks then xNextTaskUnblockTime needs to be updated
+		too. */
+		if( xTimeToWake < xNextTaskUnblockTime )
+		{
+			xNextTaskUnblockTime = xTimeToWake;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+}
+/*-----------------------------------------------------------*/
+
+static TCB_t *prvAllocateTCBAndStack( const uint16_t usStackDepth, StackType_t * const puxStackBuffer )
+{
+TCB_t *pxNewTCB;
+
+	/* If the stack grows down then allocate the stack then the TCB so the stack
+	does not grow into the TCB.  Likewise if the stack grows up then allocate
+	the TCB then the stack. */
+	#if( portSTACK_GROWTH > 0 )
+	{
+		/* Allocate space for the TCB.  Where the memory comes from depends on
+		the implementation of the port malloc function. */
+		pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) );
+
+		if( pxNewTCB != NULL )
+		{
+			/* Allocate space for the stack used by the task being created.
+			The base of the stack memory stored in the TCB so the task can
+			be deleted later if required. */
+			pxNewTCB->pxStack = ( StackType_t * ) pvPortMallocAligned( ( ( ( size_t ) usStackDepth ) * sizeof( StackType_t ) ), puxStackBuffer ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+
+			if( pxNewTCB->pxStack == NULL )
+			{
+				/* Could not allocate the stack.  Delete the allocated TCB. */
+				vPortFree( pxNewTCB );
+				pxNewTCB = NULL;
+			}
+		}
+	}
+	#else /* portSTACK_GROWTH */
+	{
+	StackType_t *pxStack;
+
+		/* Allocate space for the stack used by the task being created. */
+		pxStack = ( StackType_t * ) pvPortMallocAligned( ( ( ( size_t ) usStackDepth ) * sizeof( StackType_t ) ), puxStackBuffer ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+
+		if( pxStack != NULL )
+		{
+			/* Allocate space for the TCB.  Where the memory comes from depends
+			on the implementation of the port malloc function. */
+			pxNewTCB = ( TCB_t * ) pvPortMalloc( sizeof( TCB_t ) );
+
+			if( pxNewTCB != NULL )
+			{
+				/* Store the stack location in the TCB. */
+				pxNewTCB->pxStack = pxStack;
+			}
+			else
+			{
+				/* The stack cannot be used as the TCB was not created.  Free it
+				again. */
+				vPortFree( pxStack );
+			}
+		}
+		else
+		{
+			pxNewTCB = NULL;
+		}
+	}
+	#endif /* portSTACK_GROWTH */
+
+	if( pxNewTCB != NULL )
+	{
+		/* Avoid dependency on memset() if it is not required. */
+		#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) || ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) )
+		{
+			/* Just to help debugging. */
+			( void ) memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( StackType_t ) );
+		}
+		#endif /* ( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) || ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) ) */
+	}
+
+	return pxNewTCB;
+}
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_TRACE_FACILITY == 1 )
+
+	static UBaseType_t prvListTaskWithinSingleList( TaskStatus_t *pxTaskStatusArray, List_t *pxList, eTaskState eState )
+	{
+	volatile TCB_t *pxNextTCB, *pxFirstTCB;
+	UBaseType_t uxTask = 0;
+
+		if( listCURRENT_LIST_LENGTH( pxList ) > ( UBaseType_t ) 0 )
+		{
+			listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList );
+
+			/* Populate an TaskStatus_t structure within the
+			pxTaskStatusArray array for each task that is referenced from
+			pxList.  See the definition of TaskStatus_t in task.h for the
+			meaning of each TaskStatus_t structure member. */
+			do
+			{
+				listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList );
+
+				pxTaskStatusArray[ uxTask ].xHandle = ( TaskHandle_t ) pxNextTCB;
+				pxTaskStatusArray[ uxTask ].pcTaskName = ( const char * ) &( pxNextTCB->pcTaskName [ 0 ] );
+				pxTaskStatusArray[ uxTask ].xTaskNumber = pxNextTCB->uxTCBNumber;
+				pxTaskStatusArray[ uxTask ].eCurrentState = eState;
+				pxTaskStatusArray[ uxTask ].uxCurrentPriority = pxNextTCB->uxPriority;
+
+				#if ( INCLUDE_vTaskSuspend == 1 )
+				{
+					/* If the task is in the suspended list then there is a chance
+					it is actually just blocked indefinitely - so really it should
+					be reported as being in the Blocked state. */
+					if( eState == eSuspended )
+					{
+						if( listLIST_ITEM_CONTAINER( &( pxNextTCB->xEventListItem ) ) != NULL )
+						{
+							pxTaskStatusArray[ uxTask ].eCurrentState = eBlocked;
+						}
+					}
+				}
+				#endif /* INCLUDE_vTaskSuspend */
+
+				#if ( configUSE_MUTEXES == 1 )
+				{
+					pxTaskStatusArray[ uxTask ].uxBasePriority = pxNextTCB->uxBasePriority;
+				}
+				#else
+				{
+					pxTaskStatusArray[ uxTask ].uxBasePriority = 0;
+				}
+				#endif
+
+				#if ( configGENERATE_RUN_TIME_STATS == 1 )
+				{
+					pxTaskStatusArray[ uxTask ].ulRunTimeCounter = pxNextTCB->ulRunTimeCounter;
+				}
+				#else
+				{
+					pxTaskStatusArray[ uxTask ].ulRunTimeCounter = 0;
+				}
+				#endif
+
+				#if ( portSTACK_GROWTH > 0 )
+				{
+					pxTaskStatusArray[ uxTask ].usStackHighWaterMark = prvTaskCheckFreeStackSpace( ( uint8_t * ) pxNextTCB->pxEndOfStack );
+				}
+				#else
+				{
+					pxTaskStatusArray[ uxTask ].usStackHighWaterMark = prvTaskCheckFreeStackSpace( ( uint8_t * ) pxNextTCB->pxStack );
+				}
+				#endif
+
+				uxTask++;
+
+			} while( pxNextTCB != pxFirstTCB );
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		return uxTask;
+	}
+
+#endif /* configUSE_TRACE_FACILITY */
+/*-----------------------------------------------------------*/
+
+#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) )
+
+	static uint16_t prvTaskCheckFreeStackSpace( const uint8_t * pucStackByte )
+	{
+	uint32_t ulCount = 0U;
+
+		while( *pucStackByte == ( uint8_t ) tskSTACK_FILL_BYTE )
+		{
+			pucStackByte -= portSTACK_GROWTH;
+			ulCount++;
+		}
+
+		ulCount /= ( uint32_t ) sizeof( StackType_t ); /*lint !e961 Casting is not redundant on smaller architectures. */
+
+		return ( uint16_t ) ulCount;
+	}
+
+#endif /* ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 )
+
+	UBaseType_t uxTaskGetStackHighWaterMark( TaskHandle_t xTask )
+	{
+	TCB_t *pxTCB;
+	uint8_t *pucEndOfStack;
+	UBaseType_t uxReturn;
+
+		pxTCB = prvGetTCBFromHandle( xTask );
+
+		#if portSTACK_GROWTH < 0
+		{
+			pucEndOfStack = ( uint8_t * ) pxTCB->pxStack;
+		}
+		#else
+		{
+			pucEndOfStack = ( uint8_t * ) pxTCB->pxEndOfStack;
+		}
+		#endif
+
+		uxReturn = ( UBaseType_t ) prvTaskCheckFreeStackSpace( pucEndOfStack );
+
+		return uxReturn;
+	}
+
+#endif /* INCLUDE_uxTaskGetStackHighWaterMark */
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_vTaskDelete == 1 )
+
+	static void prvDeleteTCB( TCB_t *pxTCB )
+	{
+		/* This call is required specifically for the TriCore port.  It must be
+		above the vPortFree() calls.  The call is also used by ports/demos that
+		want to allocate and clean RAM statically. */
+		portCLEAN_UP_TCB( pxTCB );
+
+		/* Free up the memory allocated by the scheduler for the task.  It is up
+		to the task to free any memory allocated at the application level. */
+		#if ( configUSE_NEWLIB_REENTRANT == 1 )
+		{
+			_reclaim_reent( &( pxTCB->xNewLib_reent ) );
+		}
+		#endif /* configUSE_NEWLIB_REENTRANT */
+
+		#if( portUSING_MPU_WRAPPERS == 1 )
+		{
+			/* Only free the stack if it was allocated dynamically in the first
+			place. */
+			if( pxTCB->xUsingStaticallyAllocatedStack == pdFALSE )
+			{
+				vPortFreeAligned( pxTCB->pxStack );
+			}
+		}
+		#else
+		{
+			vPortFreeAligned( pxTCB->pxStack );
+		}
+		#endif
+
+		vPortFree( pxTCB );
+	}
+
+#endif /* INCLUDE_vTaskDelete */
+/*-----------------------------------------------------------*/
+
+static void prvResetNextTaskUnblockTime( void )
+{
+TCB_t *pxTCB;
+
+	if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE )
+	{
+		/* The new current delayed list is empty.  Set xNextTaskUnblockTime to
+		the maximum possible value so it is	extremely unlikely that the
+		if( xTickCount >= xNextTaskUnblockTime ) test will pass until
+		there is an item in the delayed list. */
+		xNextTaskUnblockTime = portMAX_DELAY;
+	}
+	else
+	{
+		/* The new current delayed list is not empty, get the value of
+		the item at the head of the delayed list.  This is the time at
+		which the task at the head of the delayed list should be removed
+		from the Blocked state. */
+		( pxTCB ) = ( TCB_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList );
+		xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( ( pxTCB )->xGenericListItem ) );
+	}
+}
+/*-----------------------------------------------------------*/
+
+#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) )
+
+	TaskHandle_t xTaskGetCurrentTaskHandle( void )
+	{
+	TaskHandle_t xReturn;
+
+		/* A critical section is not required as this is not called from
+		an interrupt and the current TCB will always be the same for any
+		individual execution thread. */
+		xReturn = pxCurrentTCB;
+
+		return xReturn;
+	}
+
+#endif /* ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) */
+/*-----------------------------------------------------------*/
+
+#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) )
+
+	BaseType_t xTaskGetSchedulerState( void )
+	{
+	BaseType_t xReturn;
+
+		if( xSchedulerRunning == pdFALSE )
+		{
+			xReturn = taskSCHEDULER_NOT_STARTED;
+		}
+		else
+		{
+			if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE )
+			{
+				xReturn = taskSCHEDULER_RUNNING;
+			}
+			else
+			{
+				xReturn = taskSCHEDULER_SUSPENDED;
+			}
+		}
+
+		return xReturn;
+	}
+
+#endif /* ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_MUTEXES == 1 )
+
+	void vTaskPriorityInherit( TaskHandle_t const pxMutexHolder )
+	{
+	TCB_t * const pxTCB = ( TCB_t * ) pxMutexHolder;
+
+		/* If the mutex was given back by an interrupt while the queue was
+		locked then the mutex holder might now be NULL. */
+		if( pxMutexHolder != NULL )
+		{
+			/* If the holder of the mutex has a priority below the priority of
+			the task attempting to obtain the mutex then it will temporarily
+			inherit the priority of the task attempting to obtain the mutex. */
+			if( pxTCB->uxPriority < pxCurrentTCB->uxPriority )
+			{
+				/* Adjust the mutex holder state to account for its new
+				priority.  Only reset the event list item value if the value is
+				not	being used for anything else. */
+				if( ( listGET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ) ) & taskEVENT_LIST_ITEM_VALUE_IN_USE ) == 0UL )
+				{
+					listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxCurrentTCB->uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+
+				/* If the task being modified is in the ready state it will need
+				to be moved into a new list. */
+				if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE )
+				{
+					if( uxListRemove( &( pxTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+					{
+						taskRESET_READY_PRIORITY( pxTCB->uxPriority );
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					/* Inherit the priority before being moved into the new list. */
+					pxTCB->uxPriority = pxCurrentTCB->uxPriority;
+					prvAddTaskToReadyList( pxTCB );
+				}
+				else
+				{
+					/* Just inherit the priority. */
+					pxTCB->uxPriority = pxCurrentTCB->uxPriority;
+				}
+
+				traceTASK_PRIORITY_INHERIT( pxTCB, pxCurrentTCB->uxPriority );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* configUSE_MUTEXES */
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_MUTEXES == 1 )
+
+	BaseType_t xTaskPriorityDisinherit( TaskHandle_t const pxMutexHolder )
+	{
+	TCB_t * const pxTCB = ( TCB_t * ) pxMutexHolder;
+	BaseType_t xReturn = pdFALSE;
+
+		if( pxMutexHolder != NULL )
+		{
+			/* A task can only have an inherited priority if it holds the mutex.
+			If the mutex is held by a task then it cannot be given from an
+			interrupt, and if a mutex is given by the holding task then it must
+			be the running state task. */
+			configASSERT( pxTCB == pxCurrentTCB );
+
+			configASSERT( pxTCB->uxMutexesHeld );
+			( pxTCB->uxMutexesHeld )--;
+
+			/* Has the holder of the mutex inherited the priority of another
+			task? */
+			if( pxTCB->uxPriority != pxTCB->uxBasePriority )
+			{
+				/* Only disinherit if no other mutexes are held. */
+				if( pxTCB->uxMutexesHeld == ( UBaseType_t ) 0 )
+				{
+					/* A task can only have an inherited priority if it holds
+					the mutex.  If the mutex is held by a task then it cannot be
+					given from an interrupt, and if a mutex is given by the
+					holding	task then it must be the running state task.  Remove
+					the	holding task from the ready	list. */
+					if( uxListRemove( &( pxTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+					{
+						taskRESET_READY_PRIORITY( pxTCB->uxPriority );
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					/* Disinherit the priority before adding the task into the
+					new	ready list. */
+					traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority );
+					pxTCB->uxPriority = pxTCB->uxBasePriority;
+
+					/* Reset the event list item value.  It cannot be in use for
+					any other purpose if this task is running, and it must be
+					running to give back the mutex. */
+					listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxTCB->uxPriority ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+					prvAddTaskToReadyList( pxTCB );
+
+					/* Return true to indicate that a context switch is required.
+					This is only actually required in the corner case whereby
+					multiple mutexes were held and the mutexes were given back
+					in an order different to that in which they were taken.
+					If a context switch did not occur when the first mutex was
+					returned, even if a task was waiting on it, then a context
+					switch should occur when the last mutex is returned whether
+					a task is waiting on it or not. */
+					xReturn = pdTRUE;
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+
+		return xReturn;
+	}
+
+#endif /* configUSE_MUTEXES */
+/*-----------------------------------------------------------*/
+
+#if ( portCRITICAL_NESTING_IN_TCB == 1 )
+
+	void vTaskEnterCritical( void )
+	{
+		portDISABLE_INTERRUPTS();
+
+		if( xSchedulerRunning != pdFALSE )
+		{
+			( pxCurrentTCB->uxCriticalNesting )++;
+
+			/* This is not the interrupt safe version of the enter critical
+			function so	assert() if it is being called from an interrupt
+			context.  Only API functions that end in "FromISR" can be used in an
+			interrupt.  Only assert if the critical nesting count is 1 to
+			protect against recursive calls if the assert function also uses a
+			critical section. */
+			if( pxCurrentTCB->uxCriticalNesting == 1 )
+			{
+				portASSERT_IF_IN_ISR();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* portCRITICAL_NESTING_IN_TCB */
+/*-----------------------------------------------------------*/
+
+#if ( portCRITICAL_NESTING_IN_TCB == 1 )
+
+	void vTaskExitCritical( void )
+	{
+		if( xSchedulerRunning != pdFALSE )
+		{
+			if( pxCurrentTCB->uxCriticalNesting > 0U )
+			{
+				( pxCurrentTCB->uxCriticalNesting )--;
+
+				if( pxCurrentTCB->uxCriticalNesting == 0U )
+				{
+					portENABLE_INTERRUPTS();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* portCRITICAL_NESTING_IN_TCB */
+/*-----------------------------------------------------------*/
+
+#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) )
+
+	static char *prvWriteNameToBuffer( char *pcBuffer, const char *pcTaskName )
+	{
+	size_t x;
+
+		/* Start by copying the entire string. */
+		strcpy( pcBuffer, pcTaskName );
+
+		/* Pad the end of the string with spaces to ensure columns line up when
+		printed out. */
+		for( x = strlen( pcBuffer ); x < ( size_t ) ( configMAX_TASK_NAME_LEN - 1 ); x++ )
+		{
+			pcBuffer[ x ] = ' ';
+		}
+
+		/* Terminate. */
+		pcBuffer[ x ] = 0x00;
+
+		/* Return the new end of string. */
+		return &( pcBuffer[ x ] );
+	}
+
+#endif /* ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) */
+/*-----------------------------------------------------------*/
+
+#if ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) )
+
+	void vTaskList( char * pcWriteBuffer )
+	{
+	TaskStatus_t *pxTaskStatusArray;
+	volatile UBaseType_t uxArraySize, x;
+	char cStatus;
+
+		/*
+		 * PLEASE NOTE:
+		 *
+		 * This function is provided for convenience only, and is used by many
+		 * of the demo applications.  Do not consider it to be part of the
+		 * scheduler.
+		 *
+		 * vTaskList() calls uxTaskGetSystemState(), then formats part of the
+		 * uxTaskGetSystemState() output into a human readable table that
+		 * displays task names, states and stack usage.
+		 *
+		 * vTaskList() has a dependency on the sprintf() C library function that
+		 * might bloat the code size, use a lot of stack, and provide different
+		 * results on different platforms.  An alternative, tiny, third party,
+		 * and limited functionality implementation of sprintf() is provided in
+		 * many of the FreeRTOS/Demo sub-directories in a file called
+		 * printf-stdarg.c (note printf-stdarg.c does not provide a full
+		 * snprintf() implementation!).
+		 *
+		 * It is recommended that production systems call uxTaskGetSystemState()
+		 * directly to get access to raw stats data, rather than indirectly
+		 * through a call to vTaskList().
+		 */
+
+
+		/* Make sure the write buffer does not contain a string. */
+		*pcWriteBuffer = 0x00;
+
+		/* Take a snapshot of the number of tasks in case it changes while this
+		function is executing. */
+		uxArraySize = uxCurrentNumberOfTasks;
+
+		/* Allocate an array index for each task. */
+		pxTaskStatusArray = pvPortMalloc( uxCurrentNumberOfTasks * sizeof( TaskStatus_t ) );
+
+		if( pxTaskStatusArray != NULL )
+		{
+			/* Generate the (binary) data. */
+			uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, NULL );
+
+			/* Create a human readable table from the binary data. */
+			for( x = 0; x < uxArraySize; x++ )
+			{
+				switch( pxTaskStatusArray[ x ].eCurrentState )
+				{
+					case eReady:		cStatus = tskREADY_CHAR;
+										break;
+
+					case eBlocked:		cStatus = tskBLOCKED_CHAR;
+										break;
+
+					case eSuspended:	cStatus = tskSUSPENDED_CHAR;
+										break;
+
+					case eDeleted:		cStatus = tskDELETED_CHAR;
+										break;
+
+					default:			/* Should not get here, but it is included
+										to prevent static checking errors. */
+										cStatus = 0x00;
+										break;
+				}
+
+				/* Write the task name to the string, padding with spaces so it
+				can be printed in tabular form more easily. */
+				pcWriteBuffer = prvWriteNameToBuffer( pcWriteBuffer, pxTaskStatusArray[ x ].pcTaskName );
+
+				/* Write the rest of the string. */
+				sprintf( pcWriteBuffer, "\t%c\t%u\t%u\t%u\r\n", cStatus, ( unsigned int ) pxTaskStatusArray[ x ].uxCurrentPriority, ( unsigned int ) pxTaskStatusArray[ x ].usStackHighWaterMark, ( unsigned int ) pxTaskStatusArray[ x ].xTaskNumber );
+				pcWriteBuffer += strlen( pcWriteBuffer );
+			}
+
+			/* Free the array again. */
+			vPortFree( pxTaskStatusArray );
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* ( ( configUSE_TRACE_FACILITY == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) ) */
+/*----------------------------------------------------------*/
+
+#if ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) )
+
+	void vTaskGetRunTimeStats( char *pcWriteBuffer )
+	{
+	TaskStatus_t *pxTaskStatusArray;
+	volatile UBaseType_t uxArraySize, x;
+	uint32_t ulTotalTime, ulStatsAsPercentage;
+
+		#if( configUSE_TRACE_FACILITY != 1 )
+		{
+			#error configUSE_TRACE_FACILITY must also be set to 1 in FreeRTOSConfig.h to use vTaskGetRunTimeStats().
+		}
+		#endif
+
+		/*
+		 * PLEASE NOTE:
+		 *
+		 * This function is provided for convenience only, and is used by many
+		 * of the demo applications.  Do not consider it to be part of the
+		 * scheduler.
+		 *
+		 * vTaskGetRunTimeStats() calls uxTaskGetSystemState(), then formats part
+		 * of the uxTaskGetSystemState() output into a human readable table that
+		 * displays the amount of time each task has spent in the Running state
+		 * in both absolute and percentage terms.
+		 *
+		 * vTaskGetRunTimeStats() has a dependency on the sprintf() C library
+		 * function that might bloat the code size, use a lot of stack, and
+		 * provide different results on different platforms.  An alternative,
+		 * tiny, third party, and limited functionality implementation of
+		 * sprintf() is provided in many of the FreeRTOS/Demo sub-directories in
+		 * a file called printf-stdarg.c (note printf-stdarg.c does not provide
+		 * a full snprintf() implementation!).
+		 *
+		 * It is recommended that production systems call uxTaskGetSystemState()
+		 * directly to get access to raw stats data, rather than indirectly
+		 * through a call to vTaskGetRunTimeStats().
+		 */
+
+		/* Make sure the write buffer does not contain a string. */
+		*pcWriteBuffer = 0x00;
+
+		/* Take a snapshot of the number of tasks in case it changes while this
+		function is executing. */
+		uxArraySize = uxCurrentNumberOfTasks;
+
+		/* Allocate an array index for each task. */
+		pxTaskStatusArray = pvPortMalloc( uxCurrentNumberOfTasks * sizeof( TaskStatus_t ) );
+
+		if( pxTaskStatusArray != NULL )
+		{
+			/* Generate the (binary) data. */
+			uxArraySize = uxTaskGetSystemState( pxTaskStatusArray, uxArraySize, &ulTotalTime );
+
+			/* For percentage calculations. */
+			ulTotalTime /= 100UL;
+
+			/* Avoid divide by zero errors. */
+			if( ulTotalTime > 0 )
+			{
+				/* Create a human readable table from the binary data. */
+				for( x = 0; x < uxArraySize; x++ )
+				{
+					/* What percentage of the total run time has the task used?
+					This will always be rounded down to the nearest integer.
+					ulTotalRunTimeDiv100 has already been divided by 100. */
+					ulStatsAsPercentage = pxTaskStatusArray[ x ].ulRunTimeCounter / ulTotalTime;
+
+					/* Write the task name to the string, padding with
+					spaces so it can be printed in tabular form more
+					easily. */
+					pcWriteBuffer = prvWriteNameToBuffer( pcWriteBuffer, pxTaskStatusArray[ x ].pcTaskName );
+
+					if( ulStatsAsPercentage > 0UL )
+					{
+						#ifdef portLU_PRINTF_SPECIFIER_REQUIRED
+						{
+							sprintf( pcWriteBuffer, "\t%lu\t\t%lu%%\r\n", pxTaskStatusArray[ x ].ulRunTimeCounter, ulStatsAsPercentage );
+						}
+						#else
+						{
+							/* sizeof( int ) == sizeof( long ) so a smaller
+							printf() library can be used. */
+							sprintf( pcWriteBuffer, "\t%u\t\t%u%%\r\n", ( unsigned int ) pxTaskStatusArray[ x ].ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage );
+						}
+						#endif
+					}
+					else
+					{
+						/* If the percentage is zero here then the task has
+						consumed less than 1% of the total run time. */
+						#ifdef portLU_PRINTF_SPECIFIER_REQUIRED
+						{
+							sprintf( pcWriteBuffer, "\t%lu\t\t<1%%\r\n", pxTaskStatusArray[ x ].ulRunTimeCounter );
+						}
+						#else
+						{
+							/* sizeof( int ) == sizeof( long ) so a smaller
+							printf() library can be used. */
+							sprintf( pcWriteBuffer, "\t%u\t\t<1%%\r\n", ( unsigned int ) pxTaskStatusArray[ x ].ulRunTimeCounter );
+						}
+						#endif
+					}
+
+					pcWriteBuffer += strlen( pcWriteBuffer );
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			/* Free the array again. */
+			vPortFree( pxTaskStatusArray );
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+#endif /* ( ( configGENERATE_RUN_TIME_STATS == 1 ) && ( configUSE_STATS_FORMATTING_FUNCTIONS > 0 ) ) */
+/*-----------------------------------------------------------*/
+
+TickType_t uxTaskResetEventItemValue( void )
+{
+TickType_t uxReturn;
+
+	uxReturn = listGET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ) );
+
+	/* Reset the event list item to its normal value - so it can be used with
+	queues and semaphores. */
+	listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xEventListItem ), ( ( TickType_t ) configMAX_PRIORITIES - ( TickType_t ) pxCurrentTCB->uxPriority ) ); /*lint !e961 MISRA exception as the casts are only redundant for some ports. */
+
+	return uxReturn;
+}
+/*-----------------------------------------------------------*/
+
+#if ( configUSE_MUTEXES == 1 )
+
+	void *pvTaskIncrementMutexHeldCount( void )
+	{
+		/* If xSemaphoreCreateMutex() is called before any tasks have been created
+		then pxCurrentTCB will be NULL. */
+		if( pxCurrentTCB != NULL )
+		{
+			( pxCurrentTCB->uxMutexesHeld )++;
+		}
+
+		return pxCurrentTCB;
+	}
+
+#endif /* configUSE_MUTEXES */
+/*-----------------------------------------------------------*/
+
+#if( configUSE_TASK_NOTIFICATIONS == 1 )
+
+	uint32_t ulTaskNotifyTake( BaseType_t xClearCountOnExit, TickType_t xTicksToWait )
+	{
+	TickType_t xTimeToWake;
+	uint32_t ulReturn;
+
+		taskENTER_CRITICAL();
+		{
+			/* Only block if the notification count is not already non-zero. */
+			if( pxCurrentTCB->ulNotifiedValue == 0UL )
+			{
+				/* Mark this task as waiting for a notification. */
+				pxCurrentTCB->eNotifyState = eWaitingNotification;
+
+				if( xTicksToWait > ( TickType_t ) 0 )
+				{
+					/* The task is going to block.  First it must be removed
+					from the ready list. */
+					if( uxListRemove( &( pxCurrentTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+					{
+						/* The current task must be in a ready list, so there is
+						no need to check, and the port reset macro can be called
+						directly. */
+						portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority );
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					#if ( INCLUDE_vTaskSuspend == 1 )
+					{
+						if( xTicksToWait == portMAX_DELAY )
+						{
+							/* Add the task to the suspended task list instead
+							of a delayed task list to ensure the task is not
+							woken by a timing event.  It will block
+							indefinitely. */
+							vListInsertEnd( &xSuspendedTaskList, &( pxCurrentTCB->xGenericListItem ) );
+						}
+						else
+						{
+							/* Calculate the time at which the task should be
+							woken if no notification events occur.  This may
+							overflow but this doesn't matter, the scheduler will
+							handle it. */
+							xTimeToWake = xTickCount + xTicksToWait;
+							prvAddCurrentTaskToDelayedList( xTimeToWake );
+						}
+					}
+					#else /* INCLUDE_vTaskSuspend */
+					{
+							/* Calculate the time at which the task should be
+							woken if the event does not occur.  This may
+							overflow but this doesn't matter, the scheduler will
+							handle it. */
+							xTimeToWake = xTickCount + xTicksToWait;
+							prvAddCurrentTaskToDelayedList( xTimeToWake );
+					}
+					#endif /* INCLUDE_vTaskSuspend */
+
+					traceTASK_NOTIFY_TAKE_BLOCK();
+
+					/* All ports are written to allow a yield in a critical
+					section (some will yield immediately, others wait until the
+					critical section exits) - but it is not something that
+					application code should ever do. */
+					portYIELD_WITHIN_API();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		taskENTER_CRITICAL();
+		{
+			traceTASK_NOTIFY_TAKE();
+			ulReturn = pxCurrentTCB->ulNotifiedValue;
+
+			if( ulReturn != 0UL )
+			{
+				if( xClearCountOnExit != pdFALSE )
+				{
+					pxCurrentTCB->ulNotifiedValue = 0UL;
+				}
+				else
+				{
+					( pxCurrentTCB->ulNotifiedValue )--;
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			pxCurrentTCB->eNotifyState = eNotWaitingNotification;
+		}
+		taskEXIT_CRITICAL();
+
+		return ulReturn;
+	}
+
+#endif /* configUSE_TASK_NOTIFICATIONS */
+/*-----------------------------------------------------------*/
+
+#if( configUSE_TASK_NOTIFICATIONS == 1 )
+
+	BaseType_t xTaskNotifyWait( uint32_t ulBitsToClearOnEntry, uint32_t ulBitsToClearOnExit, uint32_t *pulNotificationValue, TickType_t xTicksToWait )
+	{
+	TickType_t xTimeToWake;
+	BaseType_t xReturn;
+
+		taskENTER_CRITICAL();
+		{
+			/* Only block if a notification is not already pending. */
+			if( pxCurrentTCB->eNotifyState != eNotified )
+			{
+				/* Clear bits in the task's notification value as bits may get
+				set	by the notifying task or interrupt.  This can be used to
+				clear the value to zero. */
+				pxCurrentTCB->ulNotifiedValue &= ~ulBitsToClearOnEntry;
+
+				/* Mark this task as waiting for a notification. */
+				pxCurrentTCB->eNotifyState = eWaitingNotification;
+
+				if( xTicksToWait > ( TickType_t ) 0 )
+				{
+					/* The task is going to block.  First it must be removed
+					from the	ready list. */
+					if( uxListRemove( &( pxCurrentTCB->xGenericListItem ) ) == ( UBaseType_t ) 0 )
+					{
+						/* The current task must be in a ready list, so there is
+						no need to check, and the port reset macro can be called
+						directly. */
+						portRESET_READY_PRIORITY( pxCurrentTCB->uxPriority, uxTopReadyPriority );
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+
+					#if ( INCLUDE_vTaskSuspend == 1 )
+					{
+						if( xTicksToWait == portMAX_DELAY )
+						{
+							/* Add the task to the suspended task list instead
+							of a delayed task list to ensure the task is not
+							woken by a timing event.  It will block
+							indefinitely. */
+							vListInsertEnd( &xSuspendedTaskList, &( pxCurrentTCB->xGenericListItem ) );
+						}
+						else
+						{
+							/* Calculate the time at which the task should be
+							woken if no notification events occur.  This may
+							overflow but this doesn't matter, the scheduler will
+							handle it. */
+							xTimeToWake = xTickCount + xTicksToWait;
+							prvAddCurrentTaskToDelayedList( xTimeToWake );
+						}
+					}
+					#else /* INCLUDE_vTaskSuspend */
+					{
+							/* Calculate the time at which the task should be
+							woken if the event does not occur.  This may
+							overflow but this doesn't matter, the scheduler will
+							handle it. */
+							xTimeToWake = xTickCount + xTicksToWait;
+							prvAddCurrentTaskToDelayedList( xTimeToWake );
+					}
+					#endif /* INCLUDE_vTaskSuspend */
+
+					traceTASK_NOTIFY_WAIT_BLOCK();
+
+					/* All ports are written to allow a yield in a critical
+					section (some will yield immediately, others wait until the
+					critical section exits) - but it is not something that
+					application code should ever do. */
+					portYIELD_WITHIN_API();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		taskENTER_CRITICAL();
+		{
+			traceTASK_NOTIFY_WAIT();
+
+			if( pulNotificationValue != NULL )
+			{
+				/* Output the current notification value, which may or may not
+				have changed. */
+				*pulNotificationValue = pxCurrentTCB->ulNotifiedValue;
+			}
+
+			/* If eNotifyValue is set then either the task never entered the
+			blocked state (because a notification was already pending) or the
+			task unblocked because of a notification.  Otherwise the task
+			unblocked because of a timeout. */
+			if( pxCurrentTCB->eNotifyState == eWaitingNotification )
+			{
+				/* A notification was not received. */
+				xReturn = pdFALSE;
+			}
+			else
+			{
+				/* A notification was already pending or a notification was
+				received while the task was waiting. */
+				pxCurrentTCB->ulNotifiedValue &= ~ulBitsToClearOnExit;
+				xReturn = pdTRUE;
+			}
+
+			pxCurrentTCB->eNotifyState = eNotWaitingNotification;
+		}
+		taskEXIT_CRITICAL();
+
+		return xReturn;
+	}
+
+#endif /* configUSE_TASK_NOTIFICATIONS */
+/*-----------------------------------------------------------*/
+
+#if( configUSE_TASK_NOTIFICATIONS == 1 )
+
+	BaseType_t xTaskGenericNotify( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue )
+	{
+	TCB_t * pxTCB;
+	eNotifyValue eOriginalNotifyState;
+	BaseType_t xReturn = pdPASS;
+
+		configASSERT( xTaskToNotify );
+		pxTCB = ( TCB_t * ) xTaskToNotify;
+
+		taskENTER_CRITICAL();
+		{
+			if( pulPreviousNotificationValue != NULL )
+			{
+				*pulPreviousNotificationValue = pxTCB->ulNotifiedValue;
+			}
+
+			eOriginalNotifyState = pxTCB->eNotifyState;
+
+			pxTCB->eNotifyState = eNotified;
+
+			switch( eAction )
+			{
+				case eSetBits	:
+					pxTCB->ulNotifiedValue |= ulValue;
+					break;
+
+				case eIncrement	:
+					( pxTCB->ulNotifiedValue )++;
+					break;
+
+				case eSetValueWithOverwrite	:
+					pxTCB->ulNotifiedValue = ulValue;
+					break;
+
+				case eSetValueWithoutOverwrite :
+					if( eOriginalNotifyState != eNotified )
+					{
+						pxTCB->ulNotifiedValue = ulValue;
+					}
+					else
+					{
+						/* The value could not be written to the task. */
+						xReturn = pdFAIL;
+					}
+					break;
+
+				case eNoAction:
+					/* The task is being notified without its notify value being
+					updated. */
+					break;
+			}
+
+			traceTASK_NOTIFY();
+
+			/* If the task is in the blocked state specifically to wait for a
+			notification then unblock it now. */
+			if( eOriginalNotifyState == eWaitingNotification )
+			{
+				( void ) uxListRemove( &( pxTCB->xGenericListItem ) );
+				prvAddTaskToReadyList( pxTCB );
+
+				/* The task should not have been on an event list. */
+				configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL );
+
+				#if( configUSE_TICKLESS_IDLE != 0 )
+				{
+					/* If a task is blocked waiting for a notification then
+					xNextTaskUnblockTime might be set to the blocked task's time
+					out time.  If the task is unblocked for a reason other than
+					a timeout xNextTaskUnblockTime is normally left unchanged,
+					because it will automatically get reset to a new value when
+					the tick count equals xNextTaskUnblockTime.  However if
+					tickless idling is used it might be more important to enter
+					sleep mode at the earliest possible time - so reset
+					xNextTaskUnblockTime here to ensure it is updated at the
+					earliest possible time. */
+					prvResetNextTaskUnblockTime();
+				}
+				#endif
+
+				if( pxTCB->uxPriority > pxCurrentTCB->uxPriority )
+				{
+					/* The notified task has a priority above the currently
+					executing task so a yield is required. */
+					taskYIELD_IF_USING_PREEMPTION();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		return xReturn;
+	}
+
+#endif /* configUSE_TASK_NOTIFICATIONS */
+/*-----------------------------------------------------------*/
+
+#if( configUSE_TASK_NOTIFICATIONS == 1 )
+
+	BaseType_t xTaskGenericNotifyFromISR( TaskHandle_t xTaskToNotify, uint32_t ulValue, eNotifyAction eAction, uint32_t *pulPreviousNotificationValue, BaseType_t *pxHigherPriorityTaskWoken )
+	{
+	TCB_t * pxTCB;
+	eNotifyValue eOriginalNotifyState;
+	BaseType_t xReturn = pdPASS;
+	UBaseType_t uxSavedInterruptStatus;
+
+		configASSERT( xTaskToNotify );
+
+		/* RTOS ports that support interrupt nesting have the concept of a
+		maximum	system call (or maximum API call) interrupt priority.
+		Interrupts that are	above the maximum system call priority are keep
+		permanently enabled, even when the RTOS kernel is in a critical section,
+		but cannot make any calls to FreeRTOS API functions.  If configASSERT()
+		is defined in FreeRTOSConfig.h then
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+		failure if a FreeRTOS API function is called from an interrupt that has
+		been assigned a priority above the configured maximum system call
+		priority.  Only FreeRTOS functions that end in FromISR can be called
+		from interrupts	that have been assigned a priority at or (logically)
+		below the maximum system call interrupt priority.  FreeRTOS maintains a
+		separate interrupt safe API to ensure interrupt entry is as fast and as
+		simple as possible.  More information (albeit Cortex-M specific) is
+		provided on the following link:
+		http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+		pxTCB = ( TCB_t * ) xTaskToNotify;
+
+		uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+		{
+			if( pulPreviousNotificationValue != NULL )
+			{
+				*pulPreviousNotificationValue = pxTCB->ulNotifiedValue;
+			}
+
+			eOriginalNotifyState = pxTCB->eNotifyState;
+			pxTCB->eNotifyState = eNotified;
+
+			switch( eAction )
+			{
+				case eSetBits	:
+					pxTCB->ulNotifiedValue |= ulValue;
+					break;
+
+				case eIncrement	:
+					( pxTCB->ulNotifiedValue )++;
+					break;
+
+				case eSetValueWithOverwrite	:
+					pxTCB->ulNotifiedValue = ulValue;
+					break;
+
+				case eSetValueWithoutOverwrite :
+					if( eOriginalNotifyState != eNotified )
+					{
+						pxTCB->ulNotifiedValue = ulValue;
+					}
+					else
+					{
+						/* The value could not be written to the task. */
+						xReturn = pdFAIL;
+					}
+					break;
+
+				case eNoAction :
+					/* The task is being notified without its notify value being
+					updated. */
+					break;
+			}
+
+			traceTASK_NOTIFY_FROM_ISR();
+
+			/* If the task is in the blocked state specifically to wait for a
+			notification then unblock it now. */
+			if( eOriginalNotifyState == eWaitingNotification )
+			{
+				/* The task should not have been on an event list. */
+				configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL );
+
+				if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE )
+				{
+					( void ) uxListRemove( &( pxTCB->xGenericListItem ) );
+					prvAddTaskToReadyList( pxTCB );
+				}
+				else
+				{
+					/* The delayed and ready lists cannot be accessed, so hold
+					this task pending until the scheduler is resumed. */
+					vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) );
+				}
+
+				if( pxTCB->uxPriority > pxCurrentTCB->uxPriority )
+				{
+					/* The notified task has a priority above the currently
+					executing task so a yield is required. */
+					if( pxHigherPriorityTaskWoken != NULL )
+					{
+						*pxHigherPriorityTaskWoken = pdTRUE;
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+		}
+		portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+
+		return xReturn;
+	}
+
+#endif /* configUSE_TASK_NOTIFICATIONS */
+/*-----------------------------------------------------------*/
+
+#if( configUSE_TASK_NOTIFICATIONS == 1 )
+
+	void vTaskNotifyGiveFromISR( TaskHandle_t xTaskToNotify, BaseType_t *pxHigherPriorityTaskWoken )
+	{
+	TCB_t * pxTCB;
+	eNotifyValue eOriginalNotifyState;
+	UBaseType_t uxSavedInterruptStatus;
+
+		configASSERT( xTaskToNotify );
+
+		/* RTOS ports that support interrupt nesting have the concept of a
+		maximum	system call (or maximum API call) interrupt priority.
+		Interrupts that are	above the maximum system call priority are keep
+		permanently enabled, even when the RTOS kernel is in a critical section,
+		but cannot make any calls to FreeRTOS API functions.  If configASSERT()
+		is defined in FreeRTOSConfig.h then
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID() will result in an assertion
+		failure if a FreeRTOS API function is called from an interrupt that has
+		been assigned a priority above the configured maximum system call
+		priority.  Only FreeRTOS functions that end in FromISR can be called
+		from interrupts	that have been assigned a priority at or (logically)
+		below the maximum system call interrupt priority.  FreeRTOS maintains a
+		separate interrupt safe API to ensure interrupt entry is as fast and as
+		simple as possible.  More information (albeit Cortex-M specific) is
+		provided on the following link:
+		http://www.freertos.org/RTOS-Cortex-M3-M4.html */
+		portASSERT_IF_INTERRUPT_PRIORITY_INVALID();
+
+		pxTCB = ( TCB_t * ) xTaskToNotify;
+
+		uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR();
+		{
+			eOriginalNotifyState = pxTCB->eNotifyState;
+			pxTCB->eNotifyState = eNotified;
+
+			/* 'Giving' is equivalent to incrementing a count in a counting
+			semaphore. */
+			( pxTCB->ulNotifiedValue )++;
+
+			traceTASK_NOTIFY_GIVE_FROM_ISR();
+
+			/* If the task is in the blocked state specifically to wait for a
+			notification then unblock it now. */
+			if( eOriginalNotifyState == eWaitingNotification )
+			{
+				/* The task should not have been on an event list. */
+				configASSERT( listLIST_ITEM_CONTAINER( &( pxTCB->xEventListItem ) ) == NULL );
+
+				if( uxSchedulerSuspended == ( UBaseType_t ) pdFALSE )
+				{
+					( void ) uxListRemove( &( pxTCB->xGenericListItem ) );
+					prvAddTaskToReadyList( pxTCB );
+				}
+				else
+				{
+					/* The delayed and ready lists cannot be accessed, so hold
+					this task pending until the scheduler is resumed. */
+					vListInsertEnd( &( xPendingReadyList ), &( pxTCB->xEventListItem ) );
+				}
+
+				if( pxTCB->uxPriority > pxCurrentTCB->uxPriority )
+				{
+					/* The notified task has a priority above the currently
+					executing task so a yield is required. */
+					if( pxHigherPriorityTaskWoken != NULL )
+					{
+						*pxHigherPriorityTaskWoken = pdTRUE;
+					}
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+		}
+		portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus );
+	}
+
+#endif /* configUSE_TASK_NOTIFICATIONS */
+
+/*-----------------------------------------------------------*/
+
+#if( configUSE_TASK_NOTIFICATIONS == 1 )
+
+	BaseType_t xTaskNotifyStateClear( TaskHandle_t xTask )
+	{
+	TCB_t *pxTCB;
+	BaseType_t xReturn;
+
+		pxTCB = ( TCB_t * ) xTask;
+
+		/* If null is passed in here then it is the calling task that is having
+		its notification state cleared. */
+		pxTCB = prvGetTCBFromHandle( pxTCB );
+
+		taskENTER_CRITICAL();
+		{
+			if( pxTCB->eNotifyState == eNotified )
+			{
+				pxTCB->eNotifyState = eNotWaitingNotification;
+				xReturn = pdPASS;
+			}
+			else
+			{
+				xReturn = pdFAIL;
+			}
+		}
+		taskEXIT_CRITICAL();
+
+		return xReturn;
+	}
+
+#endif /* configUSE_TASK_NOTIFICATIONS */
+
+#ifdef FREERTOS_MODULE_TEST
+	#include "tasks_test_access_functions.h"
+#endif
+
diff --git a/crazyflie-firmware-src/src/lib/FreeRTOS/timers.c b/crazyflie-firmware-src/src/lib/FreeRTOS/timers.c
new file mode 100644
index 0000000000000000000000000000000000000000..c7ab9023f007fb4f2a3083d398243985b806f724
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/FreeRTOS/timers.c
@@ -0,0 +1,929 @@
+/*
+    FreeRTOS V8.2.3 - Copyright (C) 2015 Real Time Engineers Ltd.
+    All rights reserved
+
+    VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation >>>> AND MODIFIED BY <<<< the FreeRTOS exception.
+
+    ***************************************************************************
+    >>!   NOTE: The modification to the GPL is included to allow you to     !<<
+    >>!   distribute a combined work that includes FreeRTOS without being   !<<
+    >>!   obliged to provide the source code for proprietary components     !<<
+    >>!   outside of the FreeRTOS kernel.                                   !<<
+    ***************************************************************************
+
+    FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
+    WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
+    FOR A PARTICULAR PURPOSE.  Full license text is available on the following
+    link: http://www.freertos.org/a00114.html
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS provides completely free yet professionally developed,    *
+     *    robust, strictly quality controlled, supported, and cross          *
+     *    platform software that is more than just the market leader, it     *
+     *    is the industry's de facto standard.                               *
+     *                                                                       *
+     *    Help yourself get started quickly while simultaneously helping     *
+     *    to support the FreeRTOS project by purchasing a FreeRTOS           *
+     *    tutorial book, reference manual, or both:                          *
+     *    http://www.FreeRTOS.org/Documentation                              *
+     *                                                                       *
+    ***************************************************************************
+
+    http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
+    the FAQ page "My application does not run, what could be wrong?".  Have you
+    defined configASSERT()?
+
+    http://www.FreeRTOS.org/support - In return for receiving this top quality
+    embedded software for free we request you assist our global community by
+    participating in the support forum.
+
+    http://www.FreeRTOS.org/training - Investing in training allows your team to
+    be as productive as possible as early as possible.  Now you can receive
+    FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
+    Ltd, and the world's leading authority on the world's leading RTOS.
+
+    http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
+    including FreeRTOS+Trace - an indispensable productivity tool, a DOS
+    compatible FAT file system, and our tiny thread aware UDP/IP stack.
+
+    http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
+    Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
+
+    http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
+    Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
+    licenses offer ticketed support, indemnification and commercial middleware.
+
+    http://www.SafeRTOS.com - High Integrity Systems also provide a safety
+    engineered and independently SIL3 certified version for use in safety and
+    mission critical applications that require provable dependability.
+
+    1 tab == 4 spaces!
+*/
+
+/* Standard includes. */
+#include <stdlib.h>
+
+/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining
+all the API functions to use the MPU wrappers.  That should only be done when
+task.h is included from an application file. */
+#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "timers.h"
+
+#if ( INCLUDE_xTimerPendFunctionCall == 1 ) && ( configUSE_TIMERS == 0 )
+	#error configUSE_TIMERS must be set to 1 to make the xTimerPendFunctionCall() function available.
+#endif
+
+/* Lint e961 and e750 are suppressed as a MISRA exception justified because the
+MPU ports require MPU_WRAPPERS_INCLUDED_FROM_API_FILE to be defined for the
+header files above, but not in this file, in order to generate the correct
+privileged Vs unprivileged linkage and placement. */
+#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE /*lint !e961 !e750. */
+
+
+/* This entire source file will be skipped if the application is not configured
+to include software timer functionality.  This #if is closed at the very bottom
+of this file.  If you want to include software timer functionality then ensure
+configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */
+#if ( configUSE_TIMERS == 1 )
+
+/* Misc definitions. */
+#define tmrNO_DELAY		( TickType_t ) 0U
+
+/* The definition of the timers themselves. */
+typedef struct tmrTimerControl
+{
+	const char				*pcTimerName;		/*<< Text name.  This is not used by the kernel, it is included simply to make debugging easier. */ /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+	ListItem_t				xTimerListItem;		/*<< Standard linked list item as used by all kernel features for event management. */
+	TickType_t				xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */
+	UBaseType_t				uxAutoReload;		/*<< Set to pdTRUE if the timer should be automatically restarted once expired.  Set to pdFALSE if the timer is, in effect, a one-shot timer. */
+	void 					*pvTimerID;			/*<< An ID to identify the timer.  This allows the timer to be identified when the same callback is used for multiple timers. */
+	TimerCallbackFunction_t	pxCallbackFunction;	/*<< The function that will be called when the timer expires. */
+	#if( configUSE_TRACE_FACILITY == 1 )
+		UBaseType_t			uxTimerNumber;		/*<< An ID assigned by trace tools such as FreeRTOS+Trace */
+	#endif
+} xTIMER;
+
+/* The old xTIMER name is maintained above then typedefed to the new Timer_t
+name below to enable the use of older kernel aware debuggers. */
+typedef xTIMER Timer_t;
+
+/* The definition of messages that can be sent and received on the timer queue.
+Two types of message can be queued - messages that manipulate a software timer,
+and messages that request the execution of a non-timer related callback.  The
+two message types are defined in two separate structures, xTimerParametersType
+and xCallbackParametersType respectively. */
+typedef struct tmrTimerParameters
+{
+	TickType_t			xMessageValue;		/*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */
+	Timer_t *			pxTimer;			/*<< The timer to which the command will be applied. */
+} TimerParameter_t;
+
+
+typedef struct tmrCallbackParameters
+{
+	PendedFunction_t	pxCallbackFunction;	/* << The callback function to execute. */
+	void *pvParameter1;						/* << The value that will be used as the callback functions first parameter. */
+	uint32_t ulParameter2;					/* << The value that will be used as the callback functions second parameter. */
+} CallbackParameters_t;
+
+/* The structure that contains the two message types, along with an identifier
+that is used to determine which message type is valid. */
+typedef struct tmrTimerQueueMessage
+{
+	BaseType_t			xMessageID;			/*<< The command being sent to the timer service task. */
+	union
+	{
+		TimerParameter_t xTimerParameters;
+
+		/* Don't include xCallbackParameters if it is not going to be used as
+		it makes the structure (and therefore the timer queue) larger. */
+		#if ( INCLUDE_xTimerPendFunctionCall == 1 )
+			CallbackParameters_t xCallbackParameters;
+		#endif /* INCLUDE_xTimerPendFunctionCall */
+	} u;
+} DaemonTaskMessage_t;
+
+/*lint -e956 A manual analysis and inspection has been used to determine which
+static variables must be declared volatile. */
+
+/* The list in which active timers are stored.  Timers are referenced in expire
+time order, with the nearest expiry time at the front of the list.  Only the
+timer service task is allowed to access these lists. */
+PRIVILEGED_DATA static List_t xActiveTimerList1;
+PRIVILEGED_DATA static List_t xActiveTimerList2;
+PRIVILEGED_DATA static List_t *pxCurrentTimerList;
+PRIVILEGED_DATA static List_t *pxOverflowTimerList;
+
+/* A queue that is used to send commands to the timer service task. */
+PRIVILEGED_DATA static QueueHandle_t xTimerQueue = NULL;
+
+#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 )
+
+	PRIVILEGED_DATA static TaskHandle_t xTimerTaskHandle = NULL;
+
+#endif
+
+/*lint +e956 */
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Initialise the infrastructure used by the timer service task if it has not
+ * been initialised already.
+ */
+static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * The timer service task (daemon).  Timer functionality is controlled by this
+ * task.  Other tasks communicate with the timer service task using the
+ * xTimerQueue queue.
+ */
+static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION;
+
+/*
+ * Called by the timer service task to interpret and process a command it
+ * received on the timer queue.
+ */
+static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Insert the timer into either xActiveTimerList1, or xActiveTimerList2,
+ * depending on if the expire time causes a timer counter overflow.
+ */
+static BaseType_t prvInsertTimerInActiveList( Timer_t * const pxTimer, const TickType_t xNextExpiryTime, const TickType_t xTimeNow, const TickType_t xCommandTime ) PRIVILEGED_FUNCTION;
+
+/*
+ * An active timer has reached its expire time.  Reload the timer if it is an
+ * auto reload timer, then call its callback.
+ */
+static void prvProcessExpiredTimer( const TickType_t xNextExpireTime, const TickType_t xTimeNow ) PRIVILEGED_FUNCTION;
+
+/*
+ * The tick count has overflowed.  Switch the timer lists after ensuring the
+ * current timer list does not still reference some timers.
+ */
+static void prvSwitchTimerLists( void ) PRIVILEGED_FUNCTION;
+
+/*
+ * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE
+ * if a tick count overflow occurred since prvSampleTimeNow() was last called.
+ */
+static TickType_t prvSampleTimeNow( BaseType_t * const pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION;
+
+/*
+ * If the timer list contains any active timers then return the expire time of
+ * the timer that will expire first and set *pxListWasEmpty to false.  If the
+ * timer list does not contain any timers then return 0 and set *pxListWasEmpty
+ * to pdTRUE.
+ */
+static TickType_t prvGetNextExpireTime( BaseType_t * const pxListWasEmpty ) PRIVILEGED_FUNCTION;
+
+/*
+ * If a timer has expired, process it.  Otherwise, block the timer service task
+ * until either a timer does expire or a command is received.
+ */
+static void prvProcessTimerOrBlockTask( const TickType_t xNextExpireTime, BaseType_t xListWasEmpty ) PRIVILEGED_FUNCTION;
+
+/*-----------------------------------------------------------*/
+
+BaseType_t xTimerCreateTimerTask( void )
+{
+BaseType_t xReturn = pdFAIL;
+
+	/* This function is called when the scheduler is started if
+	configUSE_TIMERS is set to 1.  Check that the infrastructure used by the
+	timer service task has been created/initialised.  If timers have already
+	been created then the initialisation will already have been performed. */
+	prvCheckForValidListAndQueue();
+
+	if( xTimerQueue != NULL )
+	{
+		#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 )
+		{
+			/* Create the timer task, storing its handle in xTimerTaskHandle so
+			it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */
+			xReturn = xTaskCreate( prvTimerTask, "Tmr Svc", ( uint16_t ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( UBaseType_t ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, &xTimerTaskHandle );
+		}
+		#else
+		{
+			/* Create the timer task without storing its handle. */
+			xReturn = xTaskCreate( prvTimerTask, "Tmr Svc", ( uint16_t ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( UBaseType_t ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, NULL);
+		}
+		#endif
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	configASSERT( xReturn );
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+TimerHandle_t xTimerCreate( const char * const pcTimerName, const TickType_t xTimerPeriodInTicks, const UBaseType_t uxAutoReload, void * const pvTimerID, TimerCallbackFunction_t pxCallbackFunction ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+{
+Timer_t *pxNewTimer;
+
+	/* Allocate the timer structure. */
+	if( xTimerPeriodInTicks == ( TickType_t ) 0U )
+	{
+		pxNewTimer = NULL;
+	}
+	else
+	{
+		pxNewTimer = ( Timer_t * ) pvPortMalloc( sizeof( Timer_t ) );
+		if( pxNewTimer != NULL )
+		{
+			/* Ensure the infrastructure used by the timer service task has been
+			created/initialised. */
+			prvCheckForValidListAndQueue();
+
+			/* Initialise the timer structure members using the function parameters. */
+			pxNewTimer->pcTimerName = pcTimerName;
+			pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks;
+			pxNewTimer->uxAutoReload = uxAutoReload;
+			pxNewTimer->pvTimerID = pvTimerID;
+			pxNewTimer->pxCallbackFunction = pxCallbackFunction;
+			vListInitialiseItem( &( pxNewTimer->xTimerListItem ) );
+
+			traceTIMER_CREATE( pxNewTimer );
+		}
+		else
+		{
+			traceTIMER_CREATE_FAILED();
+		}
+	}
+
+	/* 0 is not a valid value for xTimerPeriodInTicks. */
+	configASSERT( ( xTimerPeriodInTicks > 0 ) );
+
+	return ( TimerHandle_t ) pxNewTimer;
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xTimerGenericCommand( TimerHandle_t xTimer, const BaseType_t xCommandID, const TickType_t xOptionalValue, BaseType_t * const pxHigherPriorityTaskWoken, const TickType_t xTicksToWait )
+{
+BaseType_t xReturn = pdFAIL;
+DaemonTaskMessage_t xMessage;
+
+	configASSERT( xTimer );
+
+	/* Send a message to the timer service task to perform a particular action
+	on a particular timer definition. */
+	if( xTimerQueue != NULL )
+	{
+		/* Send a command to the timer service task to start the xTimer timer. */
+		xMessage.xMessageID = xCommandID;
+		xMessage.u.xTimerParameters.xMessageValue = xOptionalValue;
+		xMessage.u.xTimerParameters.pxTimer = ( Timer_t * ) xTimer;
+
+		if( xCommandID < tmrFIRST_FROM_ISR_COMMAND )
+		{
+			if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING )
+			{
+				xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xTicksToWait );
+			}
+			else
+			{
+				xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY );
+			}
+		}
+		else
+		{
+			xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken );
+		}
+
+		traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn );
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	return xReturn;
+}
+/*-----------------------------------------------------------*/
+
+#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 )
+
+	TaskHandle_t xTimerGetTimerDaemonTaskHandle( void )
+	{
+		/* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been
+		started, then xTimerTaskHandle will be NULL. */
+		configASSERT( ( xTimerTaskHandle != NULL ) );
+		return xTimerTaskHandle;
+	}
+
+#endif
+/*-----------------------------------------------------------*/
+
+const char * pcTimerGetTimerName( TimerHandle_t xTimer )
+{
+Timer_t *pxTimer = ( Timer_t * ) xTimer;
+
+	configASSERT( xTimer );
+	return pxTimer->pcTimerName;
+}
+/*-----------------------------------------------------------*/
+
+static void prvProcessExpiredTimer( const TickType_t xNextExpireTime, const TickType_t xTimeNow )
+{
+BaseType_t xResult;
+Timer_t * const pxTimer = ( Timer_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList );
+
+	/* Remove the timer from the list of active timers.  A check has already
+	been performed to ensure the list is not empty. */
+	( void ) uxListRemove( &( pxTimer->xTimerListItem ) );
+	traceTIMER_EXPIRED( pxTimer );
+
+	/* If the timer is an auto reload timer then calculate the next
+	expiry time and re-insert the timer in the list of active timers. */
+	if( pxTimer->uxAutoReload == ( UBaseType_t ) pdTRUE )
+	{
+		/* The timer is inserted into a list using a time relative to anything
+		other than the current time.  It will therefore be inserted into the
+		correct list relative to the time this task thinks it is now. */
+		if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE )
+		{
+			/* The timer expired before it was added to the active timer
+			list.  Reload it now.  */
+			xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xNextExpireTime, NULL, tmrNO_DELAY );
+			configASSERT( xResult );
+			( void ) xResult;
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	else
+	{
+		mtCOVERAGE_TEST_MARKER();
+	}
+
+	/* Call the timer callback. */
+	pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer );
+}
+/*-----------------------------------------------------------*/
+
+static void prvTimerTask( void *pvParameters )
+{
+TickType_t xNextExpireTime;
+BaseType_t xListWasEmpty;
+
+	/* Just to avoid compiler warnings. */
+	( void ) pvParameters;
+
+	for( ;; )
+	{
+		/* Query the timers list to see if it contains any timers, and if so,
+		obtain the time at which the next timer will expire. */
+		xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty );
+
+		/* If a timer has expired, process it.  Otherwise, block this task
+		until either a timer does expire, or a command is received. */
+		prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty );
+
+		/* Empty the command queue. */
+		prvProcessReceivedCommands();
+	}
+}
+/*-----------------------------------------------------------*/
+
+static void prvProcessTimerOrBlockTask( const TickType_t xNextExpireTime, BaseType_t xListWasEmpty )
+{
+TickType_t xTimeNow;
+BaseType_t xTimerListsWereSwitched;
+
+	vTaskSuspendAll();
+	{
+		/* Obtain the time now to make an assessment as to whether the timer
+		has expired or not.  If obtaining the time causes the lists to switch
+		then don't process this timer as any timers that remained in the list
+		when the lists were switched will have been processed within the
+		prvSampleTimeNow() function. */
+		xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched );
+		if( xTimerListsWereSwitched == pdFALSE )
+		{
+			/* The tick count has not overflowed, has the timer expired? */
+			if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) )
+			{
+				( void ) xTaskResumeAll();
+				prvProcessExpiredTimer( xNextExpireTime, xTimeNow );
+			}
+			else
+			{
+				/* The tick count has not overflowed, and the next expire
+				time has not been reached yet.  This task should therefore
+				block to wait for the next expire time or a command to be
+				received - whichever comes first.  The following line cannot
+				be reached unless xNextExpireTime > xTimeNow, except in the
+				case when the current timer list is empty. */
+				if( xListWasEmpty != pdFALSE )
+				{
+					/* The current timer list is empty - is the overflow list
+					also empty? */
+					xListWasEmpty = listLIST_IS_EMPTY( pxOverflowTimerList );
+				}
+
+				vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ), xListWasEmpty );
+
+				if( xTaskResumeAll() == pdFALSE )
+				{
+					/* Yield to wait for either a command to arrive, or the
+					block time to expire.  If a command arrived between the
+					critical section being exited and this yield then the yield
+					will not cause the task to block. */
+					portYIELD_WITHIN_API();
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+		}
+		else
+		{
+			( void ) xTaskResumeAll();
+		}
+	}
+}
+/*-----------------------------------------------------------*/
+
+static TickType_t prvGetNextExpireTime( BaseType_t * const pxListWasEmpty )
+{
+TickType_t xNextExpireTime;
+
+	/* Timers are listed in expiry time order, with the head of the list
+	referencing the task that will expire first.  Obtain the time at which
+	the timer with the nearest expiry time will expire.  If there are no
+	active timers then just set the next expire time to 0.  That will cause
+	this task to unblock when the tick count overflows, at which point the
+	timer lists will be switched and the next expiry time can be
+	re-assessed.  */
+	*pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList );
+	if( *pxListWasEmpty == pdFALSE )
+	{
+		xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList );
+	}
+	else
+	{
+		/* Ensure the task unblocks when the tick count rolls over. */
+		xNextExpireTime = ( TickType_t ) 0U;
+	}
+
+	return xNextExpireTime;
+}
+/*-----------------------------------------------------------*/
+
+static TickType_t prvSampleTimeNow( BaseType_t * const pxTimerListsWereSwitched )
+{
+TickType_t xTimeNow;
+PRIVILEGED_DATA static TickType_t xLastTime = ( TickType_t ) 0U; /*lint !e956 Variable is only accessible to one task. */
+
+	xTimeNow = xTaskGetTickCount();
+
+	if( xTimeNow < xLastTime )
+	{
+		prvSwitchTimerLists();
+		*pxTimerListsWereSwitched = pdTRUE;
+	}
+	else
+	{
+		*pxTimerListsWereSwitched = pdFALSE;
+	}
+
+	xLastTime = xTimeNow;
+
+	return xTimeNow;
+}
+/*-----------------------------------------------------------*/
+
+static BaseType_t prvInsertTimerInActiveList( Timer_t * const pxTimer, const TickType_t xNextExpiryTime, const TickType_t xTimeNow, const TickType_t xCommandTime )
+{
+BaseType_t xProcessTimerNow = pdFALSE;
+
+	listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime );
+	listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer );
+
+	if( xNextExpiryTime <= xTimeNow )
+	{
+		/* Has the expiry time elapsed between the command to start/reset a
+		timer was issued, and the time the command was processed? */
+		if( ( xTimeNow - xCommandTime ) >= pxTimer->xTimerPeriodInTicks )
+		{
+			/* The time between a command being issued and the command being
+			processed actually exceeds the timers period.  */
+			xProcessTimerNow = pdTRUE;
+		}
+		else
+		{
+			vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) );
+		}
+	}
+	else
+	{
+		if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) )
+		{
+			/* If, since the command was issued, the tick count has overflowed
+			but the expiry time has not, then the timer must have already passed
+			its expiry time and should be processed immediately. */
+			xProcessTimerNow = pdTRUE;
+		}
+		else
+		{
+			vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) );
+		}
+	}
+
+	return xProcessTimerNow;
+}
+/*-----------------------------------------------------------*/
+
+static void	prvProcessReceivedCommands( void )
+{
+DaemonTaskMessage_t xMessage;
+Timer_t *pxTimer;
+BaseType_t xTimerListsWereSwitched, xResult;
+TickType_t xTimeNow;
+
+	while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) /*lint !e603 xMessage does not have to be initialised as it is passed out, not in, and it is not used unless xQueueReceive() returns pdTRUE. */
+	{
+		#if ( INCLUDE_xTimerPendFunctionCall == 1 )
+		{
+			/* Negative commands are pended function calls rather than timer
+			commands. */
+			if( xMessage.xMessageID < ( BaseType_t ) 0 )
+			{
+				const CallbackParameters_t * const pxCallback = &( xMessage.u.xCallbackParameters );
+
+				/* The timer uses the xCallbackParameters member to request a
+				callback be executed.  Check the callback is not NULL. */
+				configASSERT( pxCallback );
+
+				/* Call the function. */
+				pxCallback->pxCallbackFunction( pxCallback->pvParameter1, pxCallback->ulParameter2 );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+		}
+		#endif /* INCLUDE_xTimerPendFunctionCall */
+
+		/* Commands that are positive are timer commands rather than pended
+		function calls. */
+		if( xMessage.xMessageID >= ( BaseType_t ) 0 )
+		{
+			/* The messages uses the xTimerParameters member to work on a
+			software timer. */
+			pxTimer = xMessage.u.xTimerParameters.pxTimer;
+
+			if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE )
+			{
+				/* The timer is in a list, remove it. */
+				( void ) uxListRemove( &( pxTimer->xTimerListItem ) );
+			}
+			else
+			{
+				mtCOVERAGE_TEST_MARKER();
+			}
+
+			traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.u.xTimerParameters.xMessageValue );
+
+			/* In this case the xTimerListsWereSwitched parameter is not used, but
+			it must be present in the function call.  prvSampleTimeNow() must be
+			called after the message is received from xTimerQueue so there is no
+			possibility of a higher priority task adding a message to the message
+			queue with a time that is ahead of the timer daemon task (because it
+			pre-empted the timer daemon task after the xTimeNow value was set). */
+			xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched );
+
+			switch( xMessage.xMessageID )
+			{
+				case tmrCOMMAND_START :
+			    case tmrCOMMAND_START_FROM_ISR :
+			    case tmrCOMMAND_RESET :
+			    case tmrCOMMAND_RESET_FROM_ISR :
+				case tmrCOMMAND_START_DONT_TRACE :
+					/* Start or restart a timer. */
+					if( prvInsertTimerInActiveList( pxTimer,  xMessage.u.xTimerParameters.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.u.xTimerParameters.xMessageValue ) == pdTRUE )
+					{
+						/* The timer expired before it was added to the active
+						timer list.  Process it now. */
+						pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer );
+						traceTIMER_EXPIRED( pxTimer );
+
+						if( pxTimer->uxAutoReload == ( UBaseType_t ) pdTRUE )
+						{
+							xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xMessage.u.xTimerParameters.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY );
+							configASSERT( xResult );
+							( void ) xResult;
+						}
+						else
+						{
+							mtCOVERAGE_TEST_MARKER();
+						}
+					}
+					else
+					{
+						mtCOVERAGE_TEST_MARKER();
+					}
+					break;
+
+				case tmrCOMMAND_STOP :
+				case tmrCOMMAND_STOP_FROM_ISR :
+					/* The timer has already been removed from the active list.
+					There is nothing to do here. */
+					break;
+
+				case tmrCOMMAND_CHANGE_PERIOD :
+				case tmrCOMMAND_CHANGE_PERIOD_FROM_ISR :
+					pxTimer->xTimerPeriodInTicks = xMessage.u.xTimerParameters.xMessageValue;
+					configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) );
+
+					/* The new period does not really have a reference, and can be
+					longer or shorter than the old one.  The command time is
+					therefore set to the current time, and as the period cannot be
+					zero the next expiry time can only be in the future, meaning
+					(unlike for the xTimerStart() case above) there is no fail case
+					that needs to be handled here. */
+					( void ) prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow );
+					break;
+
+				case tmrCOMMAND_DELETE :
+					/* The timer has already been removed from the active list,
+					just free up the memory. */
+					vPortFree( pxTimer );
+					break;
+
+				default	:
+					/* Don't expect to get here. */
+					break;
+			}
+		}
+	}
+}
+/*-----------------------------------------------------------*/
+
+static void prvSwitchTimerLists( void )
+{
+TickType_t xNextExpireTime, xReloadTime;
+List_t *pxTemp;
+Timer_t *pxTimer;
+BaseType_t xResult;
+
+	/* The tick count has overflowed.  The timer lists must be switched.
+	If there are any timers still referenced from the current timer list
+	then they must have expired and should be processed before the lists
+	are switched. */
+	while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE )
+	{
+		xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList );
+
+		/* Remove the timer from the list. */
+		pxTimer = ( Timer_t * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList );
+		( void ) uxListRemove( &( pxTimer->xTimerListItem ) );
+		traceTIMER_EXPIRED( pxTimer );
+
+		/* Execute its callback, then send a command to restart the timer if
+		it is an auto-reload timer.  It cannot be restarted here as the lists
+		have not yet been switched. */
+		pxTimer->pxCallbackFunction( ( TimerHandle_t ) pxTimer );
+
+		if( pxTimer->uxAutoReload == ( UBaseType_t ) pdTRUE )
+		{
+			/* Calculate the reload value, and if the reload value results in
+			the timer going into the same timer list then it has already expired
+			and the timer should be re-inserted into the current list so it is
+			processed again within this loop.  Otherwise a command should be sent
+			to restart the timer to ensure it is only inserted into a list after
+			the lists have been swapped. */
+			xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks );
+			if( xReloadTime > xNextExpireTime )
+			{
+				listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime );
+				listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer );
+				vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) );
+			}
+			else
+			{
+				xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START_DONT_TRACE, xNextExpireTime, NULL, tmrNO_DELAY );
+				configASSERT( xResult );
+				( void ) xResult;
+			}
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+
+	pxTemp = pxCurrentTimerList;
+	pxCurrentTimerList = pxOverflowTimerList;
+	pxOverflowTimerList = pxTemp;
+}
+/*-----------------------------------------------------------*/
+
+static void prvCheckForValidListAndQueue( void )
+{
+	/* Check that the list from which active timers are referenced, and the
+	queue used to communicate with the timer service, have been
+	initialised. */
+	taskENTER_CRITICAL();
+	{
+		if( xTimerQueue == NULL )
+		{
+			vListInitialise( &xActiveTimerList1 );
+			vListInitialise( &xActiveTimerList2 );
+			pxCurrentTimerList = &xActiveTimerList1;
+			pxOverflowTimerList = &xActiveTimerList2;
+			xTimerQueue = xQueueCreate( ( UBaseType_t ) configTIMER_QUEUE_LENGTH, sizeof( DaemonTaskMessage_t ) );
+			configASSERT( xTimerQueue );
+
+			#if ( configQUEUE_REGISTRY_SIZE > 0 )
+			{
+				if( xTimerQueue != NULL )
+				{
+					vQueueAddToRegistry( xTimerQueue, "TmrQ" );
+				}
+				else
+				{
+					mtCOVERAGE_TEST_MARKER();
+				}
+			}
+			#endif /* configQUEUE_REGISTRY_SIZE */
+		}
+		else
+		{
+			mtCOVERAGE_TEST_MARKER();
+		}
+	}
+	taskEXIT_CRITICAL();
+}
+/*-----------------------------------------------------------*/
+
+BaseType_t xTimerIsTimerActive( TimerHandle_t xTimer )
+{
+BaseType_t xTimerIsInActiveList;
+Timer_t *pxTimer = ( Timer_t * ) xTimer;
+
+	configASSERT( xTimer );
+
+	/* Is the timer in the list of active timers? */
+	taskENTER_CRITICAL();
+	{
+		/* Checking to see if it is in the NULL list in effect checks to see if
+		it is referenced from either the current or the overflow timer lists in
+		one go, but the logic has to be reversed, hence the '!'. */
+		xTimerIsInActiveList = ( BaseType_t ) !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) );
+	}
+	taskEXIT_CRITICAL();
+
+	return xTimerIsInActiveList;
+} /*lint !e818 Can't be pointer to const due to the typedef. */
+/*-----------------------------------------------------------*/
+
+void *pvTimerGetTimerID( const TimerHandle_t xTimer )
+{
+Timer_t * const pxTimer = ( Timer_t * ) xTimer;
+void *pvReturn;
+
+	configASSERT( xTimer );
+
+	taskENTER_CRITICAL();
+	{
+		pvReturn = pxTimer->pvTimerID;
+	}
+	taskEXIT_CRITICAL();
+
+	return pvReturn;
+}
+/*-----------------------------------------------------------*/
+
+void vTimerSetTimerID( TimerHandle_t xTimer, void *pvNewID )
+{
+Timer_t * const pxTimer = ( Timer_t * ) xTimer;
+
+	configASSERT( xTimer );
+
+	taskENTER_CRITICAL();
+	{
+		pxTimer->pvTimerID = pvNewID;
+	}
+	taskEXIT_CRITICAL();
+}
+/*-----------------------------------------------------------*/
+
+#if( INCLUDE_xTimerPendFunctionCall == 1 )
+
+	BaseType_t xTimerPendFunctionCallFromISR( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, BaseType_t *pxHigherPriorityTaskWoken )
+	{
+	DaemonTaskMessage_t xMessage;
+	BaseType_t xReturn;
+
+		/* Complete the message with the function parameters and post it to the
+		daemon task. */
+		xMessage.xMessageID = tmrCOMMAND_EXECUTE_CALLBACK_FROM_ISR;
+		xMessage.u.xCallbackParameters.pxCallbackFunction = xFunctionToPend;
+		xMessage.u.xCallbackParameters.pvParameter1 = pvParameter1;
+		xMessage.u.xCallbackParameters.ulParameter2 = ulParameter2;
+
+		xReturn = xQueueSendFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken );
+
+		tracePEND_FUNC_CALL_FROM_ISR( xFunctionToPend, pvParameter1, ulParameter2, xReturn );
+
+		return xReturn;
+	}
+
+#endif /* INCLUDE_xTimerPendFunctionCall */
+/*-----------------------------------------------------------*/
+
+#if( INCLUDE_xTimerPendFunctionCall == 1 )
+
+	BaseType_t xTimerPendFunctionCall( PendedFunction_t xFunctionToPend, void *pvParameter1, uint32_t ulParameter2, TickType_t xTicksToWait )
+	{
+	DaemonTaskMessage_t xMessage;
+	BaseType_t xReturn;
+
+		/* This function can only be called after a timer has been created or
+		after the scheduler has been started because, until then, the timer
+		queue does not exist. */
+		configASSERT( xTimerQueue );
+
+		/* Complete the message with the function parameters and post it to the
+		daemon task. */
+		xMessage.xMessageID = tmrCOMMAND_EXECUTE_CALLBACK;
+		xMessage.u.xCallbackParameters.pxCallbackFunction = xFunctionToPend;
+		xMessage.u.xCallbackParameters.pvParameter1 = pvParameter1;
+		xMessage.u.xCallbackParameters.ulParameter2 = ulParameter2;
+
+		xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xTicksToWait );
+
+		tracePEND_FUNC_CALL( xFunctionToPend, pvParameter1, ulParameter2, xReturn );
+
+		return xReturn;
+	}
+
+#endif /* INCLUDE_xTimerPendFunctionCall */
+/*-----------------------------------------------------------*/
+
+/* This entire source file will be skipped if the application is not configured
+to include software timer functionality.  If you want to include software timer
+functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */
+#endif /* configUSE_TIMERS == 1 */
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/misc.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/misc.h
new file mode 100644
index 0000000000000000000000000000000000000000..7f61f8317b8f3b55659c3d2b9d9c72b9c65713ec
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/misc.h
@@ -0,0 +1,219 @@
+/**
+  ******************************************************************************
+  * @file    misc.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the miscellaneous
+  *          firmware library functions (add-on to CMSIS functions).
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MISC_H
+#define __MISC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup MISC
+  * @{
+  */
+
+/** @defgroup MISC_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  NVIC Init Structure definition  
+  */
+
+typedef struct
+{
+  uint8_t NVIC_IRQChannel;                    /*!< Specifies the IRQ channel to be enabled or disabled.
+                                                   This parameter can be a value of @ref IRQn_Type 
+                                                   (For the complete STM32 Devices IRQ Channels list, please
+                                                    refer to stm32f10x.h file) */
+
+  uint8_t NVIC_IRQChannelPreemptionPriority;  /*!< Specifies the pre-emption priority for the IRQ channel
+                                                   specified in NVIC_IRQChannel. This parameter can be a value
+                                                   between 0 and 15 as described in the table @ref NVIC_Priority_Table */
+
+  uint8_t NVIC_IRQChannelSubPriority;         /*!< Specifies the subpriority level for the IRQ channel specified
+                                                   in NVIC_IRQChannel. This parameter can be a value
+                                                   between 0 and 15 as described in the table @ref NVIC_Priority_Table */
+
+  FunctionalState NVIC_IRQChannelCmd;         /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel
+                                                   will be enabled or disabled. 
+                                                   This parameter can be set either to ENABLE or DISABLE */   
+} NVIC_InitTypeDef;
+ 
+/**
+  * @}
+  */
+
+/** @defgroup NVIC_Priority_Table 
+  * @{
+  */
+
+/**
+@code  
+ The table below gives the allowed values of the pre-emption priority and subpriority according
+ to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function
+  ============================================================================================================================
+    NVIC_PriorityGroup   | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority  | Description
+  ============================================================================================================================
+   NVIC_PriorityGroup_0  |                0                  |            0-15             |   0 bits for pre-emption priority
+                         |                                   |                             |   4 bits for subpriority
+  ----------------------------------------------------------------------------------------------------------------------------
+   NVIC_PriorityGroup_1  |                0-1                |            0-7              |   1 bits for pre-emption priority
+                         |                                   |                             |   3 bits for subpriority
+  ----------------------------------------------------------------------------------------------------------------------------    
+   NVIC_PriorityGroup_2  |                0-3                |            0-3              |   2 bits for pre-emption priority
+                         |                                   |                             |   2 bits for subpriority
+  ----------------------------------------------------------------------------------------------------------------------------    
+   NVIC_PriorityGroup_3  |                0-7                |            0-1              |   3 bits for pre-emption priority
+                         |                                   |                             |   1 bits for subpriority
+  ----------------------------------------------------------------------------------------------------------------------------    
+   NVIC_PriorityGroup_4  |                0-15               |            0                |   4 bits for pre-emption priority
+                         |                                   |                             |   0 bits for subpriority                       
+  ============================================================================================================================
+@endcode
+*/
+
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup Vector_Table_Base 
+  * @{
+  */
+
+#define NVIC_VectTab_RAM             ((uint32_t)0x20000000)
+#define NVIC_VectTab_FLASH           ((uint32_t)0x08000000)
+#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \
+                                  ((VECTTAB) == NVIC_VectTab_FLASH))
+/**
+  * @}
+  */
+
+/** @defgroup System_Low_Power 
+  * @{
+  */
+
+#define NVIC_LP_SEVONPEND            ((uint8_t)0x10)
+#define NVIC_LP_SLEEPDEEP            ((uint8_t)0x04)
+#define NVIC_LP_SLEEPONEXIT          ((uint8_t)0x02)
+#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \
+                        ((LP) == NVIC_LP_SLEEPDEEP) || \
+                        ((LP) == NVIC_LP_SLEEPONEXIT))
+/**
+  * @}
+  */
+
+/** @defgroup Preemption_Priority_Group 
+  * @{
+  */
+
+#define NVIC_PriorityGroup_0         ((uint32_t)0x700) /*!< 0 bits for pre-emption priority
+                                                            4 bits for subpriority */
+#define NVIC_PriorityGroup_1         ((uint32_t)0x600) /*!< 1 bits for pre-emption priority
+                                                            3 bits for subpriority */
+#define NVIC_PriorityGroup_2         ((uint32_t)0x500) /*!< 2 bits for pre-emption priority
+                                                            2 bits for subpriority */
+#define NVIC_PriorityGroup_3         ((uint32_t)0x400) /*!< 3 bits for pre-emption priority
+                                                            1 bits for subpriority */
+#define NVIC_PriorityGroup_4         ((uint32_t)0x300) /*!< 4 bits for pre-emption priority
+                                                            0 bits for subpriority */
+
+#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \
+                                       ((GROUP) == NVIC_PriorityGroup_1) || \
+                                       ((GROUP) == NVIC_PriorityGroup_2) || \
+                                       ((GROUP) == NVIC_PriorityGroup_3) || \
+                                       ((GROUP) == NVIC_PriorityGroup_4))
+
+#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY)  ((PRIORITY) < 0x10)
+
+#define IS_NVIC_SUB_PRIORITY(PRIORITY)  ((PRIORITY) < 0x10)
+
+#define IS_NVIC_OFFSET(OFFSET)  ((OFFSET) < 0x0007FFFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup SysTick_clock_source 
+  * @{
+  */
+
+#define SysTick_CLKSource_HCLK_Div8    ((uint32_t)0xFFFFFFFB)
+#define SysTick_CLKSource_HCLK         ((uint32_t)0x00000004)
+#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
+                                       ((SOURCE) == SysTick_CLKSource_HCLK_Div8))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Exported_Functions
+  * @{
+  */
+
+void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup);
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct);
+void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset);
+void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState);
+void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MISC_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h
new file mode 100644
index 0000000000000000000000000000000000000000..c8a07be3802dadf80f12259bd1ef38c3a5b3d425
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h
@@ -0,0 +1,479 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_adc.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the ADC firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_ADC_H
+#define __STM32F10x_ADC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup ADC
+  * @{
+  */
+
+/** @defgroup ADC_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  ADC Init structure definition  
+  */
+
+typedef struct
+{
+  uint32_t ADC_Mode;                      /*!< Configures the ADC to operate in independent or
+                                               dual mode. 
+                                               This parameter can be a value of @ref ADC_mode */
+
+  FunctionalState ADC_ScanConvMode;       /*!< Specifies whether the conversion is performed in
+                                               Scan (multichannels) or Single (one channel) mode.
+                                               This parameter can be set to ENABLE or DISABLE */
+
+  FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in
+                                               Continuous or Single mode.
+                                               This parameter can be set to ENABLE or DISABLE. */
+
+  uint32_t ADC_ExternalTrigConv;          /*!< Defines the external trigger used to start the analog
+                                               to digital conversion of regular channels. This parameter
+                                               can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */
+
+  uint32_t ADC_DataAlign;                 /*!< Specifies whether the ADC data alignment is left or right.
+                                               This parameter can be a value of @ref ADC_data_align */
+
+  uint8_t ADC_NbrOfChannel;               /*!< Specifies the number of ADC channels that will be converted
+                                               using the sequencer for regular channel group.
+                                               This parameter must range from 1 to 16. */
+}ADC_InitTypeDef;
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Exported_Constants
+  * @{
+  */
+
+#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \
+                                   ((PERIPH) == ADC2) || \
+                                   ((PERIPH) == ADC3))
+
+#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \
+                                   ((PERIPH) == ADC3))
+
+/** @defgroup ADC_mode 
+  * @{
+  */
+
+#define ADC_Mode_Independent                       ((uint32_t)0x00000000)
+#define ADC_Mode_RegInjecSimult                    ((uint32_t)0x00010000)
+#define ADC_Mode_RegSimult_AlterTrig               ((uint32_t)0x00020000)
+#define ADC_Mode_InjecSimult_FastInterl            ((uint32_t)0x00030000)
+#define ADC_Mode_InjecSimult_SlowInterl            ((uint32_t)0x00040000)
+#define ADC_Mode_InjecSimult                       ((uint32_t)0x00050000)
+#define ADC_Mode_RegSimult                         ((uint32_t)0x00060000)
+#define ADC_Mode_FastInterl                        ((uint32_t)0x00070000)
+#define ADC_Mode_SlowInterl                        ((uint32_t)0x00080000)
+#define ADC_Mode_AlterTrig                         ((uint32_t)0x00090000)
+
+#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \
+                           ((MODE) == ADC_Mode_RegInjecSimult) || \
+                           ((MODE) == ADC_Mode_RegSimult_AlterTrig) || \
+                           ((MODE) == ADC_Mode_InjecSimult_FastInterl) || \
+                           ((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \
+                           ((MODE) == ADC_Mode_InjecSimult) || \
+                           ((MODE) == ADC_Mode_RegSimult) || \
+                           ((MODE) == ADC_Mode_FastInterl) || \
+                           ((MODE) == ADC_Mode_SlowInterl) || \
+                           ((MODE) == ADC_Mode_AlterTrig))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion 
+  * @{
+  */
+
+#define ADC_ExternalTrigConv_T1_CC1                ((uint32_t)0x00000000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigConv_T1_CC2                ((uint32_t)0x00020000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigConv_T2_CC2                ((uint32_t)0x00060000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigConv_T3_TRGO               ((uint32_t)0x00080000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigConv_T4_CC4                ((uint32_t)0x000A0000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO    ((uint32_t)0x000C0000) /*!< For ADC1 and ADC2 */
+
+#define ADC_ExternalTrigConv_T1_CC3                ((uint32_t)0x00040000) /*!< For ADC1, ADC2 and ADC3 */
+#define ADC_ExternalTrigConv_None                  ((uint32_t)0x000E0000) /*!< For ADC1, ADC2 and ADC3 */
+
+#define ADC_ExternalTrigConv_T3_CC1                ((uint32_t)0x00000000) /*!< For ADC3 only */
+#define ADC_ExternalTrigConv_T2_CC3                ((uint32_t)0x00020000) /*!< For ADC3 only */
+#define ADC_ExternalTrigConv_T8_CC1                ((uint32_t)0x00060000) /*!< For ADC3 only */
+#define ADC_ExternalTrigConv_T8_TRGO               ((uint32_t)0x00080000) /*!< For ADC3 only */
+#define ADC_ExternalTrigConv_T5_CC1                ((uint32_t)0x000A0000) /*!< For ADC3 only */
+#define ADC_ExternalTrigConv_T5_CC3                ((uint32_t)0x000C0000) /*!< For ADC3 only */
+
+#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_None) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_data_align 
+  * @{
+  */
+
+#define ADC_DataAlign_Right                        ((uint32_t)0x00000000)
+#define ADC_DataAlign_Left                         ((uint32_t)0x00000800)
+#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \
+                                  ((ALIGN) == ADC_DataAlign_Left))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_channels 
+  * @{
+  */
+
+#define ADC_Channel_0                               ((uint8_t)0x00)
+#define ADC_Channel_1                               ((uint8_t)0x01)
+#define ADC_Channel_2                               ((uint8_t)0x02)
+#define ADC_Channel_3                               ((uint8_t)0x03)
+#define ADC_Channel_4                               ((uint8_t)0x04)
+#define ADC_Channel_5                               ((uint8_t)0x05)
+#define ADC_Channel_6                               ((uint8_t)0x06)
+#define ADC_Channel_7                               ((uint8_t)0x07)
+#define ADC_Channel_8                               ((uint8_t)0x08)
+#define ADC_Channel_9                               ((uint8_t)0x09)
+#define ADC_Channel_10                              ((uint8_t)0x0A)
+#define ADC_Channel_11                              ((uint8_t)0x0B)
+#define ADC_Channel_12                              ((uint8_t)0x0C)
+#define ADC_Channel_13                              ((uint8_t)0x0D)
+#define ADC_Channel_14                              ((uint8_t)0x0E)
+#define ADC_Channel_15                              ((uint8_t)0x0F)
+#define ADC_Channel_16                              ((uint8_t)0x10)
+#define ADC_Channel_17                              ((uint8_t)0x11)
+
+#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \
+                                 ((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \
+                                 ((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \
+                                 ((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \
+                                 ((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \
+                                 ((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \
+                                 ((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \
+                                 ((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \
+                                 ((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_sampling_time 
+  * @{
+  */
+
+#define ADC_SampleTime_1Cycles5                    ((uint8_t)0x00)
+#define ADC_SampleTime_7Cycles5                    ((uint8_t)0x01)
+#define ADC_SampleTime_13Cycles5                   ((uint8_t)0x02)
+#define ADC_SampleTime_28Cycles5                   ((uint8_t)0x03)
+#define ADC_SampleTime_41Cycles5                   ((uint8_t)0x04)
+#define ADC_SampleTime_55Cycles5                   ((uint8_t)0x05)
+#define ADC_SampleTime_71Cycles5                   ((uint8_t)0x06)
+#define ADC_SampleTime_239Cycles5                  ((uint8_t)0x07)
+#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \
+                                  ((TIME) == ADC_SampleTime_7Cycles5) || \
+                                  ((TIME) == ADC_SampleTime_13Cycles5) || \
+                                  ((TIME) == ADC_SampleTime_28Cycles5) || \
+                                  ((TIME) == ADC_SampleTime_41Cycles5) || \
+                                  ((TIME) == ADC_SampleTime_55Cycles5) || \
+                                  ((TIME) == ADC_SampleTime_71Cycles5) || \
+                                  ((TIME) == ADC_SampleTime_239Cycles5))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_external_trigger_sources_for_injected_channels_conversion 
+  * @{
+  */
+
+#define ADC_ExternalTrigInjecConv_T2_TRGO           ((uint32_t)0x00002000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigInjecConv_T2_CC1            ((uint32_t)0x00003000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigInjecConv_T3_CC4            ((uint32_t)0x00004000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigInjecConv_T4_TRGO           ((uint32_t)0x00005000) /*!< For ADC1 and ADC2 */
+#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((uint32_t)0x00006000) /*!< For ADC1 and ADC2 */
+
+#define ADC_ExternalTrigInjecConv_T1_TRGO           ((uint32_t)0x00000000) /*!< For ADC1, ADC2 and ADC3 */
+#define ADC_ExternalTrigInjecConv_T1_CC4            ((uint32_t)0x00001000) /*!< For ADC1, ADC2 and ADC3 */
+#define ADC_ExternalTrigInjecConv_None              ((uint32_t)0x00007000) /*!< For ADC1, ADC2 and ADC3 */
+
+#define ADC_ExternalTrigInjecConv_T4_CC3            ((uint32_t)0x00002000) /*!< For ADC3 only */
+#define ADC_ExternalTrigInjecConv_T8_CC2            ((uint32_t)0x00003000) /*!< For ADC3 only */
+#define ADC_ExternalTrigInjecConv_T8_CC4            ((uint32_t)0x00004000) /*!< For ADC3 only */
+#define ADC_ExternalTrigInjecConv_T5_TRGO           ((uint32_t)0x00005000) /*!< For ADC3 only */
+#define ADC_ExternalTrigInjecConv_T5_CC4            ((uint32_t)0x00006000) /*!< For ADC3 only */
+
+#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_injected_channel_selection 
+  * @{
+  */
+
+#define ADC_InjectedChannel_1                       ((uint8_t)0x14)
+#define ADC_InjectedChannel_2                       ((uint8_t)0x18)
+#define ADC_InjectedChannel_3                       ((uint8_t)0x1C)
+#define ADC_InjectedChannel_4                       ((uint8_t)0x20)
+#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \
+                                          ((CHANNEL) == ADC_InjectedChannel_2) || \
+                                          ((CHANNEL) == ADC_InjectedChannel_3) || \
+                                          ((CHANNEL) == ADC_InjectedChannel_4))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_analog_watchdog_selection 
+  * @{
+  */
+
+#define ADC_AnalogWatchdog_SingleRegEnable         ((uint32_t)0x00800200)
+#define ADC_AnalogWatchdog_SingleInjecEnable       ((uint32_t)0x00400200)
+#define ADC_AnalogWatchdog_SingleRegOrInjecEnable  ((uint32_t)0x00C00200)
+#define ADC_AnalogWatchdog_AllRegEnable            ((uint32_t)0x00800000)
+#define ADC_AnalogWatchdog_AllInjecEnable          ((uint32_t)0x00400000)
+#define ADC_AnalogWatchdog_AllRegAllInjecEnable    ((uint32_t)0x00C00000)
+#define ADC_AnalogWatchdog_None                    ((uint32_t)0x00000000)
+
+#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_None))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_interrupts_definition 
+  * @{
+  */
+
+#define ADC_IT_EOC                                 ((uint16_t)0x0220)
+#define ADC_IT_AWD                                 ((uint16_t)0x0140)
+#define ADC_IT_JEOC                                ((uint16_t)0x0480)
+
+#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF81F) == 0x00) && ((IT) != 0x00))
+
+#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \
+                           ((IT) == ADC_IT_JEOC))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_flags_definition 
+  * @{
+  */
+
+#define ADC_FLAG_AWD                               ((uint8_t)0x01)
+#define ADC_FLAG_EOC                               ((uint8_t)0x02)
+#define ADC_FLAG_JEOC                              ((uint8_t)0x04)
+#define ADC_FLAG_JSTRT                             ((uint8_t)0x08)
+#define ADC_FLAG_STRT                              ((uint8_t)0x10)
+#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xE0) == 0x00) && ((FLAG) != 0x00))
+#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \
+                               ((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \
+                               ((FLAG) == ADC_FLAG_STRT))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_thresholds 
+  * @{
+  */
+
+#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_injected_offset 
+  * @{
+  */
+
+#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_injected_length 
+  * @{
+  */
+
+#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4))
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_injected_rank 
+  * @{
+  */
+
+#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4))
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_regular_length 
+  * @{
+  */
+
+#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10))
+/**
+  * @}
+  */
+
+/** @defgroup ADC_regular_rank 
+  * @{
+  */
+
+#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10))
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_regular_discontinuous_mode_number 
+  * @{
+  */
+
+#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8))
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Exported_Functions
+  * @{
+  */
+
+void ADC_DeInit(ADC_TypeDef* ADCx);
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct);
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct);
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState);
+void ADC_ResetCalibration(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx);
+void ADC_StartCalibration(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx);
+void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx);
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number);
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
+void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx);
+uint32_t ADC_GetDualModeConversionValue(void);
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv);
+void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx);
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length);
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset);
+uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel);
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog);
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold);
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel);
+void ADC_TempSensorVrefintCmd(FunctionalState NewState);
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
+void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT);
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_ADC_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h
new file mode 100644
index 0000000000000000000000000000000000000000..1c16cdaf120089bdbc89ebabf962ce8406f91fa6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h
@@ -0,0 +1,194 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_bkp.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the BKP firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_BKP_H
+#define __STM32F10x_BKP_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup BKP
+  * @{
+  */
+
+/** @defgroup BKP_Exported_Types
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup BKP_Exported_Constants
+  * @{
+  */
+
+/** @defgroup Tamper_Pin_active_level 
+  * @{
+  */
+
+#define BKP_TamperPinLevel_High           ((uint16_t)0x0000)
+#define BKP_TamperPinLevel_Low            ((uint16_t)0x0001)
+#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \
+                                        ((LEVEL) == BKP_TamperPinLevel_Low))
+/**
+  * @}
+  */
+
+/** @defgroup RTC_output_source_to_output_on_the_Tamper_pin 
+  * @{
+  */
+
+#define BKP_RTCOutputSource_None          ((uint16_t)0x0000)
+#define BKP_RTCOutputSource_CalibClock    ((uint16_t)0x0080)
+#define BKP_RTCOutputSource_Alarm         ((uint16_t)0x0100)
+#define BKP_RTCOutputSource_Second        ((uint16_t)0x0300)
+#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \
+                                          ((SOURCE) == BKP_RTCOutputSource_CalibClock) || \
+                                          ((SOURCE) == BKP_RTCOutputSource_Alarm) || \
+                                          ((SOURCE) == BKP_RTCOutputSource_Second))
+/**
+  * @}
+  */
+
+/** @defgroup Data_Backup_Register 
+  * @{
+  */
+
+#define BKP_DR1                           ((uint16_t)0x0004)
+#define BKP_DR2                           ((uint16_t)0x0008)
+#define BKP_DR3                           ((uint16_t)0x000C)
+#define BKP_DR4                           ((uint16_t)0x0010)
+#define BKP_DR5                           ((uint16_t)0x0014)
+#define BKP_DR6                           ((uint16_t)0x0018)
+#define BKP_DR7                           ((uint16_t)0x001C)
+#define BKP_DR8                           ((uint16_t)0x0020)
+#define BKP_DR9                           ((uint16_t)0x0024)
+#define BKP_DR10                          ((uint16_t)0x0028)
+#define BKP_DR11                          ((uint16_t)0x0040)
+#define BKP_DR12                          ((uint16_t)0x0044)
+#define BKP_DR13                          ((uint16_t)0x0048)
+#define BKP_DR14                          ((uint16_t)0x004C)
+#define BKP_DR15                          ((uint16_t)0x0050)
+#define BKP_DR16                          ((uint16_t)0x0054)
+#define BKP_DR17                          ((uint16_t)0x0058)
+#define BKP_DR18                          ((uint16_t)0x005C)
+#define BKP_DR19                          ((uint16_t)0x0060)
+#define BKP_DR20                          ((uint16_t)0x0064)
+#define BKP_DR21                          ((uint16_t)0x0068)
+#define BKP_DR22                          ((uint16_t)0x006C)
+#define BKP_DR23                          ((uint16_t)0x0070)
+#define BKP_DR24                          ((uint16_t)0x0074)
+#define BKP_DR25                          ((uint16_t)0x0078)
+#define BKP_DR26                          ((uint16_t)0x007C)
+#define BKP_DR27                          ((uint16_t)0x0080)
+#define BKP_DR28                          ((uint16_t)0x0084)
+#define BKP_DR29                          ((uint16_t)0x0088)
+#define BKP_DR30                          ((uint16_t)0x008C)
+#define BKP_DR31                          ((uint16_t)0x0090)
+#define BKP_DR32                          ((uint16_t)0x0094)
+#define BKP_DR33                          ((uint16_t)0x0098)
+#define BKP_DR34                          ((uint16_t)0x009C)
+#define BKP_DR35                          ((uint16_t)0x00A0)
+#define BKP_DR36                          ((uint16_t)0x00A4)
+#define BKP_DR37                          ((uint16_t)0x00A8)
+#define BKP_DR38                          ((uint16_t)0x00AC)
+#define BKP_DR39                          ((uint16_t)0x00B0)
+#define BKP_DR40                          ((uint16_t)0x00B4)
+#define BKP_DR41                          ((uint16_t)0x00B8)
+#define BKP_DR42                          ((uint16_t)0x00BC)
+
+#define IS_BKP_DR(DR) (((DR) == BKP_DR1)  || ((DR) == BKP_DR2)  || ((DR) == BKP_DR3)  || \
+                       ((DR) == BKP_DR4)  || ((DR) == BKP_DR5)  || ((DR) == BKP_DR6)  || \
+                       ((DR) == BKP_DR7)  || ((DR) == BKP_DR8)  || ((DR) == BKP_DR9)  || \
+                       ((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \
+                       ((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \
+                       ((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \
+                       ((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \
+                       ((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \
+                       ((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \
+                       ((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \
+                       ((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \
+                       ((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \
+                       ((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \
+                       ((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42))
+
+#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F)
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup BKP_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup BKP_Exported_Functions
+  * @{
+  */
+
+void BKP_DeInit(void);
+void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel);
+void BKP_TamperPinCmd(FunctionalState NewState);
+void BKP_ITConfig(FunctionalState NewState);
+void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource);
+void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue);
+void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data);
+uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR);
+FlagStatus BKP_GetFlagStatus(void);
+void BKP_ClearFlag(void);
+ITStatus BKP_GetITStatus(void);
+void BKP_ClearITPendingBit(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_BKP_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h
new file mode 100644
index 0000000000000000000000000000000000000000..e8b430fc609089c38b3eaf543bd6ca4f72aa7a4e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h
@@ -0,0 +1,535 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_can.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the CAN firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CAN_H
+#define __STM32F10x_CAN_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup CAN
+  * @{
+  */
+
+/** @defgroup CAN_Exported_Types
+  * @{
+  */
+
+#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \
+                                   ((PERIPH) == CAN2))
+
+/** 
+  * @brief  CAN init structure definition
+  */
+
+typedef struct
+{
+  uint16_t CAN_Prescaler;   /*!< Specifies the length of a time quantum. It ranges from 1 to 1024. */
+  
+  uint8_t CAN_Mode;         /*!< Specifies the CAN operating mode.
+                                 This parameter can be a value of @ref CAN_operating_mode */
+
+  uint8_t CAN_SJW;          /*!< Specifies the maximum number of time quanta the CAN hardware
+                                 is allowed to lengthen or shorten a bit to perform resynchronization.
+                                 This parameter can be a value of @ref CAN_synchronisation_jump_width */
+
+  uint8_t CAN_BS1;          /*!< Specifies the number of time quanta in Bit Segment 1.
+                                 This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */
+
+  uint8_t CAN_BS2;          /*!< Specifies the number of time quanta in Bit Segment 2.
+                                 This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */
+  
+  FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered communication mode.
+                                 This parameter can be set either to ENABLE or DISABLE. */
+  
+  FunctionalState CAN_ABOM;  /*!< Enable or disable the automatic bus-off management.
+                                 This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_AWUM;  /*!< Enable or disable the automatic wake-up mode. 
+                                 This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_NART;  /*!< Enable or disable the no-automatic retransmission mode.
+                                 This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_RFLM;  /*!< Enable or disable the Receive FIFO Locked mode.
+                                 This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_TXFP;  /*!< Enable or disable the transmit FIFO priority.
+                                 This parameter can be set either to ENABLE or DISABLE. */
+} CAN_InitTypeDef;
+
+/** 
+  * @brief  CAN filter init structure definition
+  */
+
+typedef struct
+{
+  uint16_t CAN_FilterIdHigh;             /*!< Specifies the filter identification number (MSBs for a 32-bit
+                                              configuration, first one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterIdLow;              /*!< Specifies the filter identification number (LSBs for a 32-bit
+                                              configuration, second one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterMaskIdHigh;         /*!< Specifies the filter mask number or identification number,
+                                              according to the mode (MSBs for a 32-bit configuration,
+                                              first one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterMaskIdLow;          /*!< Specifies the filter mask number or identification number,
+                                              according to the mode (LSBs for a 32-bit configuration,
+                                              second one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterFIFOAssignment;     /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter.
+                                              This parameter can be a value of @ref CAN_filter_FIFO */
+  
+  uint8_t CAN_FilterNumber;              /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */
+
+  uint8_t CAN_FilterMode;                /*!< Specifies the filter mode to be initialized.
+                                              This parameter can be a value of @ref CAN_filter_mode */
+
+  uint8_t CAN_FilterScale;               /*!< Specifies the filter scale.
+                                              This parameter can be a value of @ref CAN_filter_scale */
+
+  FunctionalState CAN_FilterActivation;  /*!< Enable or disable the filter.
+                                              This parameter can be set either to ENABLE or DISABLE. */
+} CAN_FilterInitTypeDef;
+
+/** 
+  * @brief  CAN Tx message structure definition  
+  */
+
+typedef struct
+{
+  uint32_t StdId;  /*!< Specifies the standard identifier.
+                        This parameter can be a value between 0 to 0x7FF. */
+
+  uint32_t ExtId;  /*!< Specifies the extended identifier.
+                        This parameter can be a value between 0 to 0x1FFFFFFF. */
+
+  uint8_t IDE;     /*!< Specifies the type of identifier for the message that will be transmitted.
+                        This parameter can be a value of @ref CAN_identifier_type */
+
+  uint8_t RTR;     /*!< Specifies the type of frame for the message that will be transmitted.
+                        This parameter can be a value of @ref CAN_remote_transmission_request */
+
+  uint8_t DLC;     /*!< Specifies the length of the frame that will be transmitted.
+                        This parameter can be a value between 0 to 8 */
+
+  uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 to 0xFF. */
+} CanTxMsg;
+
+/** 
+  * @brief  CAN Rx message structure definition  
+  */
+
+typedef struct
+{
+  uint32_t StdId;  /*!< Specifies the standard identifier.
+                        This parameter can be a value between 0 to 0x7FF. */
+
+  uint32_t ExtId;  /*!< Specifies the extended identifier.
+                        This parameter can be a value between 0 to 0x1FFFFFFF. */
+
+  uint8_t IDE;     /*!< Specifies the type of identifier for the message that will be received.
+                        This parameter can be a value of @ref CAN_identifier_type */
+
+  uint8_t RTR;     /*!< Specifies the type of frame for the received message.
+                        This parameter can be a value of @ref CAN_remote_transmission_request */
+
+  uint8_t DLC;     /*!< Specifies the length of the frame that will be received.
+                        This parameter can be a value between 0 to 8 */
+
+  uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to 0xFF. */
+
+  uint8_t FMI;     /*!< Specifies the index of the filter the message stored in the mailbox passes through.
+                        This parameter can be a value between 0 to 0xFF */
+} CanRxMsg;
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Exported_Constants
+  * @{
+  */
+
+/** @defgroup CAN_sleep_constants 
+  * @{
+  */
+
+#define CANINITFAILED              ((uint8_t)0x00) /*!< CAN initialization failed */
+#define CANINITOK                  ((uint8_t)0x01) /*!< CAN initialization failed */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_operating_mode 
+  * @{
+  */
+
+#define CAN_Mode_Normal             ((uint8_t)0x00)  /*!< normal mode */
+#define CAN_Mode_LoopBack           ((uint8_t)0x01)  /*!< loopback mode */
+#define CAN_Mode_Silent             ((uint8_t)0x02)  /*!< silent mode */
+#define CAN_Mode_Silent_LoopBack    ((uint8_t)0x03)  /*!< loopback combined with silent mode */
+
+#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || ((MODE) == CAN_Mode_LoopBack)|| \
+                           ((MODE) == CAN_Mode_Silent) || ((MODE) == CAN_Mode_Silent_LoopBack))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_synchronisation_jump_width 
+  * @{
+  */
+
+#define CAN_SJW_1tq                 ((uint8_t)0x00)  /*!< 1 time quantum */
+#define CAN_SJW_2tq                 ((uint8_t)0x01)  /*!< 2 time quantum */
+#define CAN_SJW_3tq                 ((uint8_t)0x02)  /*!< 3 time quantum */
+#define CAN_SJW_4tq                 ((uint8_t)0x03)  /*!< 4 time quantum */
+
+#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \
+                         ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_time_quantum_in_bit_segment_1 
+  * @{
+  */
+
+#define CAN_BS1_1tq                 ((uint8_t)0x00)  /*!< 1 time quantum */
+#define CAN_BS1_2tq                 ((uint8_t)0x01)  /*!< 2 time quantum */
+#define CAN_BS1_3tq                 ((uint8_t)0x02)  /*!< 3 time quantum */
+#define CAN_BS1_4tq                 ((uint8_t)0x03)  /*!< 4 time quantum */
+#define CAN_BS1_5tq                 ((uint8_t)0x04)  /*!< 5 time quantum */
+#define CAN_BS1_6tq                 ((uint8_t)0x05)  /*!< 6 time quantum */
+#define CAN_BS1_7tq                 ((uint8_t)0x06)  /*!< 7 time quantum */
+#define CAN_BS1_8tq                 ((uint8_t)0x07)  /*!< 8 time quantum */
+#define CAN_BS1_9tq                 ((uint8_t)0x08)  /*!< 9 time quantum */
+#define CAN_BS1_10tq                ((uint8_t)0x09)  /*!< 10 time quantum */
+#define CAN_BS1_11tq                ((uint8_t)0x0A)  /*!< 11 time quantum */
+#define CAN_BS1_12tq                ((uint8_t)0x0B)  /*!< 12 time quantum */
+#define CAN_BS1_13tq                ((uint8_t)0x0C)  /*!< 13 time quantum */
+#define CAN_BS1_14tq                ((uint8_t)0x0D)  /*!< 14 time quantum */
+#define CAN_BS1_15tq                ((uint8_t)0x0E)  /*!< 15 time quantum */
+#define CAN_BS1_16tq                ((uint8_t)0x0F)  /*!< 16 time quantum */
+
+#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq)
+/**
+  * @}
+  */
+
+/** @defgroup CAN_time_quantum_in_bit_segment_2 
+  * @{
+  */
+
+#define CAN_BS2_1tq                 ((uint8_t)0x00)  /*!< 1 time quantum */
+#define CAN_BS2_2tq                 ((uint8_t)0x01)  /*!< 2 time quantum */
+#define CAN_BS2_3tq                 ((uint8_t)0x02)  /*!< 3 time quantum */
+#define CAN_BS2_4tq                 ((uint8_t)0x03)  /*!< 4 time quantum */
+#define CAN_BS2_5tq                 ((uint8_t)0x04)  /*!< 5 time quantum */
+#define CAN_BS2_6tq                 ((uint8_t)0x05)  /*!< 6 time quantum */
+#define CAN_BS2_7tq                 ((uint8_t)0x06)  /*!< 7 time quantum */
+#define CAN_BS2_8tq                 ((uint8_t)0x07)  /*!< 8 time quantum */
+
+#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq)
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_clock_prescaler 
+  * @{
+  */
+
+#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024))
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_number 
+  * @{
+  */
+#ifndef STM32F10X_CL
+  #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13)
+#else
+  #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27)
+#endif /* STM32F10X_CL */ 
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_mode 
+  * @{
+  */
+
+#define CAN_FilterMode_IdMask       ((uint8_t)0x00)  /*!< id/mask mode */
+#define CAN_FilterMode_IdList       ((uint8_t)0x01)  /*!< identifier list mode */
+
+#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \
+                                  ((MODE) == CAN_FilterMode_IdList))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_scale 
+  * @{
+  */
+
+#define CAN_FilterScale_16bit       ((uint8_t)0x00) /*!< Two 16-bit filters */
+#define CAN_FilterScale_32bit       ((uint8_t)0x01) /*!< One 32-bit filter */
+
+#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \
+                                    ((SCALE) == CAN_FilterScale_32bit))
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_FIFO
+  * @{
+  */
+
+#define CAN_FilterFIFO0             ((uint8_t)0x00)  /*!< Filter FIFO 0 assignment for filter x */
+#define CAN_FilterFIFO1             ((uint8_t)0x01)  /*!< Filter FIFO 1 assignment for filter x */
+#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \
+                                  ((FIFO) == CAN_FilterFIFO1))
+
+/**
+  * @}
+  */
+
+/** @defgroup Start_bank_filter_for_slave_CAN 
+  * @{
+  */
+#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Tx 
+  * @{
+  */
+
+#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02))
+#define IS_CAN_STDID(STDID)   ((STDID) <= ((uint32_t)0x7FF))
+#define IS_CAN_EXTID(EXTID)   ((EXTID) <= ((uint32_t)0x1FFFFFFF))
+#define IS_CAN_DLC(DLC)       ((DLC) <= ((uint8_t)0x08))
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_identifier_type 
+  * @{
+  */
+
+#define CAN_ID_STD                 ((uint32_t)0x00000000)  /*!< Standard Id */
+#define CAN_ID_EXT                 ((uint32_t)0x00000004)  /*!< Extended Id */
+#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || ((IDTYPE) == CAN_ID_EXT))
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_remote_transmission_request 
+  * @{
+  */
+
+#define CAN_RTR_DATA                ((uint32_t)0x00000000)  /*!< Data frame */
+#define CAN_RTR_REMOTE              ((uint32_t)0x00000002)  /*!< Remote frame */
+#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE))
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_transmit_constants 
+  * @{
+  */
+
+#define CANTXFAILED                 ((uint8_t)0x00) /*!< CAN transmission failed */
+#define CANTXOK                     ((uint8_t)0x01) /*!< CAN transmission succeeded */
+#define CANTXPENDING                ((uint8_t)0x02) /*!< CAN transmission pending */
+#define CAN_NO_MB                   ((uint8_t)0x04) /*!< CAN cell did not provide an empty mailbox */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_receive_FIFO_number_constants 
+  * @{
+  */
+
+#define CAN_FIFO0                 ((uint8_t)0x00) /*!< CAN FIFO0 used to receive */
+#define CAN_FIFO1                 ((uint8_t)0x01) /*!< CAN FIFO1 used to receive */
+
+#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1))
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_sleep_constants 
+  * @{
+  */
+
+#define CANSLEEPFAILED              ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */
+#define CANSLEEPOK                  ((uint8_t)0x01) /*!< CAN entered the sleep mode */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_wake_up_constants 
+  * @{
+  */
+
+#define CANWAKEUPFAILED             ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */
+#define CANWAKEUPOK                 ((uint8_t)0x01) /*!< CAN leaved the sleep mode */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_flags 
+  * @{
+  */
+
+#define CAN_FLAG_EWG                ((uint32_t)0x00000001) /*!< Error Warning Flag */
+#define CAN_FLAG_EPV                ((uint32_t)0x00000002) /*!< Error Passive Flag */
+#define CAN_FLAG_BOF                ((uint32_t)0x00000004) /*!< Bus-Off Flag */
+
+#define IS_CAN_FLAG(FLAG) (((FLAG) == CAN_FLAG_EWG) || ((FLAG) == CAN_FLAG_EPV) ||\
+                           ((FLAG) == CAN_FLAG_BOF))
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_interrupts 
+  * @{
+  */
+
+#define CAN_IT_RQCP0                ((uint32_t)0x00000005) /*!< Request completed mailbox 0 */
+#define CAN_IT_RQCP1                ((uint32_t)0x00000006) /*!< Request completed mailbox 1 */
+#define CAN_IT_RQCP2                ((uint32_t)0x00000007) /*!< Request completed mailbox 2 */
+#define CAN_IT_TME                  ((uint32_t)0x00000001) /*!< Transmit mailbox empty */
+#define CAN_IT_FMP0                 ((uint32_t)0x00000002) /*!< FIFO 0 message pending */
+#define CAN_IT_FF0                  ((uint32_t)0x00000004) /*!< FIFO 0 full */
+#define CAN_IT_FOV0                 ((uint32_t)0x00000008) /*!< FIFO 0 overrun */
+#define CAN_IT_FMP1                 ((uint32_t)0x00000010) /*!< FIFO 1 message pending */
+#define CAN_IT_FF1                  ((uint32_t)0x00000020) /*!< FIFO 1 full */
+#define CAN_IT_FOV1                 ((uint32_t)0x00000040) /*!< FIFO 1 overrun */
+#define CAN_IT_EWG                  ((uint32_t)0x00000100) /*!< Error warning */
+#define CAN_IT_EPV                  ((uint32_t)0x00000200) /*!< Error passive */
+#define CAN_IT_BOF                  ((uint32_t)0x00000400) /*!< Bus-off */
+#define CAN_IT_LEC                  ((uint32_t)0x00000800) /*!< Last error code */
+#define CAN_IT_ERR                  ((uint32_t)0x00008000) /*!< Error */
+#define CAN_IT_WKU                  ((uint32_t)0x00010000) /*!< Wake-up */
+#define CAN_IT_SLK                  ((uint32_t)0x00020000) /*!< Sleep */
+
+#define IS_CAN_ITConfig(IT) (((IT) == CAN_IT_TME)   || ((IT) == CAN_IT_FMP0)  ||\
+                             ((IT) == CAN_IT_FF0)   || ((IT) == CAN_IT_FOV0)  ||\
+                             ((IT) == CAN_IT_FMP1)  || ((IT) == CAN_IT_FF1)   ||\
+                             ((IT) == CAN_IT_FOV1)  || ((IT) == CAN_IT_EWG)   ||\
+                             ((IT) == CAN_IT_EPV)   || ((IT) == CAN_IT_BOF)   ||\
+                             ((IT) == CAN_IT_LEC)   || ((IT) == CAN_IT_ERR)   ||\
+                             ((IT) == CAN_IT_WKU)   || ((IT) == CAN_IT_SLK))
+
+#define IS_CAN_ITStatus(IT) (((IT) == CAN_IT_RQCP0)  || ((IT) == CAN_IT_RQCP1)  ||\
+                             ((IT) == CAN_IT_RQCP2)  || ((IT) == CAN_IT_FF0)    ||\
+                             ((IT) == CAN_IT_FOV0)   || ((IT) == CAN_IT_FF1)    ||\
+                             ((IT) == CAN_IT_FOV1)   || ((IT) == CAN_IT_EWG)    ||\
+                             ((IT) == CAN_IT_EPV)    || ((IT) == CAN_IT_BOF)    ||\
+                             ((IT) == CAN_IT_WKU)    || ((IT) == CAN_IT_SLK))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Exported_Functions
+  * @{
+  */
+
+void CAN_DeInit(CAN_TypeDef* CANx);
+uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct);
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct);
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct);
+void CAN_SlaveStartBank(uint8_t CAN_BankNumber); 
+void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState);
+uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage);
+uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox);
+void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox);
+void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber);
+uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber);
+void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage);
+void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState);
+uint8_t CAN_Sleep(CAN_TypeDef* CANx);
+uint8_t CAN_WakeUp(CAN_TypeDef* CANx);
+FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG);
+void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG);
+ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT);
+void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_CAN_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h
new file mode 100644
index 0000000000000000000000000000000000000000..7dec6d0e058c22470e5970aa61bb484dd7f0be6d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h
@@ -0,0 +1,93 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_crc.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the CRC firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_CRC_H
+#define __STM32F10x_CRC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup CRC
+  * @{
+  */
+
+/** @defgroup CRC_Exported_Types
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Exported_Constants
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Exported_Functions
+  * @{
+  */
+
+void CRC_ResetDR(void);
+uint32_t CRC_CalcCRC(uint32_t Data);
+uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength);
+uint32_t CRC_GetCRC(void);
+void CRC_SetIDRegister(uint8_t IDValue);
+uint8_t CRC_GetIDRegister(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_CRC_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h
new file mode 100644
index 0000000000000000000000000000000000000000..11ecaca5066f27a794e6d088af71c5c421f684fc
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h
@@ -0,0 +1,282 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_dac.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the DAC firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DAC_H
+#define __STM32F10x_DAC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DAC
+  * @{
+  */
+
+/** @defgroup DAC_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  DAC Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t DAC_Trigger;                      /*!< Specifies the external trigger for the selected DAC channel.
+                                                  This parameter can be a value of @ref DAC_trigger_selection */
+
+  uint32_t DAC_WaveGeneration;               /*!< Specifies whether DAC channel noise waves or triangle waves
+                                                  are generated, or whether no wave is generated.
+                                                  This parameter can be a value of @ref DAC_wave_generation */
+
+  uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or
+                                                  the maximum amplitude triangle generation for the DAC channel. 
+                                                  This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */
+
+  uint32_t DAC_OutputBuffer;                 /*!< Specifies whether the DAC channel output buffer is enabled or disabled.
+                                                  This parameter can be a value of @ref DAC_output_buffer */
+}DAC_InitTypeDef;
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup DAC_trigger_selection 
+  * @{
+  */
+
+#define DAC_Trigger_None                   ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register 
+                                                                       has been loaded, and not by external trigger */
+#define DAC_Trigger_T6_TRGO                ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T8_TRGO                ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel
+                                                                       only in High-density devices*/
+#define DAC_Trigger_T3_TRGO                ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel
+                                                                       only in Connectivity line devices */
+#define DAC_Trigger_T7_TRGO                ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T5_TRGO                ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T2_TRGO                ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T4_TRGO                ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_Ext_IT9                ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_Software               ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */
+
+#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \
+                                 ((TRIGGER) == DAC_Trigger_T6_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T8_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T7_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T5_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T2_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T4_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_Ext_IT9) || \
+                                 ((TRIGGER) == DAC_Trigger_Software))
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_wave_generation 
+  * @{
+  */
+
+#define DAC_WaveGeneration_None            ((uint32_t)0x00000000)
+#define DAC_WaveGeneration_Noise           ((uint32_t)0x00000040)
+#define DAC_WaveGeneration_Triangle        ((uint32_t)0x00000080)
+#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \
+                                    ((WAVE) == DAC_WaveGeneration_Noise) || \
+                                    ((WAVE) == DAC_WaveGeneration_Triangle))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_lfsrunmask_triangleamplitude
+  * @{
+  */
+
+#define DAC_LFSRUnmask_Bit0                ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */
+#define DAC_LFSRUnmask_Bits1_0             ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits2_0             ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits3_0             ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits4_0             ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits5_0             ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits6_0             ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits7_0             ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits8_0             ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits9_0             ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits10_0            ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits11_0            ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */
+#define DAC_TriangleAmplitude_1            ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */
+#define DAC_TriangleAmplitude_3            ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */
+#define DAC_TriangleAmplitude_7            ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */
+#define DAC_TriangleAmplitude_15           ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */
+#define DAC_TriangleAmplitude_31           ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */
+#define DAC_TriangleAmplitude_63           ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */
+#define DAC_TriangleAmplitude_127          ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */
+#define DAC_TriangleAmplitude_255          ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */
+#define DAC_TriangleAmplitude_511          ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */
+#define DAC_TriangleAmplitude_1023         ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */
+#define DAC_TriangleAmplitude_2047         ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */
+#define DAC_TriangleAmplitude_4095         ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */
+
+#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_1) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_3) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_7) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_15) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_31) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_63) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_127) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_255) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_511) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_1023) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_2047) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_4095))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_output_buffer 
+  * @{
+  */
+
+#define DAC_OutputBuffer_Enable            ((uint32_t)0x00000000)
+#define DAC_OutputBuffer_Disable           ((uint32_t)0x00000002)
+#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \
+                                           ((STATE) == DAC_OutputBuffer_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Channel_selection 
+  * @{
+  */
+
+#define DAC_Channel_1                      ((uint32_t)0x00000000)
+#define DAC_Channel_2                      ((uint32_t)0x00000010)
+#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \
+                                 ((CHANNEL) == DAC_Channel_2))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_data_alignement 
+  * @{
+  */
+
+#define DAC_Align_12b_R                    ((uint32_t)0x00000000)
+#define DAC_Align_12b_L                    ((uint32_t)0x00000004)
+#define DAC_Align_8b_R                     ((uint32_t)0x00000008)
+#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \
+                             ((ALIGN) == DAC_Align_12b_L) || \
+                             ((ALIGN) == DAC_Align_8b_R))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_wave_generation 
+  * @{
+  */
+
+#define DAC_Wave_Noise                     ((uint32_t)0x00000040)
+#define DAC_Wave_Triangle                  ((uint32_t)0x00000080)
+#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \
+                           ((WAVE) == DAC_Wave_Triangle))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_data 
+  * @{
+  */
+
+#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) 
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Exported_Functions
+  * @{
+  */
+
+void DAC_DeInit(void);
+void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct);
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct);
+void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState);
+void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState);
+void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState);
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState);
+void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState);
+void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data);
+void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data);
+void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1);
+uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_DAC_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h
new file mode 100644
index 0000000000000000000000000000000000000000..be48ed9c391466b4e45a301c0a01d31061ce3e65
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h
@@ -0,0 +1,109 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_dbgmcu.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the DBGMCU 
+  *          firmware library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DBGMCU_H
+#define __STM32F10x_DBGMCU_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DBGMCU
+  * @{
+  */
+
+/** @defgroup DBGMCU_Exported_Types
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DBGMCU_Exported_Constants
+  * @{
+  */
+
+#define DBGMCU_SLEEP                 ((uint32_t)0x00000001)
+#define DBGMCU_STOP                  ((uint32_t)0x00000002)
+#define DBGMCU_STANDBY               ((uint32_t)0x00000004)
+#define DBGMCU_IWDG_STOP             ((uint32_t)0x00000100)
+#define DBGMCU_WWDG_STOP             ((uint32_t)0x00000200)
+#define DBGMCU_TIM1_STOP             ((uint32_t)0x00000400)
+#define DBGMCU_TIM2_STOP             ((uint32_t)0x00000800)
+#define DBGMCU_TIM3_STOP             ((uint32_t)0x00001000)
+#define DBGMCU_TIM4_STOP             ((uint32_t)0x00002000)
+#define DBGMCU_CAN1_STOP             ((uint32_t)0x00004000)
+#define DBGMCU_I2C1_SMBUS_TIMEOUT    ((uint32_t)0x00008000)
+#define DBGMCU_I2C2_SMBUS_TIMEOUT    ((uint32_t)0x00010000)
+#define DBGMCU_TIM8_STOP             ((uint32_t)0x00020000)
+#define DBGMCU_TIM5_STOP             ((uint32_t)0x00040000)
+#define DBGMCU_TIM6_STOP             ((uint32_t)0x00080000)
+#define DBGMCU_TIM7_STOP             ((uint32_t)0x00100000)
+#define DBGMCU_CAN2_STOP             ((uint32_t)0x00200000)
+
+#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFC000F8) == 0x00) && ((PERIPH) != 0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup DBGMCU_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DBGMCU_Exported_Functions
+  * @{
+  */
+
+uint32_t DBGMCU_GetREVID(void);
+uint32_t DBGMCU_GetDEVID(void);
+void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_DBGMCU_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h
new file mode 100644
index 0000000000000000000000000000000000000000..376f8a32e529d54a4df5fcb4e56bc0bc7936f703
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h
@@ -0,0 +1,437 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_dma.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the DMA firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_DMA_H
+#define __STM32F10x_DMA_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DMA
+  * @{
+  */
+
+/** @defgroup DMA_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  DMA Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */
+
+  uint32_t DMA_MemoryBaseAddr;     /*!< Specifies the memory base address for DMAy Channelx. */
+
+  uint32_t DMA_DIR;                /*!< Specifies if the peripheral is the source or destination.
+                                        This parameter can be a value of @ref DMA_data_transfer_direction */
+
+  uint32_t DMA_BufferSize;         /*!< Specifies the buffer size, in data unit, of the specified Channel. 
+                                        The data unit is equal to the configuration set in DMA_PeripheralDataSize
+                                        or DMA_MemoryDataSize members depending in the transfer direction. */
+
+  uint32_t DMA_PeripheralInc;      /*!< Specifies whether the Peripheral address register is incremented or not.
+                                        This parameter can be a value of @ref DMA_peripheral_incremented_mode */
+
+  uint32_t DMA_MemoryInc;          /*!< Specifies whether the memory address register is incremented or not.
+                                        This parameter can be a value of @ref DMA_memory_incremented_mode */
+
+  uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width.
+                                        This parameter can be a value of @ref DMA_peripheral_data_size */
+
+  uint32_t DMA_MemoryDataSize;     /*!< Specifies the Memory data width.
+                                        This parameter can be a value of @ref DMA_memory_data_size */
+
+  uint32_t DMA_Mode;               /*!< Specifies the operation mode of the DMAy Channelx.
+                                        This parameter can be a value of @ref DMA_circular_normal_mode.
+                                        @note: The circular buffer mode cannot be used if the memory-to-memory
+                                              data transfer is configured on the selected Channel */
+
+  uint32_t DMA_Priority;           /*!< Specifies the software priority for the DMAy Channelx.
+                                        This parameter can be a value of @ref DMA_priority_level */
+
+  uint32_t DMA_M2M;                /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer.
+                                        This parameter can be a value of @ref DMA_memory_to_memory */
+}DMA_InitTypeDef;
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Exported_Constants
+  * @{
+  */
+
+#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \
+                                   ((PERIPH) == DMA1_Channel2) || \
+                                   ((PERIPH) == DMA1_Channel3) || \
+                                   ((PERIPH) == DMA1_Channel4) || \
+                                   ((PERIPH) == DMA1_Channel5) || \
+                                   ((PERIPH) == DMA1_Channel6) || \
+                                   ((PERIPH) == DMA1_Channel7) || \
+                                   ((PERIPH) == DMA2_Channel1) || \
+                                   ((PERIPH) == DMA2_Channel2) || \
+                                   ((PERIPH) == DMA2_Channel3) || \
+                                   ((PERIPH) == DMA2_Channel4) || \
+                                   ((PERIPH) == DMA2_Channel5))
+
+/** @defgroup DMA_data_transfer_direction 
+  * @{
+  */
+
+#define DMA_DIR_PeripheralDST              ((uint32_t)0x00000010)
+#define DMA_DIR_PeripheralSRC              ((uint32_t)0x00000000)
+#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \
+                         ((DIR) == DMA_DIR_PeripheralSRC))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_peripheral_incremented_mode 
+  * @{
+  */
+
+#define DMA_PeripheralInc_Enable           ((uint32_t)0x00000040)
+#define DMA_PeripheralInc_Disable          ((uint32_t)0x00000000)
+#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \
+                                            ((STATE) == DMA_PeripheralInc_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_memory_incremented_mode 
+  * @{
+  */
+
+#define DMA_MemoryInc_Enable               ((uint32_t)0x00000080)
+#define DMA_MemoryInc_Disable              ((uint32_t)0x00000000)
+#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \
+                                        ((STATE) == DMA_MemoryInc_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_peripheral_data_size 
+  * @{
+  */
+
+#define DMA_PeripheralDataSize_Byte        ((uint32_t)0x00000000)
+#define DMA_PeripheralDataSize_HalfWord    ((uint32_t)0x00000100)
+#define DMA_PeripheralDataSize_Word        ((uint32_t)0x00000200)
+#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \
+                                           ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \
+                                           ((SIZE) == DMA_PeripheralDataSize_Word))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_memory_data_size 
+  * @{
+  */
+
+#define DMA_MemoryDataSize_Byte            ((uint32_t)0x00000000)
+#define DMA_MemoryDataSize_HalfWord        ((uint32_t)0x00000400)
+#define DMA_MemoryDataSize_Word            ((uint32_t)0x00000800)
+#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \
+                                       ((SIZE) == DMA_MemoryDataSize_HalfWord) || \
+                                       ((SIZE) == DMA_MemoryDataSize_Word))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_circular_normal_mode 
+  * @{
+  */
+
+#define DMA_Mode_Circular                  ((uint32_t)0x00000020)
+#define DMA_Mode_Normal                    ((uint32_t)0x00000000)
+#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_priority_level 
+  * @{
+  */
+
+#define DMA_Priority_VeryHigh              ((uint32_t)0x00003000)
+#define DMA_Priority_High                  ((uint32_t)0x00002000)
+#define DMA_Priority_Medium                ((uint32_t)0x00001000)
+#define DMA_Priority_Low                   ((uint32_t)0x00000000)
+#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \
+                                   ((PRIORITY) == DMA_Priority_High) || \
+                                   ((PRIORITY) == DMA_Priority_Medium) || \
+                                   ((PRIORITY) == DMA_Priority_Low))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_memory_to_memory 
+  * @{
+  */
+
+#define DMA_M2M_Enable                     ((uint32_t)0x00004000)
+#define DMA_M2M_Disable                    ((uint32_t)0x00000000)
+#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable))
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_interrupts_definition 
+  * @{
+  */
+
+#define DMA_IT_TC                          ((uint32_t)0x00000002)
+#define DMA_IT_HT                          ((uint32_t)0x00000004)
+#define DMA_IT_TE                          ((uint32_t)0x00000008)
+#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00))
+
+#define DMA1_IT_GL1                        ((uint32_t)0x00000001)
+#define DMA1_IT_TC1                        ((uint32_t)0x00000002)
+#define DMA1_IT_HT1                        ((uint32_t)0x00000004)
+#define DMA1_IT_TE1                        ((uint32_t)0x00000008)
+#define DMA1_IT_GL2                        ((uint32_t)0x00000010)
+#define DMA1_IT_TC2                        ((uint32_t)0x00000020)
+#define DMA1_IT_HT2                        ((uint32_t)0x00000040)
+#define DMA1_IT_TE2                        ((uint32_t)0x00000080)
+#define DMA1_IT_GL3                        ((uint32_t)0x00000100)
+#define DMA1_IT_TC3                        ((uint32_t)0x00000200)
+#define DMA1_IT_HT3                        ((uint32_t)0x00000400)
+#define DMA1_IT_TE3                        ((uint32_t)0x00000800)
+#define DMA1_IT_GL4                        ((uint32_t)0x00001000)
+#define DMA1_IT_TC4                        ((uint32_t)0x00002000)
+#define DMA1_IT_HT4                        ((uint32_t)0x00004000)
+#define DMA1_IT_TE4                        ((uint32_t)0x00008000)
+#define DMA1_IT_GL5                        ((uint32_t)0x00010000)
+#define DMA1_IT_TC5                        ((uint32_t)0x00020000)
+#define DMA1_IT_HT5                        ((uint32_t)0x00040000)
+#define DMA1_IT_TE5                        ((uint32_t)0x00080000)
+#define DMA1_IT_GL6                        ((uint32_t)0x00100000)
+#define DMA1_IT_TC6                        ((uint32_t)0x00200000)
+#define DMA1_IT_HT6                        ((uint32_t)0x00400000)
+#define DMA1_IT_TE6                        ((uint32_t)0x00800000)
+#define DMA1_IT_GL7                        ((uint32_t)0x01000000)
+#define DMA1_IT_TC7                        ((uint32_t)0x02000000)
+#define DMA1_IT_HT7                        ((uint32_t)0x04000000)
+#define DMA1_IT_TE7                        ((uint32_t)0x08000000)
+
+#define DMA2_IT_GL1                        ((uint32_t)0x10000001)
+#define DMA2_IT_TC1                        ((uint32_t)0x10000002)
+#define DMA2_IT_HT1                        ((uint32_t)0x10000004)
+#define DMA2_IT_TE1                        ((uint32_t)0x10000008)
+#define DMA2_IT_GL2                        ((uint32_t)0x10000010)
+#define DMA2_IT_TC2                        ((uint32_t)0x10000020)
+#define DMA2_IT_HT2                        ((uint32_t)0x10000040)
+#define DMA2_IT_TE2                        ((uint32_t)0x10000080)
+#define DMA2_IT_GL3                        ((uint32_t)0x10000100)
+#define DMA2_IT_TC3                        ((uint32_t)0x10000200)
+#define DMA2_IT_HT3                        ((uint32_t)0x10000400)
+#define DMA2_IT_TE3                        ((uint32_t)0x10000800)
+#define DMA2_IT_GL4                        ((uint32_t)0x10001000)
+#define DMA2_IT_TC4                        ((uint32_t)0x10002000)
+#define DMA2_IT_HT4                        ((uint32_t)0x10004000)
+#define DMA2_IT_TE4                        ((uint32_t)0x10008000)
+#define DMA2_IT_GL5                        ((uint32_t)0x10010000)
+#define DMA2_IT_TC5                        ((uint32_t)0x10020000)
+#define DMA2_IT_HT5                        ((uint32_t)0x10040000)
+#define DMA2_IT_TE5                        ((uint32_t)0x10080000)
+
+#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00))
+
+#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \
+                           ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \
+                           ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \
+                           ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \
+                           ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \
+                           ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \
+                           ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \
+                           ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \
+                           ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \
+                           ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \
+                           ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \
+                           ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \
+                           ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \
+                           ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \
+                           ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \
+                           ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \
+                           ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \
+                           ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \
+                           ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \
+                           ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \
+                           ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \
+                           ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \
+                           ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \
+                           ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5))
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_flags_definition 
+  * @{
+  */
+#define DMA1_FLAG_GL1                      ((uint32_t)0x00000001)
+#define DMA1_FLAG_TC1                      ((uint32_t)0x00000002)
+#define DMA1_FLAG_HT1                      ((uint32_t)0x00000004)
+#define DMA1_FLAG_TE1                      ((uint32_t)0x00000008)
+#define DMA1_FLAG_GL2                      ((uint32_t)0x00000010)
+#define DMA1_FLAG_TC2                      ((uint32_t)0x00000020)
+#define DMA1_FLAG_HT2                      ((uint32_t)0x00000040)
+#define DMA1_FLAG_TE2                      ((uint32_t)0x00000080)
+#define DMA1_FLAG_GL3                      ((uint32_t)0x00000100)
+#define DMA1_FLAG_TC3                      ((uint32_t)0x00000200)
+#define DMA1_FLAG_HT3                      ((uint32_t)0x00000400)
+#define DMA1_FLAG_TE3                      ((uint32_t)0x00000800)
+#define DMA1_FLAG_GL4                      ((uint32_t)0x00001000)
+#define DMA1_FLAG_TC4                      ((uint32_t)0x00002000)
+#define DMA1_FLAG_HT4                      ((uint32_t)0x00004000)
+#define DMA1_FLAG_TE4                      ((uint32_t)0x00008000)
+#define DMA1_FLAG_GL5                      ((uint32_t)0x00010000)
+#define DMA1_FLAG_TC5                      ((uint32_t)0x00020000)
+#define DMA1_FLAG_HT5                      ((uint32_t)0x00040000)
+#define DMA1_FLAG_TE5                      ((uint32_t)0x00080000)
+#define DMA1_FLAG_GL6                      ((uint32_t)0x00100000)
+#define DMA1_FLAG_TC6                      ((uint32_t)0x00200000)
+#define DMA1_FLAG_HT6                      ((uint32_t)0x00400000)
+#define DMA1_FLAG_TE6                      ((uint32_t)0x00800000)
+#define DMA1_FLAG_GL7                      ((uint32_t)0x01000000)
+#define DMA1_FLAG_TC7                      ((uint32_t)0x02000000)
+#define DMA1_FLAG_HT7                      ((uint32_t)0x04000000)
+#define DMA1_FLAG_TE7                      ((uint32_t)0x08000000)
+
+#define DMA2_FLAG_GL1                      ((uint32_t)0x10000001)
+#define DMA2_FLAG_TC1                      ((uint32_t)0x10000002)
+#define DMA2_FLAG_HT1                      ((uint32_t)0x10000004)
+#define DMA2_FLAG_TE1                      ((uint32_t)0x10000008)
+#define DMA2_FLAG_GL2                      ((uint32_t)0x10000010)
+#define DMA2_FLAG_TC2                      ((uint32_t)0x10000020)
+#define DMA2_FLAG_HT2                      ((uint32_t)0x10000040)
+#define DMA2_FLAG_TE2                      ((uint32_t)0x10000080)
+#define DMA2_FLAG_GL3                      ((uint32_t)0x10000100)
+#define DMA2_FLAG_TC3                      ((uint32_t)0x10000200)
+#define DMA2_FLAG_HT3                      ((uint32_t)0x10000400)
+#define DMA2_FLAG_TE3                      ((uint32_t)0x10000800)
+#define DMA2_FLAG_GL4                      ((uint32_t)0x10001000)
+#define DMA2_FLAG_TC4                      ((uint32_t)0x10002000)
+#define DMA2_FLAG_HT4                      ((uint32_t)0x10004000)
+#define DMA2_FLAG_TE4                      ((uint32_t)0x10008000)
+#define DMA2_FLAG_GL5                      ((uint32_t)0x10010000)
+#define DMA2_FLAG_TC5                      ((uint32_t)0x10020000)
+#define DMA2_FLAG_HT5                      ((uint32_t)0x10040000)
+#define DMA2_FLAG_TE5                      ((uint32_t)0x10080000)
+
+#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00))
+
+#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \
+                               ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \
+                               ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \
+                               ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \
+                               ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \
+                               ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \
+                               ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \
+                               ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \
+                               ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \
+                               ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \
+                               ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \
+                               ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \
+                               ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \
+                               ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \
+                               ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \
+                               ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \
+                               ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \
+                               ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \
+                               ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \
+                               ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \
+                               ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \
+                               ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \
+                               ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \
+                               ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5))
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Buffer_Size 
+  * @{
+  */
+
+#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000))
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Exported_Functions
+  * @{
+  */
+
+void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx);
+void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct);
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct);
+void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState);
+void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState);
+uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx);
+FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG);
+void DMA_ClearFlag(uint32_t DMA_FLAG);
+ITStatus DMA_GetITStatus(uint32_t DMA_IT);
+void DMA_ClearITPendingBit(uint32_t DMA_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_DMA_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h
new file mode 100644
index 0000000000000000000000000000000000000000..442a19e5fc3f231e7cd72769f7ab821bcbfe7a29
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h
@@ -0,0 +1,183 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_exti.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the EXTI firmware
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_EXTI_H
+#define __STM32F10x_EXTI_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup EXTI
+  * @{
+  */
+
+/** @defgroup EXTI_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  EXTI mode enumeration  
+  */
+
+typedef enum
+{
+  EXTI_Mode_Interrupt = 0x00,
+  EXTI_Mode_Event = 0x04
+}EXTIMode_TypeDef;
+
+#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event))
+
+/** 
+  * @brief  EXTI Trigger enumeration  
+  */
+
+typedef enum
+{
+  EXTI_Trigger_Rising = 0x08,
+  EXTI_Trigger_Falling = 0x0C,  
+  EXTI_Trigger_Rising_Falling = 0x10
+}EXTITrigger_TypeDef;
+
+#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \
+                                  ((TRIGGER) == EXTI_Trigger_Falling) || \
+                                  ((TRIGGER) == EXTI_Trigger_Rising_Falling))
+/** 
+  * @brief  EXTI Init Structure definition  
+  */
+
+typedef struct
+{
+  uint32_t EXTI_Line;               /*!< Specifies the EXTI lines to be enabled or disabled.
+                                         This parameter can be any combination of @ref EXTI_Lines */
+   
+  EXTIMode_TypeDef EXTI_Mode;       /*!< Specifies the mode for the EXTI lines.
+                                         This parameter can be a value of @ref EXTIMode_TypeDef */
+
+  EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines.
+                                         This parameter can be a value of @ref EXTIMode_TypeDef */
+
+  FunctionalState EXTI_LineCmd;     /*!< Specifies the new state of the selected EXTI lines.
+                                         This parameter can be set either to ENABLE or DISABLE */ 
+}EXTI_InitTypeDef;
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Exported_Constants
+  * @{
+  */
+
+/** @defgroup EXTI_Lines 
+  * @{
+  */
+
+#define EXTI_Line0       ((uint32_t)0x00001)  /*!< External interrupt line 0 */
+#define EXTI_Line1       ((uint32_t)0x00002)  /*!< External interrupt line 1 */
+#define EXTI_Line2       ((uint32_t)0x00004)  /*!< External interrupt line 2 */
+#define EXTI_Line3       ((uint32_t)0x00008)  /*!< External interrupt line 3 */
+#define EXTI_Line4       ((uint32_t)0x00010)  /*!< External interrupt line 4 */
+#define EXTI_Line5       ((uint32_t)0x00020)  /*!< External interrupt line 5 */
+#define EXTI_Line6       ((uint32_t)0x00040)  /*!< External interrupt line 6 */
+#define EXTI_Line7       ((uint32_t)0x00080)  /*!< External interrupt line 7 */
+#define EXTI_Line8       ((uint32_t)0x00100)  /*!< External interrupt line 8 */
+#define EXTI_Line9       ((uint32_t)0x00200)  /*!< External interrupt line 9 */
+#define EXTI_Line10      ((uint32_t)0x00400)  /*!< External interrupt line 10 */
+#define EXTI_Line11      ((uint32_t)0x00800)  /*!< External interrupt line 11 */
+#define EXTI_Line12      ((uint32_t)0x01000)  /*!< External interrupt line 12 */
+#define EXTI_Line13      ((uint32_t)0x02000)  /*!< External interrupt line 13 */
+#define EXTI_Line14      ((uint32_t)0x04000)  /*!< External interrupt line 14 */
+#define EXTI_Line15      ((uint32_t)0x08000)  /*!< External interrupt line 15 */
+#define EXTI_Line16      ((uint32_t)0x10000)  /*!< External interrupt line 16 Connected to the PVD Output */
+#define EXTI_Line17      ((uint32_t)0x20000)  /*!< External interrupt line 17 Connected to the RTC Alarm event */
+#define EXTI_Line18      ((uint32_t)0x40000)  /*!< External interrupt line 18 Connected to the USB Device/USB OTG FS
+                                                   Wakeup from suspend event */
+#define EXTI_Line19      ((uint32_t)0x80000)  /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ 
+                                            
+#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFFF00000) == 0x00) && ((LINE) != (uint16_t)0x00))
+
+#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \
+                            ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \
+                            ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \
+                            ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \
+                            ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \
+                            ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \
+                            ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \
+                            ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \
+                            ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \
+                            ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19))
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Exported_Functions
+  * @{
+  */
+
+void EXTI_DeInit(void);
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line);
+FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line);
+void EXTI_ClearFlag(uint32_t EXTI_Line);
+ITStatus EXTI_GetITStatus(uint32_t EXTI_Line);
+void EXTI_ClearITPendingBit(uint32_t EXTI_Line);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_EXTI_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h
new file mode 100644
index 0000000000000000000000000000000000000000..e2be14607a35d7e49045747e223b4961ae645c11
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h
@@ -0,0 +1,346 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_flash.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the FLASH 
+  *          firmware library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_FLASH_H
+#define __STM32F10x_FLASH_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup FLASH
+  * @{
+  */
+
+/** @defgroup FLASH_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  FLASH Status  
+  */
+
+typedef enum
+{ 
+  FLASH_BUSY = 1,
+  FLASH_ERROR_PG,
+  FLASH_ERROR_WRP,
+  FLASH_COMPLETE,
+  FLASH_TIMEOUT
+}FLASH_Status;
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Exported_Constants
+  * @{
+  */
+
+/** @defgroup Flash_Latency 
+  * @{
+  */
+
+#define FLASH_Latency_0                ((uint32_t)0x00000000)  /*!< FLASH Zero Latency cycle */
+#define FLASH_Latency_1                ((uint32_t)0x00000001)  /*!< FLASH One Latency cycle */
+#define FLASH_Latency_2                ((uint32_t)0x00000002)  /*!< FLASH Two Latency cycles */
+#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \
+                                   ((LATENCY) == FLASH_Latency_1) || \
+                                   ((LATENCY) == FLASH_Latency_2))
+/**
+  * @}
+  */
+
+/** @defgroup Half_Cycle_Enable_Disable 
+  * @{
+  */
+
+#define FLASH_HalfCycleAccess_Enable   ((uint32_t)0x00000008)  /*!< FLASH Half Cycle Enable */
+#define FLASH_HalfCycleAccess_Disable  ((uint32_t)0x00000000)  /*!< FLASH Half Cycle Disable */
+#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \
+                                               ((STATE) == FLASH_HalfCycleAccess_Disable)) 
+/**
+  * @}
+  */
+
+/** @defgroup Prefetch_Buffer_Enable_Disable 
+  * @{
+  */
+
+#define FLASH_PrefetchBuffer_Enable    ((uint32_t)0x00000010)  /*!< FLASH Prefetch Buffer Enable */
+#define FLASH_PrefetchBuffer_Disable   ((uint32_t)0x00000000)  /*!< FLASH Prefetch Buffer Disable */
+#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \
+                                              ((STATE) == FLASH_PrefetchBuffer_Disable)) 
+/**
+  * @}
+  */
+
+/** @defgroup Option_Bytes_Write_Protection 
+  * @{
+  */
+
+/* Values to be used with STM32 Low and Medium density devices */
+#define FLASH_WRProt_Pages0to3         ((uint32_t)0x00000001) /*!< STM32 Low and Medium density devices: Write protection of page 0 to 3 */
+#define FLASH_WRProt_Pages4to7         ((uint32_t)0x00000002) /*!< STM32 Low and Medium density devices: Write protection of page 4 to 7 */
+#define FLASH_WRProt_Pages8to11        ((uint32_t)0x00000004) /*!< STM32 Low and Medium density devices: Write protection of page 8 to 11 */
+#define FLASH_WRProt_Pages12to15       ((uint32_t)0x00000008) /*!< STM32 Low and Medium density devices: Write protection of page 12 to 15 */
+#define FLASH_WRProt_Pages16to19       ((uint32_t)0x00000010) /*!< STM32 Low and Medium density devices: Write protection of page 16 to 19 */
+#define FLASH_WRProt_Pages20to23       ((uint32_t)0x00000020) /*!< STM32 Low and Medium density devices: Write protection of page 20 to 23 */
+#define FLASH_WRProt_Pages24to27       ((uint32_t)0x00000040) /*!< STM32 Low and Medium density devices: Write protection of page 24 to 27 */
+#define FLASH_WRProt_Pages28to31       ((uint32_t)0x00000080) /*!< STM32 Low and Medium density devices: Write protection of page 28 to 31 */
+
+/* Values to be used with STM32 Medium-density devices */
+#define FLASH_WRProt_Pages32to35       ((uint32_t)0x00000100) /*!< STM32 Medium-density devices: Write protection of page 32 to 35 */
+#define FLASH_WRProt_Pages36to39       ((uint32_t)0x00000200) /*!< STM32 Medium-density devices: Write protection of page 36 to 39 */
+#define FLASH_WRProt_Pages40to43       ((uint32_t)0x00000400) /*!< STM32 Medium-density devices: Write protection of page 40 to 43 */
+#define FLASH_WRProt_Pages44to47       ((uint32_t)0x00000800) /*!< STM32 Medium-density devices: Write protection of page 44 to 47 */
+#define FLASH_WRProt_Pages48to51       ((uint32_t)0x00001000) /*!< STM32 Medium-density devices: Write protection of page 48 to 51 */
+#define FLASH_WRProt_Pages52to55       ((uint32_t)0x00002000) /*!< STM32 Medium-density devices: Write protection of page 52 to 55 */
+#define FLASH_WRProt_Pages56to59       ((uint32_t)0x00004000) /*!< STM32 Medium-density devices: Write protection of page 56 to 59 */
+#define FLASH_WRProt_Pages60to63       ((uint32_t)0x00008000) /*!< STM32 Medium-density devices: Write protection of page 60 to 63 */
+#define FLASH_WRProt_Pages64to67       ((uint32_t)0x00010000) /*!< STM32 Medium-density devices: Write protection of page 64 to 67 */
+#define FLASH_WRProt_Pages68to71       ((uint32_t)0x00020000) /*!< STM32 Medium-density devices: Write protection of page 68 to 71 */
+#define FLASH_WRProt_Pages72to75       ((uint32_t)0x00040000) /*!< STM32 Medium-density devices: Write protection of page 72 to 75 */
+#define FLASH_WRProt_Pages76to79       ((uint32_t)0x00080000) /*!< STM32 Medium-density devices: Write protection of page 76 to 79 */
+#define FLASH_WRProt_Pages80to83       ((uint32_t)0x00100000) /*!< STM32 Medium-density devices: Write protection of page 80 to 83 */
+#define FLASH_WRProt_Pages84to87       ((uint32_t)0x00200000) /*!< STM32 Medium-density devices: Write protection of page 84 to 87 */
+#define FLASH_WRProt_Pages88to91       ((uint32_t)0x00400000) /*!< STM32 Medium-density devices: Write protection of page 88 to 91 */
+#define FLASH_WRProt_Pages92to95       ((uint32_t)0x00800000) /*!< STM32 Medium-density devices: Write protection of page 92 to 95 */
+#define FLASH_WRProt_Pages96to99       ((uint32_t)0x01000000) /*!< STM32 Medium-density devices: Write protection of page 96 to 99 */
+#define FLASH_WRProt_Pages100to103     ((uint32_t)0x02000000) /*!< STM32 Medium-density devices: Write protection of page 100 to 103 */
+#define FLASH_WRProt_Pages104to107     ((uint32_t)0x04000000) /*!< STM32 Medium-density devices: Write protection of page 104 to 107 */
+#define FLASH_WRProt_Pages108to111     ((uint32_t)0x08000000) /*!< STM32 Medium-density devices: Write protection of page 108 to 111 */
+#define FLASH_WRProt_Pages112to115     ((uint32_t)0x10000000) /*!< STM32 Medium-density devices: Write protection of page 112 to 115 */
+#define FLASH_WRProt_Pages116to119     ((uint32_t)0x20000000) /*!< STM32 Medium-density devices: Write protection of page 115 to 119 */
+#define FLASH_WRProt_Pages120to123     ((uint32_t)0x40000000) /*!< STM32 Medium-density devices: Write protection of page 120 to 123 */
+#define FLASH_WRProt_Pages124to127     ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 124 to 127 */
+
+/* Values to be used with STM32 High-density and STM32F10X Connectivity line devices */
+#define FLASH_WRProt_Pages0to1         ((uint32_t)0x00000001) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 0 to 1 */
+#define FLASH_WRProt_Pages2to3         ((uint32_t)0x00000002) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 2 to 3 */
+#define FLASH_WRProt_Pages4to5         ((uint32_t)0x00000004) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 4 to 5 */
+#define FLASH_WRProt_Pages6to7         ((uint32_t)0x00000008) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 6 to 7 */
+#define FLASH_WRProt_Pages8to9         ((uint32_t)0x00000010) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 8 to 9 */
+#define FLASH_WRProt_Pages10to11       ((uint32_t)0x00000020) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 10 to 11 */
+#define FLASH_WRProt_Pages12to13       ((uint32_t)0x00000040) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 12 to 13 */
+#define FLASH_WRProt_Pages14to15       ((uint32_t)0x00000080) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 14 to 15 */
+#define FLASH_WRProt_Pages16to17       ((uint32_t)0x00000100) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 16 to 17 */
+#define FLASH_WRProt_Pages18to19       ((uint32_t)0x00000200) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 18 to 19 */
+#define FLASH_WRProt_Pages20to21       ((uint32_t)0x00000400) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 20 to 21 */
+#define FLASH_WRProt_Pages22to23       ((uint32_t)0x00000800) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 22 to 23 */
+#define FLASH_WRProt_Pages24to25       ((uint32_t)0x00001000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 24 to 25 */
+#define FLASH_WRProt_Pages26to27       ((uint32_t)0x00002000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 26 to 27 */
+#define FLASH_WRProt_Pages28to29       ((uint32_t)0x00004000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 28 to 29 */
+#define FLASH_WRProt_Pages30to31       ((uint32_t)0x00008000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 30 to 31 */
+#define FLASH_WRProt_Pages32to33       ((uint32_t)0x00010000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 32 to 33 */
+#define FLASH_WRProt_Pages34to35       ((uint32_t)0x00020000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 34 to 35 */
+#define FLASH_WRProt_Pages36to37       ((uint32_t)0x00040000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 36 to 37 */
+#define FLASH_WRProt_Pages38to39       ((uint32_t)0x00080000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 38 to 39 */
+#define FLASH_WRProt_Pages40to41       ((uint32_t)0x00100000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 40 to 41 */
+#define FLASH_WRProt_Pages42to43       ((uint32_t)0x00200000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 42 to 43 */
+#define FLASH_WRProt_Pages44to45       ((uint32_t)0x00400000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 44 to 45 */
+#define FLASH_WRProt_Pages46to47       ((uint32_t)0x00800000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 46 to 47 */
+#define FLASH_WRProt_Pages48to49       ((uint32_t)0x01000000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 48 to 49 */
+#define FLASH_WRProt_Pages50to51       ((uint32_t)0x02000000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 50 to 51 */
+#define FLASH_WRProt_Pages52to53       ((uint32_t)0x04000000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 52 to 53 */
+#define FLASH_WRProt_Pages54to55       ((uint32_t)0x08000000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 54 to 55 */
+#define FLASH_WRProt_Pages56to57       ((uint32_t)0x10000000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 56 to 57 */
+#define FLASH_WRProt_Pages58to59       ((uint32_t)0x20000000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 58 to 59 */
+#define FLASH_WRProt_Pages60to61       ((uint32_t)0x40000000) /*!< STM32 Medium-density and Connectivity line devices:
+                                                                   Write protection of page 60 to 61 */
+#define FLASH_WRProt_Pages62to127      ((uint32_t)0x80000000) /*!< STM32 Connectivity line devices: Write protection of page 62 to 127 */
+#define FLASH_WRProt_Pages62to255      ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 62 to 255 */
+
+#define FLASH_WRProt_AllPages          ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Pages */
+
+#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000))
+
+#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x0807FFFF))
+
+#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806))
+
+/**
+  * @}
+  */
+
+/** @defgroup Option_Bytes_IWatchdog 
+  * @{
+  */
+
+#define OB_IWDG_SW                     ((uint16_t)0x0001)  /*!< Software IWDG selected */
+#define OB_IWDG_HW                     ((uint16_t)0x0000)  /*!< Hardware IWDG selected */
+#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
+
+/**
+  * @}
+  */
+
+/** @defgroup Option_Bytes_nRST_STOP 
+  * @{
+  */
+
+#define OB_STOP_NoRST                  ((uint16_t)0x0002) /*!< No reset generated when entering in STOP */
+#define OB_STOP_RST                    ((uint16_t)0x0000) /*!< Reset generated when entering in STOP */
+#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST))
+
+/**
+  * @}
+  */
+
+/** @defgroup Option_Bytes_nRST_STDBY 
+  * @{
+  */
+
+#define OB_STDBY_NoRST                 ((uint16_t)0x0004) /*!< No reset generated when entering in STANDBY */
+#define OB_STDBY_RST                   ((uint16_t)0x0000) /*!< Reset generated when entering in STANDBY */
+#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Interrupts 
+  * @{
+  */
+
+#define FLASH_IT_ERROR                 ((uint32_t)0x00000400)  /*!< FPEC error interrupt source */
+#define FLASH_IT_EOP                   ((uint32_t)0x00001000)  /*!< End of FLASH Operation Interrupt source */
+#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000)))
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Flags 
+  * @{
+  */
+
+#define FLASH_FLAG_BSY                 ((uint32_t)0x00000001)  /*!< FLASH Busy flag */
+#define FLASH_FLAG_EOP                 ((uint32_t)0x00000020)  /*!< FLASH End of Operation flag */
+#define FLASH_FLAG_PGERR               ((uint32_t)0x00000004)  /*!< FLASH Program error flag */
+#define FLASH_FLAG_WRPRTERR            ((uint32_t)0x00000010)  /*!< FLASH Write protected error flag */
+#define FLASH_FLAG_OPTERR              ((uint32_t)0x00000001)  /*!< FLASH Option Byte error flag */
+ 
+#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000))
+#define IS_FLASH_GET_FLAG(FLAG)  (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \
+                                  ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \
+                                  ((FLAG) == FLASH_FLAG_OPTERR))
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Exported_Functions
+  * @{
+  */
+
+void FLASH_SetLatency(uint32_t FLASH_Latency);
+void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess);
+void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer);
+void FLASH_Unlock(void);
+void FLASH_Lock(void);
+FLASH_Status FLASH_ErasePage(uint32_t Page_Address);
+FLASH_Status FLASH_EraseAllPages(void);
+FLASH_Status FLASH_EraseOptionBytes(void);
+FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data);
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data);
+FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data);
+FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages);
+FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState);
+FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY);
+uint32_t FLASH_GetUserOptionByte(void);
+uint32_t FLASH_GetWriteProtectionOptionByte(void);
+FlagStatus FLASH_GetReadOutProtectionStatus(void);
+FlagStatus FLASH_GetPrefetchBufferStatus(void);
+void FLASH_ITConfig(uint16_t FLASH_IT, FunctionalState NewState);
+FlagStatus FLASH_GetFlagStatus(uint16_t FLASH_FLAG);
+void FLASH_ClearFlag(uint16_t FLASH_FLAG);
+FLASH_Status FLASH_GetStatus(void);
+FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_FLASH_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h
new file mode 100644
index 0000000000000000000000000000000000000000..ce22848513545d35080a70280eb2f2991d79d6c8
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h
@@ -0,0 +1,716 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_fsmc.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the FSMC firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_FSMC_H
+#define __STM32F10x_FSMC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup FSMC
+  * @{
+  */
+
+/** @defgroup FSMC_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  Timing parameters For NOR/SRAM Banks  
+  */
+
+typedef struct
+{
+  uint32_t FSMC_AddressSetupTime;       /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the address setup time. 
+                                             This parameter can be a value between 0 and 0xF.
+                                             @note: It is not used with synchronous NOR Flash memories. */
+
+  uint32_t FSMC_AddressHoldTime;        /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the address hold time.
+                                             This parameter can be a value between 0 and 0xF. 
+                                             @note: It is not used with synchronous NOR Flash memories.*/
+
+  uint32_t FSMC_DataSetupTime;          /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the data setup time.
+                                             This parameter can be a value between 0 and 0xFF.
+                                             @note: It is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */
+
+  uint32_t FSMC_BusTurnAroundDuration;  /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the bus turnaround.
+                                             This parameter can be a value between 0 and 0xF.
+                                             @note: It is only used for multiplexed NOR Flash memories. */
+
+  uint32_t FSMC_CLKDivision;            /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles.
+                                             This parameter can be a value between 1 and 0xF.
+                                             @note: This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */
+
+  uint32_t FSMC_DataLatency;            /*!< Defines the number of memory clock cycles to issue
+                                             to the memory before getting the first data.
+                                             The value of this parameter depends on the memory type as shown below:
+                                              - It must be set to 0 in case of a CRAM
+                                              - It is don’t care in asynchronous NOR, SRAM or ROM accesses
+                                              - It may assume a value between 0 and 0xF in NOR Flash memories
+                                                with synchronous burst mode enable */
+
+  uint32_t FSMC_AccessMode;             /*!< Specifies the asynchronous access mode. 
+                                             This parameter can be a value of @ref FSMC_Access_Mode */
+}FSMC_NORSRAMTimingInitTypeDef;
+
+/** 
+  * @brief  FSMC NOR/SRAM Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t FSMC_Bank;                /*!< Specifies the NOR/SRAM memory bank that will be used.
+                                          This parameter can be a value of @ref FSMC_NORSRAM_Bank */
+
+  uint32_t FSMC_DataAddressMux;      /*!< Specifies whether the address and data values are
+                                          multiplexed on the databus or not. 
+                                          This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */
+
+  uint32_t FSMC_MemoryType;          /*!< Specifies the type of external memory attached to
+                                          the corresponding memory bank.
+                                          This parameter can be a value of @ref FSMC_Memory_Type */
+
+  uint32_t FSMC_MemoryDataWidth;     /*!< Specifies the external memory device width.
+                                          This parameter can be a value of @ref FSMC_Data_Width */
+
+  uint32_t FSMC_BurstAccessMode;     /*!< Enables or disables the burst access mode for Flash memory,
+                                          valid only with synchronous burst Flash memories.
+                                          This parameter can be a value of @ref FSMC_Burst_Access_Mode */
+
+  uint32_t FSMC_WaitSignalPolarity;  /*!< Specifies the wait signal polarity, valid only when accessing
+                                          the Flash memory in burst mode.
+                                          This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */
+
+  uint32_t FSMC_WrapMode;            /*!< Enables or disables the Wrapped burst access mode for Flash
+                                          memory, valid only when accessing Flash memories in burst mode.
+                                          This parameter can be a value of @ref FSMC_Wrap_Mode */
+
+  uint32_t FSMC_WaitSignalActive;    /*!< Specifies if the wait signal is asserted by the memory one
+                                          clock cycle before the wait state or during the wait state,
+                                          valid only when accessing memories in burst mode. 
+                                          This parameter can be a value of @ref FSMC_Wait_Timing */
+
+  uint32_t FSMC_WriteOperation;      /*!< Enables or disables the write operation in the selected bank by the FSMC. 
+                                          This parameter can be a value of @ref FSMC_Write_Operation */
+
+  uint32_t FSMC_WaitSignal;          /*!< Enables or disables the wait-state insertion via wait
+                                          signal, valid for Flash memory access in burst mode. 
+                                          This parameter can be a value of @ref FSMC_Wait_Signal */
+
+  uint32_t FSMC_ExtendedMode;        /*!< Enables or disables the extended mode.
+                                          This parameter can be a value of @ref FSMC_Extended_Mode */
+
+  uint32_t FSMC_WriteBurst;          /*!< Enables or disables the write burst operation.
+                                          This parameter can be a value of @ref FSMC_Write_Burst */ 
+
+  FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the  ExtendedMode is not used*/  
+
+  FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct;     /*!< Timing Parameters for write access if the  ExtendedMode is used*/      
+}FSMC_NORSRAMInitTypeDef;
+
+/** 
+  * @brief  Timing parameters For FSMC NAND and PCCARD Banks
+  */
+
+typedef struct
+{
+  uint32_t FSMC_SetupTime;      /*!< Defines the number of HCLK cycles to setup address before
+                                     the command assertion for NAND-Flash read or write access
+                                     to common/Attribute or I/O memory space (depending on
+                                     the memory space timing to be configured).
+                                     This parameter can be a value between 0 and 0xFF.*/
+
+  uint32_t FSMC_WaitSetupTime;  /*!< Defines the minimum number of HCLK cycles to assert the
+                                     command for NAND-Flash read or write access to
+                                     common/Attribute or I/O memory space (depending on the
+                                     memory space timing to be configured). 
+                                     This parameter can be a number between 0x00 and 0xFF */
+
+  uint32_t FSMC_HoldSetupTime;  /*!< Defines the number of HCLK clock cycles to hold address
+                                     (and data for write access) after the command deassertion
+                                     for NAND-Flash read or write access to common/Attribute
+                                     or I/O memory space (depending on the memory space timing
+                                     to be configured).
+                                     This parameter can be a number between 0x00 and 0xFF */
+
+  uint32_t FSMC_HiZSetupTime;   /*!< Defines the number of HCLK clock cycles during which the
+                                     databus is kept in HiZ after the start of a NAND-Flash
+                                     write access to common/Attribute or I/O memory space (depending
+                                     on the memory space timing to be configured).
+                                     This parameter can be a number between 0x00 and 0xFF */
+}FSMC_NAND_PCCARDTimingInitTypeDef;
+
+/** 
+  * @brief  FSMC NAND Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t FSMC_Bank;              /*!< Specifies the NAND memory bank that will be used.
+                                      This parameter can be a value of @ref FSMC_NAND_Bank */
+
+  uint32_t FSMC_Waitfeature;      /*!< Enables or disables the Wait feature for the NAND Memory Bank.
+                                       This parameter can be any value of @ref FSMC_Wait_feature */
+
+  uint32_t FSMC_MemoryDataWidth;  /*!< Specifies the external memory device width.
+                                       This parameter can be any value of @ref FSMC_Data_Width */
+
+  uint32_t FSMC_ECC;              /*!< Enables or disables the ECC computation.
+                                       This parameter can be any value of @ref FSMC_ECC */
+
+  uint32_t FSMC_ECCPageSize;      /*!< Defines the page size for the extended ECC.
+                                       This parameter can be any value of @ref FSMC_ECC_Page_Size */
+
+  uint32_t FSMC_TCLRSetupTime;    /*!< Defines the number of HCLK cycles to configure the
+                                       delay between CLE low and RE low.
+                                       This parameter can be a value between 0 and 0xFF. */
+
+  uint32_t FSMC_TARSetupTime;     /*!< Defines the number of HCLK cycles to configure the
+                                       delay between ALE low and RE low.
+                                       This parameter can be a number between 0x0 and 0xFF */ 
+
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_CommonSpaceTimingStruct;   /*!< FSMC Common Space Timing */ 
+
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */
+}FSMC_NANDInitTypeDef;
+
+/** 
+  * @brief  FSMC PCCARD Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t FSMC_Waitfeature;    /*!< Enables or disables the Wait feature for the Memory Bank.
+                                    This parameter can be any value of @ref FSMC_Wait_feature */
+
+  uint32_t FSMC_TCLRSetupTime;  /*!< Defines the number of HCLK cycles to configure the
+                                     delay between CLE low and RE low.
+                                     This parameter can be a value between 0 and 0xFF. */
+
+  uint32_t FSMC_TARSetupTime;   /*!< Defines the number of HCLK cycles to configure the
+                                     delay between ALE low and RE low.
+                                     This parameter can be a number between 0x0 and 0xFF */ 
+
+  
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */
+
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_AttributeSpaceTimingStruct;  /*!< FSMC Attribute Space Timing */ 
+  
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */  
+}FSMC_PCCARDInitTypeDef;
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup FSMC_NORSRAM_Bank 
+  * @{
+  */
+#define FSMC_Bank1_NORSRAM1                             ((uint32_t)0x00000000)
+#define FSMC_Bank1_NORSRAM2                             ((uint32_t)0x00000002)
+#define FSMC_Bank1_NORSRAM3                             ((uint32_t)0x00000004)
+#define FSMC_Bank1_NORSRAM4                             ((uint32_t)0x00000006)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_NAND_Bank 
+  * @{
+  */  
+#define FSMC_Bank2_NAND                                 ((uint32_t)0x00000010)
+#define FSMC_Bank3_NAND                                 ((uint32_t)0x00000100)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_PCCARD_Bank 
+  * @{
+  */    
+#define FSMC_Bank4_PCCARD                               ((uint32_t)0x00001000)
+/**
+  * @}
+  */
+
+#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \
+                                    ((BANK) == FSMC_Bank1_NORSRAM2) || \
+                                    ((BANK) == FSMC_Bank1_NORSRAM3) || \
+                                    ((BANK) == FSMC_Bank1_NORSRAM4))
+
+#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+                                 ((BANK) == FSMC_Bank3_NAND))
+
+#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+                                    ((BANK) == FSMC_Bank3_NAND) || \
+                                    ((BANK) == FSMC_Bank4_PCCARD))
+
+#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+                               ((BANK) == FSMC_Bank3_NAND) || \
+                               ((BANK) == FSMC_Bank4_PCCARD))
+
+/** @defgroup NOR_SRAM_Controller 
+  * @{
+  */
+
+/** @defgroup FSMC_Data_Address_Bus_Multiplexing 
+  * @{
+  */
+
+#define FSMC_DataAddressMux_Disable                       ((uint32_t)0x00000000)
+#define FSMC_DataAddressMux_Enable                        ((uint32_t)0x00000002)
+#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \
+                          ((MUX) == FSMC_DataAddressMux_Enable))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Memory_Type 
+  * @{
+  */
+
+#define FSMC_MemoryType_SRAM                            ((uint32_t)0x00000000)
+#define FSMC_MemoryType_PSRAM                           ((uint32_t)0x00000004)
+#define FSMC_MemoryType_NOR                             ((uint32_t)0x00000008)
+#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \
+                                ((MEMORY) == FSMC_MemoryType_PSRAM)|| \
+                                ((MEMORY) == FSMC_MemoryType_NOR))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Data_Width 
+  * @{
+  */
+
+#define FSMC_MemoryDataWidth_8b                         ((uint32_t)0x00000000)
+#define FSMC_MemoryDataWidth_16b                        ((uint32_t)0x00000010)
+#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \
+                                     ((WIDTH) == FSMC_MemoryDataWidth_16b))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Burst_Access_Mode 
+  * @{
+  */
+
+#define FSMC_BurstAccessMode_Disable                    ((uint32_t)0x00000000) 
+#define FSMC_BurstAccessMode_Enable                     ((uint32_t)0x00000100)
+#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \
+                                  ((STATE) == FSMC_BurstAccessMode_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Signal_Polarity 
+  * @{
+  */
+
+#define FSMC_WaitSignalPolarity_Low                     ((uint32_t)0x00000000)
+#define FSMC_WaitSignalPolarity_High                    ((uint32_t)0x00000200)
+#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \
+                                         ((POLARITY) == FSMC_WaitSignalPolarity_High)) 
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wrap_Mode 
+  * @{
+  */
+
+#define FSMC_WrapMode_Disable                           ((uint32_t)0x00000000)
+#define FSMC_WrapMode_Enable                            ((uint32_t)0x00000400) 
+#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \
+                                 ((MODE) == FSMC_WrapMode_Enable))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Timing 
+  * @{
+  */
+
+#define FSMC_WaitSignalActive_BeforeWaitState           ((uint32_t)0x00000000)
+#define FSMC_WaitSignalActive_DuringWaitState           ((uint32_t)0x00000800) 
+#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \
+                                            ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Write_Operation 
+  * @{
+  */
+
+#define FSMC_WriteOperation_Disable                     ((uint32_t)0x00000000)
+#define FSMC_WriteOperation_Enable                      ((uint32_t)0x00001000)
+#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \
+                                            ((OPERATION) == FSMC_WriteOperation_Enable))
+                              
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Signal 
+  * @{
+  */
+
+#define FSMC_WaitSignal_Disable                         ((uint32_t)0x00000000)
+#define FSMC_WaitSignal_Enable                          ((uint32_t)0x00002000) 
+#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \
+                                      ((SIGNAL) == FSMC_WaitSignal_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Extended_Mode 
+  * @{
+  */
+
+#define FSMC_ExtendedMode_Disable                       ((uint32_t)0x00000000)
+#define FSMC_ExtendedMode_Enable                        ((uint32_t)0x00004000)
+
+#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \
+                                     ((MODE) == FSMC_ExtendedMode_Enable)) 
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Write_Burst 
+  * @{
+  */
+
+#define FSMC_WriteBurst_Disable                         ((uint32_t)0x00000000)
+#define FSMC_WriteBurst_Enable                          ((uint32_t)0x00080000) 
+#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \
+                                    ((BURST) == FSMC_WriteBurst_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Address_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Address_Hold_Time 
+  * @{
+  */
+
+#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Data_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Bus_Turn_around_Duration 
+  * @{
+  */
+
+#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_CLK_Division 
+  * @{
+  */
+
+#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Data_Latency 
+  * @{
+  */
+
+#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Access_Mode 
+  * @{
+  */
+
+#define FSMC_AccessMode_A                               ((uint32_t)0x00000000)
+#define FSMC_AccessMode_B                               ((uint32_t)0x10000000) 
+#define FSMC_AccessMode_C                               ((uint32_t)0x20000000)
+#define FSMC_AccessMode_D                               ((uint32_t)0x30000000)
+#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \
+                                   ((MODE) == FSMC_AccessMode_B) || \
+                                   ((MODE) == FSMC_AccessMode_C) || \
+                                   ((MODE) == FSMC_AccessMode_D)) 
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+  
+/** @defgroup NAND_PCCARD_Controller 
+  * @{
+  */
+
+/** @defgroup FSMC_Wait_feature 
+  * @{
+  */
+
+#define FSMC_Waitfeature_Disable                        ((uint32_t)0x00000000)
+#define FSMC_Waitfeature_Enable                         ((uint32_t)0x00000002)
+#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \
+                                       ((FEATURE) == FSMC_Waitfeature_Enable))
+
+/**
+  * @}
+  */
+
+
+/** @defgroup FSMC_ECC 
+  * @{
+  */
+
+#define FSMC_ECC_Disable                                ((uint32_t)0x00000000)
+#define FSMC_ECC_Enable                                 ((uint32_t)0x00000040)
+#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \
+                                  ((STATE) == FSMC_ECC_Enable))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_ECC_Page_Size 
+  * @{
+  */
+
+#define FSMC_ECCPageSize_256Bytes                       ((uint32_t)0x00000000)
+#define FSMC_ECCPageSize_512Bytes                       ((uint32_t)0x00020000)
+#define FSMC_ECCPageSize_1024Bytes                      ((uint32_t)0x00040000)
+#define FSMC_ECCPageSize_2048Bytes                      ((uint32_t)0x00060000)
+#define FSMC_ECCPageSize_4096Bytes                      ((uint32_t)0x00080000)
+#define FSMC_ECCPageSize_8192Bytes                      ((uint32_t)0x000A0000)
+#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_512Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_8192Bytes))
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_TCLR_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_TAR_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Hold_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_HiZ_Setup_Time 
+  * @{
+  */
+
+#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Interrupt_sources 
+  * @{
+  */
+
+#define FSMC_IT_RisingEdge                              ((uint32_t)0x00000008)
+#define FSMC_IT_Level                                   ((uint32_t)0x00000010)
+#define FSMC_IT_FallingEdge                             ((uint32_t)0x00000020)
+#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000))
+#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \
+                            ((IT) == FSMC_IT_Level) || \
+                            ((IT) == FSMC_IT_FallingEdge)) 
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Flags 
+  * @{
+  */
+
+#define FSMC_FLAG_RisingEdge                            ((uint32_t)0x00000001)
+#define FSMC_FLAG_Level                                 ((uint32_t)0x00000002)
+#define FSMC_FLAG_FallingEdge                           ((uint32_t)0x00000004)
+#define FSMC_FLAG_FEMPT                                 ((uint32_t)0x00000040)
+#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \
+                                ((FLAG) == FSMC_FLAG_Level) || \
+                                ((FLAG) == FSMC_FLAG_FallingEdge) || \
+                                ((FLAG) == FSMC_FLAG_FEMPT))
+
+#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000))
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Exported_Functions
+  * @{
+  */
+
+void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank);
+void FSMC_NANDDeInit(uint32_t FSMC_Bank);
+void FSMC_PCCARDDeInit(void);
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState);
+void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState);
+void FSMC_PCCARDCmd(FunctionalState NewState);
+void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState);
+uint32_t FSMC_GetECC(uint32_t FSMC_Bank);
+void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState);
+FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG);
+void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG);
+ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT);
+void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_FSMC_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h
new file mode 100644
index 0000000000000000000000000000000000000000..127d07550aa804a41f9fd4967e614f7cf382bd92
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h
@@ -0,0 +1,359 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_gpio.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the GPIO 
+  *          firmware library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_GPIO_H
+#define __STM32F10x_GPIO_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup GPIO
+  * @{
+  */
+
+/** @defgroup GPIO_Exported_Types
+  * @{
+  */
+
+#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \
+                                    ((PERIPH) == GPIOB) || \
+                                    ((PERIPH) == GPIOC) || \
+                                    ((PERIPH) == GPIOD) || \
+                                    ((PERIPH) == GPIOE) || \
+                                    ((PERIPH) == GPIOF) || \
+                                    ((PERIPH) == GPIOG))
+                                     
+/** 
+  * @brief  Output Maximum frequency selection  
+  */
+
+typedef enum
+{ 
+  GPIO_Speed_10MHz = 1,
+  GPIO_Speed_2MHz, 
+  GPIO_Speed_50MHz
+}GPIOSpeed_TypeDef;
+#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \
+                              ((SPEED) == GPIO_Speed_50MHz))
+
+/** 
+  * @brief  Configuration Mode enumeration  
+  */
+
+typedef enum
+{ GPIO_Mode_AIN = 0x0,
+  GPIO_Mode_IN_FLOATING = 0x04,
+  GPIO_Mode_IPD = 0x28,
+  GPIO_Mode_IPU = 0x48,
+  GPIO_Mode_Out_OD = 0x14,
+  GPIO_Mode_Out_PP = 0x10,
+  GPIO_Mode_AF_OD = 0x1C,
+  GPIO_Mode_AF_PP = 0x18
+}GPIOMode_TypeDef;
+
+#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \
+                            ((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \
+                            ((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \
+                            ((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP))
+
+/** 
+  * @brief  GPIO Init structure definition  
+  */
+
+typedef struct
+{
+  uint16_t GPIO_Pin;             /*!< Specifies the GPIO pins to be configured.
+                                      This parameter can be any value of @ref GPIO_pins_define */
+
+  GPIOSpeed_TypeDef GPIO_Speed;  /*!< Specifies the speed for the selected pins.
+                                      This parameter can be a value of @ref GPIOSpeed_TypeDef */
+
+  GPIOMode_TypeDef GPIO_Mode;    /*!< Specifies the operating mode for the selected pins.
+                                      This parameter can be a value of @ref GPIOMode_TypeDef */
+}GPIO_InitTypeDef;
+
+
+/** 
+  * @brief  Bit_SET and Bit_RESET enumeration  
+  */
+
+typedef enum
+{ Bit_RESET = 0,
+  Bit_SET
+}BitAction;
+
+#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET))
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Exported_Constants
+  * @{
+  */
+
+/** @defgroup GPIO_pins_define 
+  * @{
+  */
+
+#define GPIO_Pin_0                 ((uint16_t)0x0001)  /*!< Pin 0 selected */
+#define GPIO_Pin_1                 ((uint16_t)0x0002)  /*!< Pin 1 selected */
+#define GPIO_Pin_2                 ((uint16_t)0x0004)  /*!< Pin 2 selected */
+#define GPIO_Pin_3                 ((uint16_t)0x0008)  /*!< Pin 3 selected */
+#define GPIO_Pin_4                 ((uint16_t)0x0010)  /*!< Pin 4 selected */
+#define GPIO_Pin_5                 ((uint16_t)0x0020)  /*!< Pin 5 selected */
+#define GPIO_Pin_6                 ((uint16_t)0x0040)  /*!< Pin 6 selected */
+#define GPIO_Pin_7                 ((uint16_t)0x0080)  /*!< Pin 7 selected */
+#define GPIO_Pin_8                 ((uint16_t)0x0100)  /*!< Pin 8 selected */
+#define GPIO_Pin_9                 ((uint16_t)0x0200)  /*!< Pin 9 selected */
+#define GPIO_Pin_10                ((uint16_t)0x0400)  /*!< Pin 10 selected */
+#define GPIO_Pin_11                ((uint16_t)0x0800)  /*!< Pin 11 selected */
+#define GPIO_Pin_12                ((uint16_t)0x1000)  /*!< Pin 12 selected */
+#define GPIO_Pin_13                ((uint16_t)0x2000)  /*!< Pin 13 selected */
+#define GPIO_Pin_14                ((uint16_t)0x4000)  /*!< Pin 14 selected */
+#define GPIO_Pin_15                ((uint16_t)0x8000)  /*!< Pin 15 selected */
+#define GPIO_Pin_All               ((uint16_t)0xFFFF)  /*!< All pins selected */
+
+#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00))
+
+#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \
+                              ((PIN) == GPIO_Pin_1) || \
+                              ((PIN) == GPIO_Pin_2) || \
+                              ((PIN) == GPIO_Pin_3) || \
+                              ((PIN) == GPIO_Pin_4) || \
+                              ((PIN) == GPIO_Pin_5) || \
+                              ((PIN) == GPIO_Pin_6) || \
+                              ((PIN) == GPIO_Pin_7) || \
+                              ((PIN) == GPIO_Pin_8) || \
+                              ((PIN) == GPIO_Pin_9) || \
+                              ((PIN) == GPIO_Pin_10) || \
+                              ((PIN) == GPIO_Pin_11) || \
+                              ((PIN) == GPIO_Pin_12) || \
+                              ((PIN) == GPIO_Pin_13) || \
+                              ((PIN) == GPIO_Pin_14) || \
+                              ((PIN) == GPIO_Pin_15))
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Remap_define 
+  * @{
+  */
+
+#define GPIO_Remap_SPI1             ((uint32_t)0x00000001)  /*!< SPI1 Alternate Function mapping */
+#define GPIO_Remap_I2C1             ((uint32_t)0x00000002)  /*!< I2C1 Alternate Function mapping */
+#define GPIO_Remap_USART1           ((uint32_t)0x00000004)  /*!< USART1 Alternate Function mapping */
+#define GPIO_Remap_USART2           ((uint32_t)0x00000008)  /*!< USART2 Alternate Function mapping */
+#define GPIO_PartialRemap_USART3    ((uint32_t)0x00140010)  /*!< USART3 Partial Alternate Function mapping */
+#define GPIO_FullRemap_USART3       ((uint32_t)0x00140030)  /*!< USART3 Full Alternate Function mapping */
+#define GPIO_PartialRemap_TIM1      ((uint32_t)0x00160040)  /*!< TIM1 Partial Alternate Function mapping */
+#define GPIO_FullRemap_TIM1         ((uint32_t)0x001600C0)  /*!< TIM1 Full Alternate Function mapping */
+#define GPIO_PartialRemap1_TIM2     ((uint32_t)0x00180100)  /*!< TIM2 Partial1 Alternate Function mapping */
+#define GPIO_PartialRemap2_TIM2     ((uint32_t)0x00180200)  /*!< TIM2 Partial2 Alternate Function mapping */
+#define GPIO_FullRemap_TIM2         ((uint32_t)0x00180300)  /*!< TIM2 Full Alternate Function mapping */
+#define GPIO_PartialRemap_TIM3      ((uint32_t)0x001A0800)  /*!< TIM3 Partial Alternate Function mapping */
+#define GPIO_FullRemap_TIM3         ((uint32_t)0x001A0C00)  /*!< TIM3 Full Alternate Function mapping */
+#define GPIO_Remap_TIM4             ((uint32_t)0x00001000)  /*!< TIM4 Alternate Function mapping */
+#define GPIO_Remap1_CAN1            ((uint32_t)0x001D4000)  /*!< CAN1 Alternate Function mapping */
+#define GPIO_Remap2_CAN1            ((uint32_t)0x001D6000)  /*!< CAN1 Alternate Function mapping */
+#define GPIO_Remap_PD01             ((uint32_t)0x00008000)  /*!< PD01 Alternate Function mapping */
+#define GPIO_Remap_TIM5CH4_LSI      ((uint32_t)0x00200001)  /*!< LSI connected to TIM5 Channel4 input capture for calibration */
+#define GPIO_Remap_ADC1_ETRGINJ     ((uint32_t)0x00200002)  /*!< ADC1 External Trigger Injected Conversion remapping */
+#define GPIO_Remap_ADC1_ETRGREG     ((uint32_t)0x00200004)  /*!< ADC1 External Trigger Regular Conversion remapping */
+#define GPIO_Remap_ADC2_ETRGINJ     ((uint32_t)0x00200008)  /*!< ADC2 External Trigger Injected Conversion remapping */
+#define GPIO_Remap_ADC2_ETRGREG     ((uint32_t)0x00200010)  /*!< ADC2 External Trigger Regular Conversion remapping */
+#define GPIO_Remap_ETH              ((uint32_t)0x00200020)  /*!< Ethernet remapping (only for Connectivity line devices) */
+#define GPIO_Remap_CAN2             ((uint32_t)0x00200040)  /*!< CAN2 remapping (only for Connectivity line devices) */
+#define GPIO_Remap_SWJ_NoJTRST      ((uint32_t)0x00300100)  /*!< Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */
+#define GPIO_Remap_SWJ_JTAGDisable  ((uint32_t)0x00300200)  /*!< JTAG-DP Disabled and SW-DP Enabled */
+#define GPIO_Remap_SWJ_Disable      ((uint32_t)0x00300400)  /*!< Full SWJ Disabled (JTAG-DP + SW-DP) */
+#define GPIO_Remap_SPI3             ((uint32_t)0x00201000)  /*!< SPI3 Alternate Function mapping (only for Connectivity line devices) */
+#define GPIO_Remap_TIM2ITR1_PTP_SOF ((uint32_t)0x00202000)  /*!< Ethernet PTP output or USB OTG SOF (Start of Frame) connected
+                                                                 to TIM2 Internal Trigger 1 for calibration
+                                                                 (only for Connectivity line devices) */
+#define GPIO_Remap_PTP_PPS          ((uint32_t)0x00204000)  /*!< Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) */                                                       
+
+#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \
+                              ((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \
+                              ((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \
+                              ((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \
+                              ((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \
+                              ((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \
+                              ((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \
+                              ((REMAP) == GPIO_Remap1_CAN1) || ((REMAP) == GPIO_Remap2_CAN1) || \
+                              ((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \
+                              ((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \
+                              ((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \
+                              ((REMAP) == GPIO_Remap_ETH) ||((REMAP) == GPIO_Remap_CAN2) || \
+                              ((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable) || \
+                              ((REMAP) == GPIO_Remap_SWJ_Disable)|| ((REMAP) == GPIO_Remap_SPI3) || \
+                              ((REMAP) == GPIO_Remap_TIM2ITR1_PTP_SOF) || ((REMAP) == GPIO_Remap_PTP_PPS))
+                              
+/**
+  * @}
+  */ 
+
+/** @defgroup GPIO_Port_Sources 
+  * @{
+  */
+
+#define GPIO_PortSourceGPIOA       ((uint8_t)0x00)
+#define GPIO_PortSourceGPIOB       ((uint8_t)0x01)
+#define GPIO_PortSourceGPIOC       ((uint8_t)0x02)
+#define GPIO_PortSourceGPIOD       ((uint8_t)0x03)
+#define GPIO_PortSourceGPIOE       ((uint8_t)0x04)
+#define GPIO_PortSourceGPIOF       ((uint8_t)0x05)
+#define GPIO_PortSourceGPIOG       ((uint8_t)0x06)
+#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
+                                                  ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
+                                                  ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
+                                                  ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
+                                                  ((PORTSOURCE) == GPIO_PortSourceGPIOE))
+
+#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \
+                                              ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \
+                                              ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \
+                                              ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \
+                                              ((PORTSOURCE) == GPIO_PortSourceGPIOE) || \
+                                              ((PORTSOURCE) == GPIO_PortSourceGPIOF) || \
+                                              ((PORTSOURCE) == GPIO_PortSourceGPIOG))
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Pin_sources 
+  * @{
+  */
+
+#define GPIO_PinSource0            ((uint8_t)0x00)
+#define GPIO_PinSource1            ((uint8_t)0x01)
+#define GPIO_PinSource2            ((uint8_t)0x02)
+#define GPIO_PinSource3            ((uint8_t)0x03)
+#define GPIO_PinSource4            ((uint8_t)0x04)
+#define GPIO_PinSource5            ((uint8_t)0x05)
+#define GPIO_PinSource6            ((uint8_t)0x06)
+#define GPIO_PinSource7            ((uint8_t)0x07)
+#define GPIO_PinSource8            ((uint8_t)0x08)
+#define GPIO_PinSource9            ((uint8_t)0x09)
+#define GPIO_PinSource10           ((uint8_t)0x0A)
+#define GPIO_PinSource11           ((uint8_t)0x0B)
+#define GPIO_PinSource12           ((uint8_t)0x0C)
+#define GPIO_PinSource13           ((uint8_t)0x0D)
+#define GPIO_PinSource14           ((uint8_t)0x0E)
+#define GPIO_PinSource15           ((uint8_t)0x0F)
+
+#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \
+                                       ((PINSOURCE) == GPIO_PinSource1) || \
+                                       ((PINSOURCE) == GPIO_PinSource2) || \
+                                       ((PINSOURCE) == GPIO_PinSource3) || \
+                                       ((PINSOURCE) == GPIO_PinSource4) || \
+                                       ((PINSOURCE) == GPIO_PinSource5) || \
+                                       ((PINSOURCE) == GPIO_PinSource6) || \
+                                       ((PINSOURCE) == GPIO_PinSource7) || \
+                                       ((PINSOURCE) == GPIO_PinSource8) || \
+                                       ((PINSOURCE) == GPIO_PinSource9) || \
+                                       ((PINSOURCE) == GPIO_PinSource10) || \
+                                       ((PINSOURCE) == GPIO_PinSource11) || \
+                                       ((PINSOURCE) == GPIO_PinSource12) || \
+                                       ((PINSOURCE) == GPIO_PinSource13) || \
+                                       ((PINSOURCE) == GPIO_PinSource14) || \
+                                       ((PINSOURCE) == GPIO_PinSource15))
+
+/**
+  * @}
+  */
+
+/** @defgroup Ethernet_Media_Interface 
+  * @{
+  */ 
+#define GPIO_ETH_MediaInterface_MII    ((uint32_t)0x00000000) 
+#define GPIO_ETH_MediaInterface_RMII   ((uint32_t)0x00000001)                                       
+
+#define IS_GPIO_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == GPIO_ETH_MediaInterface_MII) || \
+                                                ((INTERFACE) == GPIO_ETH_MediaInterface_RMII))
+
+/**
+  * @}
+  */                                                
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Exported_Functions
+  * @{
+  */
+
+void GPIO_DeInit(GPIO_TypeDef* GPIOx);
+void GPIO_AFIODeInit(void);
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct);
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct);
+uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx);
+uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx);
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal);
+void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal);
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
+void GPIO_EventOutputCmd(FunctionalState NewState);
+void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState);
+void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource);
+void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_GPIO_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h
new file mode 100644
index 0000000000000000000000000000000000000000..7461770f3b72391d063cd83ad86e3222b188f469
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h
@@ -0,0 +1,472 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_i2c.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the I2C firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_I2C_H
+#define __STM32F10x_I2C_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup I2C
+  * @{
+  */
+
+/** @defgroup I2C_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  I2C Init structure definition  
+  */
+
+typedef struct
+{
+  uint32_t I2C_ClockSpeed;          /*!< Specifies the clock frequency.
+                                         This parameter must be set to a value lower than 400kHz */
+
+  uint16_t I2C_Mode;                /*!< Specifies the I2C mode.
+                                         This parameter can be a value of @ref I2C_mode */
+
+  uint16_t I2C_DutyCycle;           /*!< Specifies the I2C fast mode duty cycle.
+                                         This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */
+
+  uint16_t I2C_OwnAddress1;         /*!< Specifies the first device own address.
+                                         This parameter can be a 7-bit or 10-bit address. */
+
+  uint16_t I2C_Ack;                 /*!< Enables or disables the acknowledgement.
+                                         This parameter can be a value of @ref I2C_acknowledgement */
+
+  uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged.
+                                         This parameter can be a value of @ref I2C_acknowledged_address */
+}I2C_InitTypeDef;
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup I2C_Exported_Constants
+  * @{
+  */
+
+#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \
+                                   ((PERIPH) == I2C2))
+/** @defgroup I2C_mode 
+  * @{
+  */
+
+#define I2C_Mode_I2C                    ((uint16_t)0x0000)
+#define I2C_Mode_SMBusDevice            ((uint16_t)0x0002)  
+#define I2C_Mode_SMBusHost              ((uint16_t)0x000A)
+#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \
+                           ((MODE) == I2C_Mode_SMBusDevice) || \
+                           ((MODE) == I2C_Mode_SMBusHost))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_duty_cycle_in_fast_mode 
+  * @{
+  */
+
+#define I2C_DutyCycle_16_9              ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */
+#define I2C_DutyCycle_2                 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */
+#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \
+                                  ((CYCLE) == I2C_DutyCycle_2))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_acknowledgement
+  * @{
+  */
+
+#define I2C_Ack_Enable                  ((uint16_t)0x0400)
+#define I2C_Ack_Disable                 ((uint16_t)0x0000)
+#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \
+                                 ((STATE) == I2C_Ack_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_transfer_direction 
+  * @{
+  */
+
+#define  I2C_Direction_Transmitter      ((uint8_t)0x00)
+#define  I2C_Direction_Receiver         ((uint8_t)0x01)
+#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \
+                                     ((DIRECTION) == I2C_Direction_Receiver))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_acknowledged_address 
+  * @{
+  */
+
+#define I2C_AcknowledgedAddress_7bit    ((uint16_t)0x4000)
+#define I2C_AcknowledgedAddress_10bit   ((uint16_t)0xC000)
+#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \
+                                             ((ADDRESS) == I2C_AcknowledgedAddress_10bit))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_registers 
+  * @{
+  */
+
+#define I2C_Register_CR1                ((uint8_t)0x00)
+#define I2C_Register_CR2                ((uint8_t)0x04)
+#define I2C_Register_OAR1               ((uint8_t)0x08)
+#define I2C_Register_OAR2               ((uint8_t)0x0C)
+#define I2C_Register_DR                 ((uint8_t)0x10)
+#define I2C_Register_SR1                ((uint8_t)0x14)
+#define I2C_Register_SR2                ((uint8_t)0x18)
+#define I2C_Register_CCR                ((uint8_t)0x1C)
+#define I2C_Register_TRISE              ((uint8_t)0x20)
+#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \
+                                   ((REGISTER) == I2C_Register_CR2) || \
+                                   ((REGISTER) == I2C_Register_OAR1) || \
+                                   ((REGISTER) == I2C_Register_OAR2) || \
+                                   ((REGISTER) == I2C_Register_DR) || \
+                                   ((REGISTER) == I2C_Register_SR1) || \
+                                   ((REGISTER) == I2C_Register_SR2) || \
+                                   ((REGISTER) == I2C_Register_CCR) || \
+                                   ((REGISTER) == I2C_Register_TRISE))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_SMBus_alert_pin_level 
+  * @{
+  */
+
+#define I2C_SMBusAlert_Low              ((uint16_t)0x2000)
+#define I2C_SMBusAlert_High             ((uint16_t)0xDFFF)
+#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \
+                                   ((ALERT) == I2C_SMBusAlert_High))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_PEC_position 
+  * @{
+  */
+
+#define I2C_PECPosition_Next            ((uint16_t)0x0800)
+#define I2C_PECPosition_Current         ((uint16_t)0xF7FF)
+#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \
+                                       ((POSITION) == I2C_PECPosition_Current))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_interrupts_definition 
+  * @{
+  */
+
+#define I2C_IT_BUF                      ((uint16_t)0x0400)
+#define I2C_IT_EVT                      ((uint16_t)0x0200)
+#define I2C_IT_ERR                      ((uint16_t)0x0100)
+#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_interrupts_definition 
+  * @{
+  */
+
+#define I2C_IT_SMBALERT                 ((uint32_t)0x01008000)
+#define I2C_IT_TIMEOUT                  ((uint32_t)0x01004000)
+#define I2C_IT_PECERR                   ((uint32_t)0x01001000)
+#define I2C_IT_OVR                      ((uint32_t)0x01000800)
+#define I2C_IT_AF                       ((uint32_t)0x01000400)
+#define I2C_IT_ARLO                     ((uint32_t)0x01000200)
+#define I2C_IT_BERR                     ((uint32_t)0x01000100)
+#define I2C_IT_TXE                      ((uint32_t)0x06000080)
+#define I2C_IT_RXNE                     ((uint32_t)0x06000040)
+#define I2C_IT_STOPF                    ((uint32_t)0x02000010)
+#define I2C_IT_ADD10                    ((uint32_t)0x02000008)
+#define I2C_IT_BTF                      ((uint32_t)0x02000004)
+#define I2C_IT_ADDR                     ((uint32_t)0x02000002)
+#define I2C_IT_SB                       ((uint32_t)0x02000001)
+
+#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00))
+
+#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \
+                           ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \
+                           ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \
+                           ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \
+                           ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \
+                           ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \
+                           ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_flags_definition 
+  * @{
+  */
+
+/** 
+  * @brief  SR2 register flags  
+  */
+
+#define I2C_FLAG_DUALF                  ((uint32_t)0x00800000)
+#define I2C_FLAG_SMBHOST                ((uint32_t)0x00400000)
+#define I2C_FLAG_SMBDEFAULT             ((uint32_t)0x00200000)
+#define I2C_FLAG_GENCALL                ((uint32_t)0x00100000)
+#define I2C_FLAG_TRA                    ((uint32_t)0x00040000)
+#define I2C_FLAG_BUSY                   ((uint32_t)0x00020000)
+#define I2C_FLAG_MSL                    ((uint32_t)0x00010000)
+
+/** 
+  * @brief  SR1 register flags  
+  */
+
+#define I2C_FLAG_SMBALERT               ((uint32_t)0x10008000)
+#define I2C_FLAG_TIMEOUT                ((uint32_t)0x10004000)
+#define I2C_FLAG_PECERR                 ((uint32_t)0x10001000)
+#define I2C_FLAG_OVR                    ((uint32_t)0x10000800)
+#define I2C_FLAG_AF                     ((uint32_t)0x10000400)
+#define I2C_FLAG_ARLO                   ((uint32_t)0x10000200)
+#define I2C_FLAG_BERR                   ((uint32_t)0x10000100)
+#define I2C_FLAG_TXE                    ((uint32_t)0x10000080)
+#define I2C_FLAG_RXNE                   ((uint32_t)0x10000040)
+#define I2C_FLAG_STOPF                  ((uint32_t)0x10000010)
+#define I2C_FLAG_ADD10                  ((uint32_t)0x10000008)
+#define I2C_FLAG_BTF                    ((uint32_t)0x10000004)
+#define I2C_FLAG_ADDR                   ((uint32_t)0x10000002)
+#define I2C_FLAG_SB                     ((uint32_t)0x10000001)
+
+#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00))
+
+#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \
+                               ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \
+                               ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \
+                               ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \
+                               ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \
+                               ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \
+                               ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \
+                               ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \
+                               ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \
+                               ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \
+                               ((FLAG) == I2C_FLAG_SB))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Events 
+  * @{
+  */
+
+/** 
+  * @brief  EV1
+  */
+
+#define  I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED       ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */
+#define  I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED          ((uint32_t)0x00020002) /* BUSY and ADDR flags */
+#define  I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080)  /* DUALF, TRA, BUSY and TXE flags */
+#define  I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED    ((uint32_t)0x00820000)  /* DUALF and BUSY flags */
+#define  I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED        ((uint32_t)0x00120000)  /* GENCALL and BUSY flags */
+
+/** 
+  * @brief  EV2  
+  */
+
+#define  I2C_EVENT_SLAVE_BYTE_RECEIVED                     ((uint32_t)0x00020040)  /* BUSY and RXNE flags */
+
+/** 
+  * @brief  EV3  
+  */
+
+#define  I2C_EVENT_SLAVE_BYTE_TRANSMITTED                  ((uint32_t)0x00060084)  /* TRA, BUSY, TXE and BTF flags */
+
+/** 
+  * @brief  EV4
+  */
+
+#define  I2C_EVENT_SLAVE_STOP_DETECTED                     ((uint32_t)0x00000010)  /* STOPF flag */
+
+/** 
+  * @brief  EV5
+  */
+
+#define  I2C_EVENT_MASTER_MODE_SELECT                      ((uint32_t)0x00030001)  /* BUSY, MSL and SB flag */
+
+/** 
+  * @brief  EV6
+  */
+
+#define  I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED        ((uint32_t)0x00070082)  /* BUSY, MSL, ADDR, TXE and TRA flags */
+#define  I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED           ((uint32_t)0x00030002)  /* BUSY, MSL and ADDR flags */
+
+/** 
+  * @brief  EV7
+  */
+
+#define  I2C_EVENT_MASTER_BYTE_RECEIVED                    ((uint32_t)0x00030040)  /* BUSY, MSL and RXNE flags */
+
+/** 
+  * @brief  EV8
+  */
+
+#define I2C_EVENT_MASTER_BYTE_TRANSMITTING                 ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */
+
+/** 
+  * @brief  EV8_2
+  */
+
+#define  I2C_EVENT_MASTER_BYTE_TRANSMITTED                 ((uint32_t)0x00070084)  /* TRA, BUSY, MSL, TXE and BTF flags */
+
+/** 
+  * @brief  EV9
+  */
+
+#define  I2C_EVENT_MASTER_MODE_ADDRESS10                   ((uint32_t)0x00030008)  /* BUSY, MSL and ADD10 flags */
+
+/** 
+  * @brief  EV3_2
+  */
+
+#define  I2C_EVENT_SLAVE_ACK_FAILURE                       ((uint32_t)0x00000400)  /* AF flag */
+
+#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \
+                             ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \
+                             ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_own_address1 
+  * @{
+  */
+
+#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF)
+/**
+  * @}
+  */
+
+/** @defgroup I2C_clock_speed 
+  * @{
+  */
+
+#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Exported_Functions
+  * @{
+  */
+
+void I2C_DeInit(I2C_TypeDef* I2Cx);
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct);
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct);
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address);
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState);
+void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data);
+uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx);
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction);
+uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register);
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert);
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition);
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx);
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle);
+uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx);
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT);
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_I2C_H */
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h
new file mode 100644
index 0000000000000000000000000000000000000000..a46546a70ddfced33ef412b33073d9e3fdb97f9b
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h
@@ -0,0 +1,139 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_iwdg.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the IWDG 
+  *          firmware library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_IWDG_H
+#define __STM32F10x_IWDG_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup IWDG
+  * @{
+  */
+
+/** @defgroup IWDG_Exported_Types
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Exported_Constants
+  * @{
+  */
+
+/** @defgroup IWDG_WriteAccess
+  * @{
+  */
+
+#define IWDG_WriteAccess_Enable     ((uint16_t)0x5555)
+#define IWDG_WriteAccess_Disable    ((uint16_t)0x0000)
+#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \
+                                      ((ACCESS) == IWDG_WriteAccess_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_prescaler 
+  * @{
+  */
+
+#define IWDG_Prescaler_4            ((uint8_t)0x00)
+#define IWDG_Prescaler_8            ((uint8_t)0x01)
+#define IWDG_Prescaler_16           ((uint8_t)0x02)
+#define IWDG_Prescaler_32           ((uint8_t)0x03)
+#define IWDG_Prescaler_64           ((uint8_t)0x04)
+#define IWDG_Prescaler_128          ((uint8_t)0x05)
+#define IWDG_Prescaler_256          ((uint8_t)0x06)
+#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4)  || \
+                                      ((PRESCALER) == IWDG_Prescaler_8)  || \
+                                      ((PRESCALER) == IWDG_Prescaler_16) || \
+                                      ((PRESCALER) == IWDG_Prescaler_32) || \
+                                      ((PRESCALER) == IWDG_Prescaler_64) || \
+                                      ((PRESCALER) == IWDG_Prescaler_128)|| \
+                                      ((PRESCALER) == IWDG_Prescaler_256))
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Flag 
+  * @{
+  */
+
+#define IWDG_FLAG_PVU               ((uint16_t)0x0001)
+#define IWDG_FLAG_RVU               ((uint16_t)0x0002)
+#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU))
+#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF)
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Exported_Functions
+  * @{
+  */
+
+void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess);
+void IWDG_SetPrescaler(uint8_t IWDG_Prescaler);
+void IWDG_SetReload(uint16_t Reload);
+void IWDG_ReloadCounter(void);
+void IWDG_Enable(void);
+FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_IWDG_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h
new file mode 100644
index 0000000000000000000000000000000000000000..f8d59dfe31c65b64ec87423fbfee3235f14ab720
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h
@@ -0,0 +1,155 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_pwr.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the PWR firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_PWR_H
+#define __STM32F10x_PWR_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup PWR
+  * @{
+  */ 
+
+/** @defgroup PWR_Exported_Types
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup PWR_Exported_Constants
+  * @{
+  */ 
+
+/** @defgroup PVD_detection_level 
+  * @{
+  */ 
+
+#define PWR_PVDLevel_2V2          ((uint32_t)0x00000000)
+#define PWR_PVDLevel_2V3          ((uint32_t)0x00000020)
+#define PWR_PVDLevel_2V4          ((uint32_t)0x00000040)
+#define PWR_PVDLevel_2V5          ((uint32_t)0x00000060)
+#define PWR_PVDLevel_2V6          ((uint32_t)0x00000080)
+#define PWR_PVDLevel_2V7          ((uint32_t)0x000000A0)
+#define PWR_PVDLevel_2V8          ((uint32_t)0x000000C0)
+#define PWR_PVDLevel_2V9          ((uint32_t)0x000000E0)
+#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \
+                                 ((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \
+                                 ((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \
+                                 ((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9))
+/**
+  * @}
+  */
+
+/** @defgroup Regulator_state_is_STOP_mode 
+  * @{
+  */
+
+#define PWR_Regulator_ON          ((uint32_t)0x00000000)
+#define PWR_Regulator_LowPower    ((uint32_t)0x00000001)
+#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \
+                                     ((REGULATOR) == PWR_Regulator_LowPower))
+/**
+  * @}
+  */
+
+/** @defgroup STOP_mode_entry 
+  * @{
+  */
+
+#define PWR_STOPEntry_WFI         ((uint8_t)0x01)
+#define PWR_STOPEntry_WFE         ((uint8_t)0x02)
+#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE))
+ 
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Flag 
+  * @{
+  */
+
+#define PWR_FLAG_WU               ((uint32_t)0x00000001)
+#define PWR_FLAG_SB               ((uint32_t)0x00000002)
+#define PWR_FLAG_PVDO             ((uint32_t)0x00000004)
+#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \
+                               ((FLAG) == PWR_FLAG_PVDO))
+
+#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Exported_Functions
+  * @{
+  */
+
+void PWR_DeInit(void);
+void PWR_BackupAccessCmd(FunctionalState NewState);
+void PWR_PVDCmd(FunctionalState NewState);
+void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel);
+void PWR_WakeUpPinCmd(FunctionalState NewState);
+void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry);
+void PWR_EnterSTANDBYMode(void);
+FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG);
+void PWR_ClearFlag(uint32_t PWR_FLAG);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_PWR_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h
new file mode 100644
index 0000000000000000000000000000000000000000..2d183767246ad9428293b576282e6535fc33e531
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h
@@ -0,0 +1,700 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_rcc.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the RCC firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_RCC_H
+#define __STM32F10x_RCC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup RCC
+  * @{
+  */
+
+/** @defgroup RCC_Exported_Types
+  * @{
+  */
+
+typedef struct
+{
+  uint32_t SYSCLK_Frequency;  /*!< returns SYSCLK clock frequency expressed in Hz */
+  uint32_t HCLK_Frequency;    /*!< returns HCLK clock frequency expressed in Hz */
+  uint32_t PCLK1_Frequency;   /*!< returns PCLK1 clock frequency expressed in Hz */
+  uint32_t PCLK2_Frequency;   /*!< returns PCLK2 clock frequency expressed in Hz */
+  uint32_t ADCCLK_Frequency;  /*!< returns ADCCLK clock frequency expressed in Hz */
+}RCC_ClocksTypeDef;
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup HSE_configuration 
+  * @{
+  */
+
+#define RCC_HSE_OFF                      ((uint32_t)0x00000000)
+#define RCC_HSE_ON                       ((uint32_t)0x00010000)
+#define RCC_HSE_Bypass                   ((uint32_t)0x00040000)
+#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \
+                         ((HSE) == RCC_HSE_Bypass))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup PLL_entry_clock_source 
+  * @{
+  */
+
+#define RCC_PLLSource_HSI_Div2           ((uint32_t)0x00000000)
+
+#ifndef STM32F10X_CL
+ #define RCC_PLLSource_HSE_Div1           ((uint32_t)0x00010000)
+ #define RCC_PLLSource_HSE_Div2           ((uint32_t)0x00030000)
+ #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
+                                   ((SOURCE) == RCC_PLLSource_HSE_Div1) || \
+                                   ((SOURCE) == RCC_PLLSource_HSE_Div2))
+#else
+ #define RCC_PLLSource_PREDIV1            ((uint32_t)0x00010000)
+#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \
+                                   ((SOURCE) == RCC_PLLSource_PREDIV1))
+#endif /* STM32F10X_CL */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup PLL_multiplication_factor 
+  * @{
+  */
+#ifndef STM32F10X_CL
+ #define RCC_PLLMul_2                    ((uint32_t)0x00000000)
+ #define RCC_PLLMul_3                    ((uint32_t)0x00040000)
+ #define RCC_PLLMul_4                    ((uint32_t)0x00080000)
+ #define RCC_PLLMul_5                    ((uint32_t)0x000C0000)
+ #define RCC_PLLMul_6                    ((uint32_t)0x00100000)
+ #define RCC_PLLMul_7                    ((uint32_t)0x00140000)
+ #define RCC_PLLMul_8                    ((uint32_t)0x00180000)
+ #define RCC_PLLMul_9                    ((uint32_t)0x001C0000)
+ #define RCC_PLLMul_10                   ((uint32_t)0x00200000)
+ #define RCC_PLLMul_11                   ((uint32_t)0x00240000)
+ #define RCC_PLLMul_12                   ((uint32_t)0x00280000)
+ #define RCC_PLLMul_13                   ((uint32_t)0x002C0000)
+ #define RCC_PLLMul_14                   ((uint32_t)0x00300000)
+ #define RCC_PLLMul_15                   ((uint32_t)0x00340000)
+ #define RCC_PLLMul_16                   ((uint32_t)0x00380000)
+ #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3)   || \
+                              ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5)   || \
+                              ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7)   || \
+                              ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9)   || \
+                              ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \
+                              ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \
+                              ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \
+                              ((MUL) == RCC_PLLMul_16))
+
+#else
+ #define RCC_PLLMul_4                    ((uint32_t)0x00080000)
+ #define RCC_PLLMul_5                    ((uint32_t)0x000C0000)
+ #define RCC_PLLMul_6                    ((uint32_t)0x00100000)
+ #define RCC_PLLMul_7                    ((uint32_t)0x00140000)
+ #define RCC_PLLMul_8                    ((uint32_t)0x00180000)
+ #define RCC_PLLMul_9                    ((uint32_t)0x001C0000)
+ #define RCC_PLLMul_6_5                  ((uint32_t)0x00340000)
+
+ #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \
+                              ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \
+                              ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \
+                              ((MUL) == RCC_PLLMul_6_5))
+#endif /* STM32F10X_CL */                              
+/**
+  * @}
+  */
+
+#ifdef STM32F10X_CL
+/** @defgroup PREDIV1_division_factor
+  * @{
+  */
+ #define  RCC_PREDIV1_Div1               ((uint32_t)0x00000000)
+ #define  RCC_PREDIV1_Div2               ((uint32_t)0x00000001)
+ #define  RCC_PREDIV1_Div3               ((uint32_t)0x00000002)
+ #define  RCC_PREDIV1_Div4               ((uint32_t)0x00000003)
+ #define  RCC_PREDIV1_Div5               ((uint32_t)0x00000004)
+ #define  RCC_PREDIV1_Div6               ((uint32_t)0x00000005)
+ #define  RCC_PREDIV1_Div7               ((uint32_t)0x00000006)
+ #define  RCC_PREDIV1_Div8               ((uint32_t)0x00000007)
+ #define  RCC_PREDIV1_Div9               ((uint32_t)0x00000008)
+ #define  RCC_PREDIV1_Div10              ((uint32_t)0x00000009)
+ #define  RCC_PREDIV1_Div11              ((uint32_t)0x0000000A)
+ #define  RCC_PREDIV1_Div12              ((uint32_t)0x0000000B)
+ #define  RCC_PREDIV1_Div13              ((uint32_t)0x0000000C)
+ #define  RCC_PREDIV1_Div14              ((uint32_t)0x0000000D)
+ #define  RCC_PREDIV1_Div15              ((uint32_t)0x0000000E)
+ #define  RCC_PREDIV1_Div16              ((uint32_t)0x0000000F)
+
+ #define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \
+                                  ((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \
+                                  ((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \
+                                  ((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \
+                                  ((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \
+                                  ((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \
+                                  ((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \
+                                  ((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16))
+/**
+  * @}
+  */
+
+
+/** @defgroup PREDIV1_clock_source
+  * @{
+  */
+/* PREDIV1 clock source (only for STM32 connectivity line devices) */
+ #define  RCC_PREDIV1_Source_HSE         ((uint32_t)0x00000000) 
+ #define  RCC_PREDIV1_Source_PLL2        ((uint32_t)0x00010000) 
+
+ #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE) || \
+                                        ((SOURCE) == RCC_PREDIV1_Source_PLL2)) 
+/**
+  * @}
+  */
+
+
+/** @defgroup PREDIV2_division_factor
+  * @{
+  */
+  
+ #define  RCC_PREDIV2_Div1               ((uint32_t)0x00000000)
+ #define  RCC_PREDIV2_Div2               ((uint32_t)0x00000010)
+ #define  RCC_PREDIV2_Div3               ((uint32_t)0x00000020)
+ #define  RCC_PREDIV2_Div4               ((uint32_t)0x00000030)
+ #define  RCC_PREDIV2_Div5               ((uint32_t)0x00000040)
+ #define  RCC_PREDIV2_Div6               ((uint32_t)0x00000050)
+ #define  RCC_PREDIV2_Div7               ((uint32_t)0x00000060)
+ #define  RCC_PREDIV2_Div8               ((uint32_t)0x00000070)
+ #define  RCC_PREDIV2_Div9               ((uint32_t)0x00000080)
+ #define  RCC_PREDIV2_Div10              ((uint32_t)0x00000090)
+ #define  RCC_PREDIV2_Div11              ((uint32_t)0x000000A0)
+ #define  RCC_PREDIV2_Div12              ((uint32_t)0x000000B0)
+ #define  RCC_PREDIV2_Div13              ((uint32_t)0x000000C0)
+ #define  RCC_PREDIV2_Div14              ((uint32_t)0x000000D0)
+ #define  RCC_PREDIV2_Div15              ((uint32_t)0x000000E0)
+ #define  RCC_PREDIV2_Div16              ((uint32_t)0x000000F0)
+
+ #define IS_RCC_PREDIV2(PREDIV2) (((PREDIV2) == RCC_PREDIV2_Div1) || ((PREDIV2) == RCC_PREDIV2_Div2) || \
+                                  ((PREDIV2) == RCC_PREDIV2_Div3) || ((PREDIV2) == RCC_PREDIV2_Div4) || \
+                                  ((PREDIV2) == RCC_PREDIV2_Div5) || ((PREDIV2) == RCC_PREDIV2_Div6) || \
+                                  ((PREDIV2) == RCC_PREDIV2_Div7) || ((PREDIV2) == RCC_PREDIV2_Div8) || \
+                                  ((PREDIV2) == RCC_PREDIV2_Div9) || ((PREDIV2) == RCC_PREDIV2_Div10) || \
+                                  ((PREDIV2) == RCC_PREDIV2_Div11) || ((PREDIV2) == RCC_PREDIV2_Div12) || \
+                                  ((PREDIV2) == RCC_PREDIV2_Div13) || ((PREDIV2) == RCC_PREDIV2_Div14) || \
+                                  ((PREDIV2) == RCC_PREDIV2_Div15) || ((PREDIV2) == RCC_PREDIV2_Div16))
+/**
+  * @}
+  */
+
+
+/** @defgroup PLL2_multiplication_factor
+  * @{
+  */
+  
+ #define  RCC_PLL2Mul_8                  ((uint32_t)0x00000600)
+ #define  RCC_PLL2Mul_9                  ((uint32_t)0x00000700)
+ #define  RCC_PLL2Mul_10                 ((uint32_t)0x00000800)
+ #define  RCC_PLL2Mul_11                 ((uint32_t)0x00000900)
+ #define  RCC_PLL2Mul_12                 ((uint32_t)0x00000A00)
+ #define  RCC_PLL2Mul_13                 ((uint32_t)0x00000B00)
+ #define  RCC_PLL2Mul_14                 ((uint32_t)0x00000C00)
+ #define  RCC_PLL2Mul_16                 ((uint32_t)0x00000E00)
+ #define  RCC_PLL2Mul_20                 ((uint32_t)0x00000F00)
+
+ #define IS_RCC_PLL2_MUL(MUL) (((MUL) == RCC_PLL2Mul_8) || ((MUL) == RCC_PLL2Mul_9)  || \
+                               ((MUL) == RCC_PLL2Mul_10) || ((MUL) == RCC_PLL2Mul_11) || \
+                               ((MUL) == RCC_PLL2Mul_12) || ((MUL) == RCC_PLL2Mul_13) || \
+                               ((MUL) == RCC_PLL2Mul_14) || ((MUL) == RCC_PLL2Mul_16) || \
+                               ((MUL) == RCC_PLL2Mul_20))
+/**
+  * @}
+  */
+
+
+/** @defgroup PLL3_multiplication_factor
+  * @{
+  */
+
+ #define  RCC_PLL3Mul_8                  ((uint32_t)0x00006000)
+ #define  RCC_PLL3Mul_9                  ((uint32_t)0x00007000)
+ #define  RCC_PLL3Mul_10                 ((uint32_t)0x00008000)
+ #define  RCC_PLL3Mul_11                 ((uint32_t)0x00009000)
+ #define  RCC_PLL3Mul_12                 ((uint32_t)0x0000A000)
+ #define  RCC_PLL3Mul_13                 ((uint32_t)0x0000B000)
+ #define  RCC_PLL3Mul_14                 ((uint32_t)0x0000C000)
+ #define  RCC_PLL3Mul_16                 ((uint32_t)0x0000E000)
+ #define  RCC_PLL3Mul_20                 ((uint32_t)0x0000F000)
+
+ #define IS_RCC_PLL3_MUL(MUL) (((MUL) == RCC_PLL3Mul_8) || ((MUL) == RCC_PLL3Mul_9)  || \
+                               ((MUL) == RCC_PLL3Mul_10) || ((MUL) == RCC_PLL3Mul_11) || \
+                               ((MUL) == RCC_PLL3Mul_12) || ((MUL) == RCC_PLL3Mul_13) || \
+                               ((MUL) == RCC_PLL3Mul_14) || ((MUL) == RCC_PLL3Mul_16) || \
+                               ((MUL) == RCC_PLL3Mul_20))
+/**
+  * @}
+  */
+
+#endif /* STM32F10X_CL */
+
+
+/** @defgroup System_clock_source 
+  * @{
+  */
+
+#define RCC_SYSCLKSource_HSI             ((uint32_t)0x00000000)
+#define RCC_SYSCLKSource_HSE             ((uint32_t)0x00000001)
+#define RCC_SYSCLKSource_PLLCLK          ((uint32_t)0x00000002)
+#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \
+                                      ((SOURCE) == RCC_SYSCLKSource_HSE) || \
+                                      ((SOURCE) == RCC_SYSCLKSource_PLLCLK))
+/**
+  * @}
+  */
+
+/** @defgroup AHB_clock_source 
+  * @{
+  */
+
+#define RCC_SYSCLK_Div1                  ((uint32_t)0x00000000)
+#define RCC_SYSCLK_Div2                  ((uint32_t)0x00000080)
+#define RCC_SYSCLK_Div4                  ((uint32_t)0x00000090)
+#define RCC_SYSCLK_Div8                  ((uint32_t)0x000000A0)
+#define RCC_SYSCLK_Div16                 ((uint32_t)0x000000B0)
+#define RCC_SYSCLK_Div64                 ((uint32_t)0x000000C0)
+#define RCC_SYSCLK_Div128                ((uint32_t)0x000000D0)
+#define RCC_SYSCLK_Div256                ((uint32_t)0x000000E0)
+#define RCC_SYSCLK_Div512                ((uint32_t)0x000000F0)
+#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \
+                           ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \
+                           ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \
+                           ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \
+                           ((HCLK) == RCC_SYSCLK_Div512))
+/**
+  * @}
+  */ 
+
+/** @defgroup APB1_APB2_clock_source 
+  * @{
+  */
+
+#define RCC_HCLK_Div1                    ((uint32_t)0x00000000)
+#define RCC_HCLK_Div2                    ((uint32_t)0x00000400)
+#define RCC_HCLK_Div4                    ((uint32_t)0x00000500)
+#define RCC_HCLK_Div8                    ((uint32_t)0x00000600)
+#define RCC_HCLK_Div16                   ((uint32_t)0x00000700)
+#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \
+                           ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \
+                           ((PCLK) == RCC_HCLK_Div16))
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Interrupt_source 
+  * @{
+  */
+
+#define RCC_IT_LSIRDY                    ((uint8_t)0x01)
+#define RCC_IT_LSERDY                    ((uint8_t)0x02)
+#define RCC_IT_HSIRDY                    ((uint8_t)0x04)
+#define RCC_IT_HSERDY                    ((uint8_t)0x08)
+#define RCC_IT_PLLRDY                    ((uint8_t)0x10)
+#define RCC_IT_CSS                       ((uint8_t)0x80)
+
+#ifndef STM32F10X_CL
+ #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xE0) == 0x00) && ((IT) != 0x00))
+ #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
+                            ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
+                            ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS))
+ #define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x60) == 0x00) && ((IT) != 0x00))
+#else
+ #define RCC_IT_PLL2RDY                  ((uint8_t)0x20)
+ #define RCC_IT_PLL3RDY                  ((uint8_t)0x40)
+ #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00))
+ #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
+                            ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
+                            ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \
+                            ((IT) == RCC_IT_PLL2RDY) || ((IT) == RCC_IT_PLL3RDY))
+ #define IS_RCC_CLEAR_IT(IT) ((IT) != 0x00)
+#endif /* STM32F10X_CL */ 
+
+
+/**
+  * @}
+  */
+
+#ifndef STM32F10X_CL
+/** @defgroup USB_Device_clock_source 
+  * @{
+  */
+
+ #define RCC_USBCLKSource_PLLCLK_1Div5   ((uint8_t)0x00)
+ #define RCC_USBCLKSource_PLLCLK_Div1    ((uint8_t)0x01)
+
+ #define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \
+                                      ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1))
+#else
+/** @defgroup USB_OTG_FS_clock_source 
+  * @{
+  */
+ #define RCC_OTGFSCLKSource_PLLVCO_Div3    ((uint8_t)0x00)
+ #define RCC_OTGFSCLKSource_PLLVCO_Div2    ((uint8_t)0x01)
+
+ #define IS_RCC_OTGFSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div3) || \
+                                         ((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div2))
+#endif /* STM32F10X_CL */ 
+/**
+  * @}
+  */
+
+#ifdef STM32F10X_CL
+/** @defgroup I2S2_clock_source 
+  * @{
+  */
+ #define RCC_I2S2CLKSource_SYSCLK        ((uint8_t)0x00)
+ #define RCC_I2S2CLKSource_PLL3_VCO      ((uint8_t)0x01)
+
+ #define IS_RCC_I2S2CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || \
+                                        ((SOURCE) == RCC_I2S2CLKSource_PLL3_VCO))
+/**
+  * @}
+  */
+
+/** @defgroup I2S3_clock_source 
+  * @{
+  */
+ #define RCC_I2S3CLKSource_SYSCLK        ((uint8_t)0x00)
+ #define RCC_I2S3CLKSource_PLL3_VCO      ((uint8_t)0x01)
+
+ #define IS_RCC_I2S3CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S3CLKSource_SYSCLK) || \
+                                        ((SOURCE) == RCC_I2S3CLKSource_PLL3_VCO))    
+/**
+  * @}
+  */
+#endif /* STM32F10X_CL */  
+  
+
+/** @defgroup ADC_clock_source 
+  * @{
+  */
+
+#define RCC_PCLK2_Div2                   ((uint32_t)0x00000000)
+#define RCC_PCLK2_Div4                   ((uint32_t)0x00004000)
+#define RCC_PCLK2_Div6                   ((uint32_t)0x00008000)
+#define RCC_PCLK2_Div8                   ((uint32_t)0x0000C000)
+#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \
+                               ((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8))
+/**
+  * @}
+  */
+
+/** @defgroup LSE_configuration 
+  * @{
+  */
+
+#define RCC_LSE_OFF                      ((uint8_t)0x00)
+#define RCC_LSE_ON                       ((uint8_t)0x01)
+#define RCC_LSE_Bypass                   ((uint8_t)0x04)
+#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \
+                         ((LSE) == RCC_LSE_Bypass))
+/**
+  * @}
+  */
+
+/** @defgroup RTC_clock_source 
+  * @{
+  */
+
+#define RCC_RTCCLKSource_LSE             ((uint32_t)0x00000100)
+#define RCC_RTCCLKSource_LSI             ((uint32_t)0x00000200)
+#define RCC_RTCCLKSource_HSE_Div128      ((uint32_t)0x00000300)
+#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_LSI) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div128))
+/**
+  * @}
+  */
+
+/** @defgroup AHB_peripheral 
+  * @{
+  */
+
+#define RCC_AHBPeriph_DMA1               ((uint32_t)0x00000001)
+#define RCC_AHBPeriph_DMA2               ((uint32_t)0x00000002)
+#define RCC_AHBPeriph_SRAM               ((uint32_t)0x00000004)
+#define RCC_AHBPeriph_FLITF              ((uint32_t)0x00000010)
+#define RCC_AHBPeriph_CRC                ((uint32_t)0x00000040)
+
+#ifndef STM32F10X_CL
+ #define RCC_AHBPeriph_FSMC              ((uint32_t)0x00000100)
+ #define RCC_AHBPeriph_SDIO              ((uint32_t)0x00000400)
+ #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00))
+#else
+ #define RCC_AHBPeriph_OTG_FS            ((uint32_t)0x00001000)
+ #define RCC_AHBPeriph_ETH_MAC           ((uint32_t)0x00004000)
+ #define RCC_AHBPeriph_ETH_MAC_Tx        ((uint32_t)0x00008000)
+ #define RCC_AHBPeriph_ETH_MAC_Rx        ((uint32_t)0x00010000)
+
+ #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFE2FA8) == 0x00) && ((PERIPH) != 0x00))
+ #define IS_RCC_AHB_PERIPH_RESET(PERIPH) ((((PERIPH) & 0xFFFFAFFF) == 0x00) && ((PERIPH) != 0x00))
+#endif /* STM32F10X_CL */
+/**
+  * @}
+  */
+
+/** @defgroup APB2_peripheral 
+  * @{
+  */
+
+#define RCC_APB2Periph_AFIO              ((uint32_t)0x00000001)
+#define RCC_APB2Periph_GPIOA             ((uint32_t)0x00000004)
+#define RCC_APB2Periph_GPIOB             ((uint32_t)0x00000008)
+#define RCC_APB2Periph_GPIOC             ((uint32_t)0x00000010)
+#define RCC_APB2Periph_GPIOD             ((uint32_t)0x00000020)
+#define RCC_APB2Periph_GPIOE             ((uint32_t)0x00000040)
+#define RCC_APB2Periph_GPIOF             ((uint32_t)0x00000080)
+#define RCC_APB2Periph_GPIOG             ((uint32_t)0x00000100)
+#define RCC_APB2Periph_ADC1              ((uint32_t)0x00000200)
+#define RCC_APB2Periph_ADC2              ((uint32_t)0x00000400)
+#define RCC_APB2Periph_TIM1              ((uint32_t)0x00000800)
+#define RCC_APB2Periph_SPI1              ((uint32_t)0x00001000)
+#define RCC_APB2Periph_TIM8              ((uint32_t)0x00002000)
+#define RCC_APB2Periph_USART1            ((uint32_t)0x00004000)
+#define RCC_APB2Periph_ADC3              ((uint32_t)0x00008000)
+
+#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFFF0002) == 0x00) && ((PERIPH) != 0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup APB1_peripheral 
+  * @{
+  */
+
+#define RCC_APB1Periph_TIM2              ((uint32_t)0x00000001)
+#define RCC_APB1Periph_TIM3              ((uint32_t)0x00000002)
+#define RCC_APB1Periph_TIM4              ((uint32_t)0x00000004)
+#define RCC_APB1Periph_TIM5              ((uint32_t)0x00000008)
+#define RCC_APB1Periph_TIM6              ((uint32_t)0x00000010)
+#define RCC_APB1Periph_TIM7              ((uint32_t)0x00000020)
+#define RCC_APB1Periph_WWDG              ((uint32_t)0x00000800)
+#define RCC_APB1Periph_SPI2              ((uint32_t)0x00004000)
+#define RCC_APB1Periph_SPI3              ((uint32_t)0x00008000)
+#define RCC_APB1Periph_USART2            ((uint32_t)0x00020000)
+#define RCC_APB1Periph_USART3            ((uint32_t)0x00040000)
+#define RCC_APB1Periph_UART4             ((uint32_t)0x00080000)
+#define RCC_APB1Periph_UART5             ((uint32_t)0x00100000)
+#define RCC_APB1Periph_I2C1              ((uint32_t)0x00200000)
+#define RCC_APB1Periph_I2C2              ((uint32_t)0x00400000)
+#define RCC_APB1Periph_USB               ((uint32_t)0x00800000)
+#define RCC_APB1Periph_CAN1              ((uint32_t)0x02000000)
+#define RCC_APB1Periph_BKP               ((uint32_t)0x08000000)
+#define RCC_APB1Periph_PWR               ((uint32_t)0x10000000)
+#define RCC_APB1Periph_DAC               ((uint32_t)0x20000000)
+#define RCC_APB1Periph_CAN2             ((uint32_t)0x04000000) 
+#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0xC10137C0) == 0x00) && ((PERIPH) != 0x00))
+
+/**
+  * @}
+  */
+
+/** @defgroup Clock_source_to_output_on_MCO_pin 
+  * @{
+  */
+
+#define RCC_MCO_NoClock                  ((uint8_t)0x00)
+#define RCC_MCO_SYSCLK                   ((uint8_t)0x04)
+#define RCC_MCO_HSI                      ((uint8_t)0x05)
+#define RCC_MCO_HSE                      ((uint8_t)0x06)
+#define RCC_MCO_PLLCLK_Div2              ((uint8_t)0x07)
+
+#ifndef STM32F10X_CL
+ #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
+                          ((MCO) == RCC_MCO_SYSCLK)  || ((MCO) == RCC_MCO_HSE) || \
+                          ((MCO) == RCC_MCO_PLLCLK_Div2))
+#else
+ #define RCC_MCO_PLL2CLK                 ((uint8_t)0x08)
+ #define RCC_MCO_PLL3CLK_Div2            ((uint8_t)0x09)
+ #define RCC_MCO_XT1                     ((uint8_t)0x0A)
+ #define RCC_MCO_PLL3CLK                 ((uint8_t)0x0B)
+
+ #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \
+                          ((MCO) == RCC_MCO_SYSCLK)  || ((MCO) == RCC_MCO_HSE) || \
+                          ((MCO) == RCC_MCO_PLLCLK_Div2) || ((MCO) == RCC_MCO_PLL2CLK) || \
+                          ((MCO) == RCC_MCO_PLL3CLK_Div2) || ((MCO) == RCC_MCO_XT1) || \
+                          ((MCO) == RCC_MCO_PLL3CLK))
+#endif /* STM32F10X_CL */ 
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Flag 
+  * @{
+  */
+
+#define RCC_FLAG_HSIRDY                  ((uint8_t)0x21)
+#define RCC_FLAG_HSERDY                  ((uint8_t)0x31)
+#define RCC_FLAG_PLLRDY                  ((uint8_t)0x39)
+#define RCC_FLAG_LSERDY                  ((uint8_t)0x41)
+#define RCC_FLAG_LSIRDY                  ((uint8_t)0x61)
+#define RCC_FLAG_PINRST                  ((uint8_t)0x7A)
+#define RCC_FLAG_PORRST                  ((uint8_t)0x7B)
+#define RCC_FLAG_SFTRST                  ((uint8_t)0x7C)
+#define RCC_FLAG_IWDGRST                 ((uint8_t)0x7D)
+#define RCC_FLAG_WWDGRST                 ((uint8_t)0x7E)
+#define RCC_FLAG_LPWRRST                 ((uint8_t)0x7F)
+
+#ifndef STM32F10X_CL
+ #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
+                            ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
+                            ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
+                            ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
+                            ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
+                            ((FLAG) == RCC_FLAG_LPWRRST))
+#else
+ #define RCC_FLAG_PLL2RDY                ((uint8_t)0x3B) 
+ #define RCC_FLAG_PLL3RDY                ((uint8_t)0x3D) 
+ #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \
+                            ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \
+                            ((FLAG) == RCC_FLAG_PLL2RDY) || ((FLAG) == RCC_FLAG_PLL3RDY) || \
+                            ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \
+                            ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \
+                            ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \
+                            ((FLAG) == RCC_FLAG_LPWRRST))
+#endif /* STM32F10X_CL */ 
+
+#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F)
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Exported_Functions
+  * @{
+  */
+
+void RCC_DeInit(void);
+void RCC_HSEConfig(uint32_t RCC_HSE);
+ErrorStatus RCC_WaitForHSEStartUp(void);
+void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue);
+void RCC_HSICmd(FunctionalState NewState);
+void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul);
+void RCC_PLLCmd(FunctionalState NewState);
+
+#ifdef STM32F10X_CL
+ void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div);
+ void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div);
+ void RCC_PLL2Config(uint32_t RCC_PLL2Mul);
+ void RCC_PLL2Cmd(FunctionalState NewState);
+ void RCC_PLL3Config(uint32_t RCC_PLL3Mul);
+ void RCC_PLL3Cmd(FunctionalState NewState);
+#endif /* STM32F10X_CL */ 
+
+void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource);
+uint8_t RCC_GetSYSCLKSource(void);
+void RCC_HCLKConfig(uint32_t RCC_SYSCLK);
+void RCC_PCLK1Config(uint32_t RCC_HCLK);
+void RCC_PCLK2Config(uint32_t RCC_HCLK);
+void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState);
+
+#ifndef STM32F10X_CL
+ void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource);
+#else
+ void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource);
+#endif /* STM32F10X_CL */ 
+
+void RCC_ADCCLKConfig(uint32_t RCC_PCLK2);
+
+#ifdef STM32F10X_CL
+ void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource);                                  
+ void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource);
+#endif /* STM32F10X_CL */ 
+
+void RCC_LSEConfig(uint8_t RCC_LSE);
+void RCC_LSICmd(FunctionalState NewState);
+void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource);
+void RCC_RTCCLKCmd(FunctionalState NewState);
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks);
+void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
+void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
+void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
+
+#ifdef STM32F10X_CL
+void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState);
+#endif /* STM32F10X_CL */ 
+
+void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
+void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
+void RCC_BackupResetCmd(FunctionalState NewState);
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState);
+void RCC_MCOConfig(uint8_t RCC_MCO);
+FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG);
+void RCC_ClearFlag(void);
+ITStatus RCC_GetITStatus(uint8_t RCC_IT);
+void RCC_ClearITPendingBit(uint8_t RCC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_RCC_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h
new file mode 100644
index 0000000000000000000000000000000000000000..1c76d58bf449e92ab6aec8b8fc71b9e66bb32c1b
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h
@@ -0,0 +1,134 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_rtc.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the RTC firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_RTC_H
+#define __STM32F10x_RTC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup RTC
+  * @{
+  */ 
+
+/** @defgroup RTC_Exported_Types
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup RTC_interrupts_define 
+  * @{
+  */
+
+#define RTC_IT_OW            ((uint16_t)0x0004)  /*!< Overflow interrupt */
+#define RTC_IT_ALR           ((uint16_t)0x0002)  /*!< Alarm interrupt */
+#define RTC_IT_SEC           ((uint16_t)0x0001)  /*!< Second interrupt */
+#define IS_RTC_IT(IT) ((((IT) & (uint16_t)0xFFF8) == 0x00) && ((IT) != 0x00))
+#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \
+                           ((IT) == RTC_IT_SEC))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_interrupts_flags 
+  * @{
+  */
+
+#define RTC_FLAG_RTOFF       ((uint16_t)0x0020)  /*!< RTC Operation OFF flag */
+#define RTC_FLAG_RSF         ((uint16_t)0x0008)  /*!< Registers Synchronized flag */
+#define RTC_FLAG_OW          ((uint16_t)0x0004)  /*!< Overflow flag */
+#define RTC_FLAG_ALR         ((uint16_t)0x0002)  /*!< Alarm flag */
+#define RTC_FLAG_SEC         ((uint16_t)0x0001)  /*!< Second flag */
+#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFF0) == 0x00) && ((FLAG) != 0x00))
+#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \
+                               ((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \
+                               ((FLAG) == RTC_FLAG_SEC))
+#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF)
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Exported_Functions
+  * @{
+  */
+
+void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState);
+void RTC_EnterConfigMode(void);
+void RTC_ExitConfigMode(void);
+uint32_t  RTC_GetCounter(void);
+void RTC_SetCounter(uint32_t CounterValue);
+void RTC_SetPrescaler(uint32_t PrescalerValue);
+void RTC_SetAlarm(uint32_t AlarmValue);
+uint32_t  RTC_GetDivider(void);
+void RTC_WaitForLastTask(void);
+void RTC_WaitForSynchro(void);
+FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG);
+void RTC_ClearFlag(uint16_t RTC_FLAG);
+ITStatus RTC_GetITStatus(uint16_t RTC_IT);
+void RTC_ClearITPendingBit(uint16_t RTC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_RTC_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h
new file mode 100644
index 0000000000000000000000000000000000000000..76736baf9d2e5c33f3b7d38ad0d3becf320ada8d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h
@@ -0,0 +1,530 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_sdio.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the SDIO firmware
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SDIO_H
+#define __STM32F10x_SDIO_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup SDIO
+  * @{
+  */
+
+/** @defgroup SDIO_Exported_Types
+  * @{
+  */
+
+typedef struct
+{
+  uint32_t SDIO_ClockEdge;            /*!< Specifies the clock transition on which the bit capture is made.
+                                           This parameter can be a value of @ref SDIO_Clock_Edge */
+
+  uint32_t SDIO_ClockBypass;          /*!< Specifies whether the SDIO Clock divider bypass is
+                                           enabled or disabled.
+                                           This parameter can be a value of @ref SDIO_Clock_Bypass */
+
+  uint32_t SDIO_ClockPowerSave;       /*!< Specifies whether SDIO Clock output is enabled or
+                                           disabled when the bus is idle.
+                                           This parameter can be a value of @ref SDIO_Clock_Power_Save */
+
+  uint32_t SDIO_BusWide;              /*!< Specifies the SDIO bus width.
+                                           This parameter can be a value of @ref SDIO_Bus_Wide */
+
+  uint32_t SDIO_HardwareFlowControl;  /*!< Specifies whether the SDIO hardware flow control is enabled or disabled.
+                                           This parameter can be a value of @ref SDIO_Hardware_Flow_Control */
+
+  uint8_t SDIO_ClockDiv;              /*!< Specifies the clock frequency of the SDIO controller.
+                                           This parameter can be a value between 0x00 and 0xFF. */
+                                           
+} SDIO_InitTypeDef;
+
+typedef struct
+{
+  uint32_t SDIO_Argument;  /*!< Specifies the SDIO command argument which is sent
+                                to a card as part of a command message. If a command
+                                contains an argument, it must be loaded into this register
+                                before writing the command to the command register */
+
+  uint32_t SDIO_CmdIndex;  /*!< Specifies the SDIO command index. It must be lower than 0x40. */
+
+  uint32_t SDIO_Response;  /*!< Specifies the SDIO response type.
+                                This parameter can be a value of @ref SDIO_Response_Type */
+
+  uint32_t SDIO_Wait;      /*!< Specifies whether SDIO wait-for-interrupt request is enabled or disabled.
+                                This parameter can be a value of @ref SDIO_Wait_Interrupt_State */
+
+  uint32_t SDIO_CPSM;      /*!< Specifies whether SDIO Command path state machine (CPSM)
+                                is enabled or disabled.
+                                This parameter can be a value of @ref SDIO_CPSM_State */
+} SDIO_CmdInitTypeDef;
+
+typedef struct
+{
+  uint32_t SDIO_DataTimeOut;    /*!< Specifies the data timeout period in card bus clock periods. */
+
+  uint32_t SDIO_DataLength;     /*!< Specifies the number of data bytes to be transferred. */
+ 
+  uint32_t SDIO_DataBlockSize;  /*!< Specifies the data block size for block transfer.
+                                     This parameter can be a value of @ref SDIO_Data_Block_Size */
+ 
+  uint32_t SDIO_TransferDir;    /*!< Specifies the data transfer direction, whether the transfer
+                                     is a read or write.
+                                     This parameter can be a value of @ref SDIO_Transfer_Direction */
+ 
+  uint32_t SDIO_TransferMode;   /*!< Specifies whether data transfer is in stream or block mode.
+                                     This parameter can be a value of @ref SDIO_Transfer_Type */
+ 
+  uint32_t SDIO_DPSM;           /*!< Specifies whether SDIO Data path state machine (DPSM)
+                                     is enabled or disabled.
+                                     This parameter can be a value of @ref SDIO_DPSM_State */
+} SDIO_DataInitTypeDef;
+
+/**
+  * @}
+  */ 
+
+/** @defgroup SDIO_Exported_Constants
+  * @{
+  */
+
+/** @defgroup SDIO_Clock_Edge 
+  * @{
+  */
+
+#define SDIO_ClockEdge_Rising               ((uint32_t)0x00000000)
+#define SDIO_ClockEdge_Falling              ((uint32_t)0x00002000)
+#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \
+                                  ((EDGE) == SDIO_ClockEdge_Falling))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Clock_Bypass 
+  * @{
+  */
+
+#define SDIO_ClockBypass_Disable             ((uint32_t)0x00000000)
+#define SDIO_ClockBypass_Enable              ((uint32_t)0x00000400)    
+#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \
+                                     ((BYPASS) == SDIO_ClockBypass_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup SDIO_Clock_Power_Save 
+  * @{
+  */
+
+#define SDIO_ClockPowerSave_Disable         ((uint32_t)0x00000000)
+#define SDIO_ClockPowerSave_Enable          ((uint32_t)0x00000200) 
+#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \
+                                        ((SAVE) == SDIO_ClockPowerSave_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Bus_Wide 
+  * @{
+  */
+
+#define SDIO_BusWide_1b                     ((uint32_t)0x00000000)
+#define SDIO_BusWide_4b                     ((uint32_t)0x00000800)
+#define SDIO_BusWide_8b                     ((uint32_t)0x00001000)
+#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \
+                                ((WIDE) == SDIO_BusWide_8b))
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Hardware_Flow_Control 
+  * @{
+  */
+
+#define SDIO_HardwareFlowControl_Disable    ((uint32_t)0x00000000)
+#define SDIO_HardwareFlowControl_Enable     ((uint32_t)0x00004000)
+#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \
+                                                ((CONTROL) == SDIO_HardwareFlowControl_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Power_State 
+  * @{
+  */
+
+#define SDIO_PowerState_OFF                 ((uint32_t)0x00000000)
+#define SDIO_PowerState_ON                  ((uint32_t)0x00000003)
+#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON)) 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup SDIO_Interrupt_soucres 
+  * @{
+  */
+
+#define SDIO_IT_CCRCFAIL                    ((uint32_t)0x00000001)
+#define SDIO_IT_DCRCFAIL                    ((uint32_t)0x00000002)
+#define SDIO_IT_CTIMEOUT                    ((uint32_t)0x00000004)
+#define SDIO_IT_DTIMEOUT                    ((uint32_t)0x00000008)
+#define SDIO_IT_TXUNDERR                    ((uint32_t)0x00000010)
+#define SDIO_IT_RXOVERR                     ((uint32_t)0x00000020)
+#define SDIO_IT_CMDREND                     ((uint32_t)0x00000040)
+#define SDIO_IT_CMDSENT                     ((uint32_t)0x00000080)
+#define SDIO_IT_DATAEND                     ((uint32_t)0x00000100)
+#define SDIO_IT_STBITERR                    ((uint32_t)0x00000200)
+#define SDIO_IT_DBCKEND                     ((uint32_t)0x00000400)
+#define SDIO_IT_CMDACT                      ((uint32_t)0x00000800)
+#define SDIO_IT_TXACT                       ((uint32_t)0x00001000)
+#define SDIO_IT_RXACT                       ((uint32_t)0x00002000)
+#define SDIO_IT_TXFIFOHE                    ((uint32_t)0x00004000)
+#define SDIO_IT_RXFIFOHF                    ((uint32_t)0x00008000)
+#define SDIO_IT_TXFIFOF                     ((uint32_t)0x00010000)
+#define SDIO_IT_RXFIFOF                     ((uint32_t)0x00020000)
+#define SDIO_IT_TXFIFOE                     ((uint32_t)0x00040000)
+#define SDIO_IT_RXFIFOE                     ((uint32_t)0x00080000)
+#define SDIO_IT_TXDAVL                      ((uint32_t)0x00100000)
+#define SDIO_IT_RXDAVL                      ((uint32_t)0x00200000)
+#define SDIO_IT_SDIOIT                      ((uint32_t)0x00400000)
+#define SDIO_IT_CEATAEND                    ((uint32_t)0x00800000)
+#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup SDIO_Command_Index
+  * @{
+  */
+
+#define IS_SDIO_CMD_INDEX(INDEX)            ((INDEX) < 0x40)
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Response_Type 
+  * @{
+  */
+
+#define SDIO_Response_No                    ((uint32_t)0x00000000)
+#define SDIO_Response_Short                 ((uint32_t)0x00000040)
+#define SDIO_Response_Long                  ((uint32_t)0x000000C0)
+#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \
+                                    ((RESPONSE) == SDIO_Response_Short) || \
+                                    ((RESPONSE) == SDIO_Response_Long))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Wait_Interrupt_State 
+  * @{
+  */
+
+#define SDIO_Wait_No                        ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */
+#define SDIO_Wait_IT                        ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */
+#define SDIO_Wait_Pend                      ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */
+#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \
+                            ((WAIT) == SDIO_Wait_Pend))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_CPSM_State 
+  * @{
+  */
+
+#define SDIO_CPSM_Disable                    ((uint32_t)0x00000000)
+#define SDIO_CPSM_Enable                     ((uint32_t)0x00000400)
+#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup SDIO_Response_Registers 
+  * @{
+  */
+
+#define SDIO_RESP1                          ((uint32_t)0x00000000)
+#define SDIO_RESP2                          ((uint32_t)0x00000004)
+#define SDIO_RESP3                          ((uint32_t)0x00000008)
+#define SDIO_RESP4                          ((uint32_t)0x0000000C)
+#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \
+                            ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Data_Length 
+  * @{
+  */
+
+#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF)
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Data_Block_Size 
+  * @{
+  */
+
+#define SDIO_DataBlockSize_1b               ((uint32_t)0x00000000)
+#define SDIO_DataBlockSize_2b               ((uint32_t)0x00000010)
+#define SDIO_DataBlockSize_4b               ((uint32_t)0x00000020)
+#define SDIO_DataBlockSize_8b               ((uint32_t)0x00000030)
+#define SDIO_DataBlockSize_16b              ((uint32_t)0x00000040)
+#define SDIO_DataBlockSize_32b              ((uint32_t)0x00000050)
+#define SDIO_DataBlockSize_64b              ((uint32_t)0x00000060)
+#define SDIO_DataBlockSize_128b             ((uint32_t)0x00000070)
+#define SDIO_DataBlockSize_256b             ((uint32_t)0x00000080)
+#define SDIO_DataBlockSize_512b             ((uint32_t)0x00000090)
+#define SDIO_DataBlockSize_1024b            ((uint32_t)0x000000A0)
+#define SDIO_DataBlockSize_2048b            ((uint32_t)0x000000B0)
+#define SDIO_DataBlockSize_4096b            ((uint32_t)0x000000C0)
+#define SDIO_DataBlockSize_8192b            ((uint32_t)0x000000D0)
+#define SDIO_DataBlockSize_16384b           ((uint32_t)0x000000E0)
+#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_2b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_4b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_8b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_16b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_32b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_64b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_128b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_256b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_512b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_1024b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_2048b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_4096b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_8192b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_16384b)) 
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Transfer_Direction 
+  * @{
+  */
+
+#define SDIO_TransferDir_ToCard             ((uint32_t)0x00000000)
+#define SDIO_TransferDir_ToSDIO             ((uint32_t)0x00000002)
+#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \
+                                   ((DIR) == SDIO_TransferDir_ToSDIO))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Transfer_Type 
+  * @{
+  */
+
+#define SDIO_TransferMode_Block             ((uint32_t)0x00000000)
+#define SDIO_TransferMode_Stream            ((uint32_t)0x00000004)
+#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \
+                                     ((MODE) == SDIO_TransferMode_Block))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_DPSM_State 
+  * @{
+  */
+
+#define SDIO_DPSM_Disable                    ((uint32_t)0x00000000)
+#define SDIO_DPSM_Enable                     ((uint32_t)0x00000001)
+#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Flags 
+  * @{
+  */
+
+#define SDIO_FLAG_CCRCFAIL                  ((uint32_t)0x00000001)
+#define SDIO_FLAG_DCRCFAIL                  ((uint32_t)0x00000002)
+#define SDIO_FLAG_CTIMEOUT                  ((uint32_t)0x00000004)
+#define SDIO_FLAG_DTIMEOUT                  ((uint32_t)0x00000008)
+#define SDIO_FLAG_TXUNDERR                  ((uint32_t)0x00000010)
+#define SDIO_FLAG_RXOVERR                   ((uint32_t)0x00000020)
+#define SDIO_FLAG_CMDREND                   ((uint32_t)0x00000040)
+#define SDIO_FLAG_CMDSENT                   ((uint32_t)0x00000080)
+#define SDIO_FLAG_DATAEND                   ((uint32_t)0x00000100)
+#define SDIO_FLAG_STBITERR                  ((uint32_t)0x00000200)
+#define SDIO_FLAG_DBCKEND                   ((uint32_t)0x00000400)
+#define SDIO_FLAG_CMDACT                    ((uint32_t)0x00000800)
+#define SDIO_FLAG_TXACT                     ((uint32_t)0x00001000)
+#define SDIO_FLAG_RXACT                     ((uint32_t)0x00002000)
+#define SDIO_FLAG_TXFIFOHE                  ((uint32_t)0x00004000)
+#define SDIO_FLAG_RXFIFOHF                  ((uint32_t)0x00008000)
+#define SDIO_FLAG_TXFIFOF                   ((uint32_t)0x00010000)
+#define SDIO_FLAG_RXFIFOF                   ((uint32_t)0x00020000)
+#define SDIO_FLAG_TXFIFOE                   ((uint32_t)0x00040000)
+#define SDIO_FLAG_RXFIFOE                   ((uint32_t)0x00080000)
+#define SDIO_FLAG_TXDAVL                    ((uint32_t)0x00100000)
+#define SDIO_FLAG_RXDAVL                    ((uint32_t)0x00200000)
+#define SDIO_FLAG_SDIOIT                    ((uint32_t)0x00400000)
+#define SDIO_FLAG_CEATAEND                  ((uint32_t)0x00800000)
+#define IS_SDIO_FLAG(FLAG) (((FLAG)  == SDIO_FLAG_CCRCFAIL) || \
+                            ((FLAG)  == SDIO_FLAG_DCRCFAIL) || \
+                            ((FLAG)  == SDIO_FLAG_CTIMEOUT) || \
+                            ((FLAG)  == SDIO_FLAG_DTIMEOUT) || \
+                            ((FLAG)  == SDIO_FLAG_TXUNDERR) || \
+                            ((FLAG)  == SDIO_FLAG_RXOVERR) || \
+                            ((FLAG)  == SDIO_FLAG_CMDREND) || \
+                            ((FLAG)  == SDIO_FLAG_CMDSENT) || \
+                            ((FLAG)  == SDIO_FLAG_DATAEND) || \
+                            ((FLAG)  == SDIO_FLAG_STBITERR) || \
+                            ((FLAG)  == SDIO_FLAG_DBCKEND) || \
+                            ((FLAG)  == SDIO_FLAG_CMDACT) || \
+                            ((FLAG)  == SDIO_FLAG_TXACT) || \
+                            ((FLAG)  == SDIO_FLAG_RXACT) || \
+                            ((FLAG)  == SDIO_FLAG_TXFIFOHE) || \
+                            ((FLAG)  == SDIO_FLAG_RXFIFOHF) || \
+                            ((FLAG)  == SDIO_FLAG_TXFIFOF) || \
+                            ((FLAG)  == SDIO_FLAG_RXFIFOF) || \
+                            ((FLAG)  == SDIO_FLAG_TXFIFOE) || \
+                            ((FLAG)  == SDIO_FLAG_RXFIFOE) || \
+                            ((FLAG)  == SDIO_FLAG_TXDAVL) || \
+                            ((FLAG)  == SDIO_FLAG_RXDAVL) || \
+                            ((FLAG)  == SDIO_FLAG_SDIOIT) || \
+                            ((FLAG)  == SDIO_FLAG_CEATAEND))
+
+#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00))
+
+#define IS_SDIO_GET_IT(IT) (((IT)  == SDIO_IT_CCRCFAIL) || \
+                            ((IT)  == SDIO_IT_DCRCFAIL) || \
+                            ((IT)  == SDIO_IT_CTIMEOUT) || \
+                            ((IT)  == SDIO_IT_DTIMEOUT) || \
+                            ((IT)  == SDIO_IT_TXUNDERR) || \
+                            ((IT)  == SDIO_IT_RXOVERR) || \
+                            ((IT)  == SDIO_IT_CMDREND) || \
+                            ((IT)  == SDIO_IT_CMDSENT) || \
+                            ((IT)  == SDIO_IT_DATAEND) || \
+                            ((IT)  == SDIO_IT_STBITERR) || \
+                            ((IT)  == SDIO_IT_DBCKEND) || \
+                            ((IT)  == SDIO_IT_CMDACT) || \
+                            ((IT)  == SDIO_IT_TXACT) || \
+                            ((IT)  == SDIO_IT_RXACT) || \
+                            ((IT)  == SDIO_IT_TXFIFOHE) || \
+                            ((IT)  == SDIO_IT_RXFIFOHF) || \
+                            ((IT)  == SDIO_IT_TXFIFOF) || \
+                            ((IT)  == SDIO_IT_RXFIFOF) || \
+                            ((IT)  == SDIO_IT_TXFIFOE) || \
+                            ((IT)  == SDIO_IT_RXFIFOE) || \
+                            ((IT)  == SDIO_IT_TXDAVL) || \
+                            ((IT)  == SDIO_IT_RXDAVL) || \
+                            ((IT)  == SDIO_IT_SDIOIT) || \
+                            ((IT)  == SDIO_IT_CEATAEND))
+
+#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00))
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Read_Wait_Mode 
+  * @{
+  */
+
+#define SDIO_ReadWaitMode_CLK               ((uint32_t)0x00000000)
+#define SDIO_ReadWaitMode_DATA2             ((uint32_t)0x00000001)
+#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \
+                                     ((MODE) == SDIO_ReadWaitMode_DATA2))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Exported_Functions
+  * @{
+  */
+
+void SDIO_DeInit(void);
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_ClockCmd(FunctionalState NewState);
+void SDIO_SetPowerState(uint32_t SDIO_PowerState);
+uint32_t SDIO_GetPowerState(void);
+void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState);
+void SDIO_DMACmd(FunctionalState NewState);
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct);
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct);
+uint8_t SDIO_GetCommandResponse(void);
+uint32_t SDIO_GetResponse(uint32_t SDIO_RESP);
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+uint32_t SDIO_GetDataCounter(void);
+uint32_t SDIO_ReadData(void);
+void SDIO_WriteData(uint32_t Data);
+uint32_t SDIO_GetFIFOCount(void);
+void SDIO_StartSDIOReadWait(FunctionalState NewState);
+void SDIO_StopSDIOReadWait(FunctionalState NewState);
+void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode);
+void SDIO_SetSDIOOperation(FunctionalState NewState);
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState);
+void SDIO_CommandCompletionCmd(FunctionalState NewState);
+void SDIO_CEATAITCmd(FunctionalState NewState);
+void SDIO_SendCEATACmd(FunctionalState NewState);
+FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG);
+void SDIO_ClearFlag(uint32_t SDIO_FLAG);
+ITStatus SDIO_GetITStatus(uint32_t SDIO_IT);
+void SDIO_ClearITPendingBit(uint32_t SDIO_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_SDIO_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h
new file mode 100644
index 0000000000000000000000000000000000000000..36fd845326568c526c46c54a204fe2e67601fd01
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h
@@ -0,0 +1,490 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_spi.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the SPI firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_SPI_H
+#define __STM32F10x_SPI_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup SPI
+  * @{
+  */ 
+
+/** @defgroup SPI_Exported_Types
+  * @{
+  */
+
+/** 
+  * @brief  SPI Init structure definition  
+  */
+
+typedef struct
+{
+  uint16_t SPI_Direction;           /*!< Specifies the SPI unidirectional or bidirectional data mode.
+                                         This parameter can be any combination of @ref SPI_data_direction */
+
+  uint16_t SPI_Mode;                /*!< Specifies the SPI operating mode.
+                                         This parameter can be any combination of @ref SPI_mode */
+
+  uint16_t SPI_DataSize;            /*!< Specifies the SPI data size.
+                                         This parameter can be any combination of @ref SPI_data_size */
+
+  uint16_t SPI_CPOL;                /*!< Specifies the serial clock steady state.
+                                         This parameter can be any combination of @ref SPI_Clock_Polarity */
+
+  uint16_t SPI_CPHA;                /*!< Specifies the clock active edge for the bit capture.
+                                         This parameter can be any combination of @ref SPI_Clock_Phase */
+
+  uint16_t SPI_NSS;                 /*!< Specifies whether the NSS signal is managed by
+                                         hardware (NSS pin) or by software using the SSI bit.
+                                         This parameter can be any combination of @ref SPI_Slave_Select_management */
+ 
+  uint16_t SPI_BaudRatePrescaler;   /*!< Specifies the Baud Rate prescaler value which will be
+                                         used to configure the transmit and receive SCK clock.
+                                         This parameter can be any combination of @ref SPI_BaudRate_Prescaler.
+                                         @note The communication clock is derived from the master
+                                               clock. The slave clock does not need to be set. */
+
+  uint16_t SPI_FirstBit;            /*!< Specifies whether data transfers start from MSB or LSB bit.
+                                         This parameter can be any combination of @ref SPI_MSB_LSB_transmission */
+
+  uint16_t SPI_CRCPolynomial;       /*!< Specifies the polynomial used for the CRC calculation. */
+}SPI_InitTypeDef;
+
+/** 
+  * @brief  I2S Init structure definition  
+  */
+
+typedef struct
+{
+
+  uint16_t I2S_Mode;         /*!< Specifies the I2S operating mode.
+                                  This parameter can be any combination of @ref I2S_Mode */
+
+  uint16_t I2S_Standard;     /*!< Specifies the standard used for the I2S communication.
+                                  This parameter can be any combination of @ref I2S_Standard */
+
+  uint16_t I2S_DataFormat;   /*!< Specifies the data format for the I2S communication.
+                                  This parameter can be any combination of @ref I2S_Data_Format */
+
+  uint16_t I2S_MCLKOutput;   /*!< Specifies whether the I2S MCLK output is enabled or not.
+                                  This parameter can be any combination of @ref I2S_MCLK_Output */
+
+  uint32_t I2S_AudioFreq;    /*!< Specifies the frequency selected for the I2S communication.
+                                  This parameter can be any combination of @ref I2S_Audio_Frequency */
+
+  uint16_t I2S_CPOL;         /*!< Specifies the idle state of the I2S clock.
+                                  This parameter can be any combination of @ref I2S_Clock_Polarity */
+}I2S_InitTypeDef;
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Exported_Constants
+  * @{
+  */
+
+#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \
+                                   ((PERIPH) == SPI2) || \
+                                   ((PERIPH) == SPI3))
+
+#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \
+                                  ((PERIPH) == SPI3))
+
+/** @defgroup SPI_data_direction 
+  * @{
+  */
+  
+#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000)
+#define SPI_Direction_2Lines_RxOnly     ((uint16_t)0x0400)
+#define SPI_Direction_1Line_Rx          ((uint16_t)0x8000)
+#define SPI_Direction_1Line_Tx          ((uint16_t)0xC000)
+#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \
+                                     ((MODE) == SPI_Direction_2Lines_RxOnly) || \
+                                     ((MODE) == SPI_Direction_1Line_Rx) || \
+                                     ((MODE) == SPI_Direction_1Line_Tx))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_mode 
+  * @{
+  */
+
+#define SPI_Mode_Master                 ((uint16_t)0x0104)
+#define SPI_Mode_Slave                  ((uint16_t)0x0000)
+#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \
+                           ((MODE) == SPI_Mode_Slave))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_data_size 
+  * @{
+  */
+
+#define SPI_DataSize_16b                ((uint16_t)0x0800)
+#define SPI_DataSize_8b                 ((uint16_t)0x0000)
+#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \
+                                   ((DATASIZE) == SPI_DataSize_8b))
+/**
+  * @}
+  */ 
+
+/** @defgroup SPI_Clock_Polarity 
+  * @{
+  */
+
+#define SPI_CPOL_Low                    ((uint16_t)0x0000)
+#define SPI_CPOL_High                   ((uint16_t)0x0002)
+#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \
+                           ((CPOL) == SPI_CPOL_High))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Clock_Phase 
+  * @{
+  */
+
+#define SPI_CPHA_1Edge                  ((uint16_t)0x0000)
+#define SPI_CPHA_2Edge                  ((uint16_t)0x0001)
+#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \
+                           ((CPHA) == SPI_CPHA_2Edge))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Slave_Select_management 
+  * @{
+  */
+
+#define SPI_NSS_Soft                    ((uint16_t)0x0200)
+#define SPI_NSS_Hard                    ((uint16_t)0x0000)
+#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \
+                         ((NSS) == SPI_NSS_Hard))
+/**
+  * @}
+  */ 
+
+/** @defgroup SPI_BaudRate_Prescaler 
+  * @{
+  */
+
+#define SPI_BaudRatePrescaler_2         ((uint16_t)0x0000)
+#define SPI_BaudRatePrescaler_4         ((uint16_t)0x0008)
+#define SPI_BaudRatePrescaler_8         ((uint16_t)0x0010)
+#define SPI_BaudRatePrescaler_16        ((uint16_t)0x0018)
+#define SPI_BaudRatePrescaler_32        ((uint16_t)0x0020)
+#define SPI_BaudRatePrescaler_64        ((uint16_t)0x0028)
+#define SPI_BaudRatePrescaler_128       ((uint16_t)0x0030)
+#define SPI_BaudRatePrescaler_256       ((uint16_t)0x0038)
+#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_4) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_8) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_16) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_32) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_64) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_128) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_256))
+/**
+  * @}
+  */ 
+
+/** @defgroup SPI_MSB_LSB_transmission 
+  * @{
+  */
+
+#define SPI_FirstBit_MSB                ((uint16_t)0x0000)
+#define SPI_FirstBit_LSB                ((uint16_t)0x0080)
+#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \
+                               ((BIT) == SPI_FirstBit_LSB))
+/**
+  * @}
+  */
+
+/** @defgroup I2S_Mode 
+  * @{
+  */
+
+#define I2S_Mode_SlaveTx                ((uint16_t)0x0000)
+#define I2S_Mode_SlaveRx                ((uint16_t)0x0100)
+#define I2S_Mode_MasterTx               ((uint16_t)0x0200)
+#define I2S_Mode_MasterRx               ((uint16_t)0x0300)
+#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \
+                           ((MODE) == I2S_Mode_SlaveRx) || \
+                           ((MODE) == I2S_Mode_MasterTx) || \
+                           ((MODE) == I2S_Mode_MasterRx) )
+/**
+  * @}
+  */
+
+/** @defgroup I2S_Standard 
+  * @{
+  */
+
+#define I2S_Standard_Phillips           ((uint16_t)0x0000)
+#define I2S_Standard_MSB                ((uint16_t)0x0010)
+#define I2S_Standard_LSB                ((uint16_t)0x0020)
+#define I2S_Standard_PCMShort           ((uint16_t)0x0030)
+#define I2S_Standard_PCMLong            ((uint16_t)0x00B0)
+#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \
+                                   ((STANDARD) == I2S_Standard_MSB) || \
+                                   ((STANDARD) == I2S_Standard_LSB) || \
+                                   ((STANDARD) == I2S_Standard_PCMShort) || \
+                                   ((STANDARD) == I2S_Standard_PCMLong))
+/**
+  * @}
+  */
+
+/** @defgroup I2S_Data_Format 
+  * @{
+  */
+
+#define I2S_DataFormat_16b              ((uint16_t)0x0000)
+#define I2S_DataFormat_16bextended      ((uint16_t)0x0001)
+#define I2S_DataFormat_24b              ((uint16_t)0x0003)
+#define I2S_DataFormat_32b              ((uint16_t)0x0005)
+#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \
+                                    ((FORMAT) == I2S_DataFormat_16bextended) || \
+                                    ((FORMAT) == I2S_DataFormat_24b) || \
+                                    ((FORMAT) == I2S_DataFormat_32b))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2S_MCLK_Output 
+  * @{
+  */
+
+#define I2S_MCLKOutput_Enable           ((uint16_t)0x0200)
+#define I2S_MCLKOutput_Disable          ((uint16_t)0x0000)
+#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \
+                                    ((OUTPUT) == I2S_MCLKOutput_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup I2S_Audio_Frequency 
+  * @{
+  */
+
+#define I2S_AudioFreq_96k                ((uint32_t)96000)
+#define I2S_AudioFreq_48k                ((uint32_t)48000)
+#define I2S_AudioFreq_44k                ((uint32_t)44100)
+#define I2S_AudioFreq_32k                ((uint32_t)32000)
+#define I2S_AudioFreq_22k                ((uint32_t)22050)
+#define I2S_AudioFreq_16k                ((uint32_t)16000)
+#define I2S_AudioFreq_11k                ((uint32_t)11025)
+#define I2S_AudioFreq_8k                 ((uint32_t)8000)
+#define I2S_AudioFreq_Default            ((uint32_t)2)
+#define IS_I2S_AUDIO_FREQ(FREQ) (((FREQ) == I2S_AudioFreq_96k) || \
+                                 ((FREQ) == I2S_AudioFreq_48k) || \
+                                 ((FREQ) == I2S_AudioFreq_44k) || \
+                                 ((FREQ) == I2S_AudioFreq_32k) || \
+                                 ((FREQ) == I2S_AudioFreq_22k) || \
+                                 ((FREQ) == I2S_AudioFreq_16k) || \
+                                 ((FREQ) == I2S_AudioFreq_11k) || \
+                                 ((FREQ) == I2S_AudioFreq_8k)  || \
+                                 ((FREQ) == I2S_AudioFreq_Default))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2S_Clock_Polarity 
+  * @{
+  */
+
+#define I2S_CPOL_Low                    ((uint16_t)0x0000)
+#define I2S_CPOL_High                   ((uint16_t)0x0008)
+#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \
+                           ((CPOL) == I2S_CPOL_High))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_DMA_transfer_requests 
+  * @{
+  */
+
+#define SPI_I2S_DMAReq_Tx               ((uint16_t)0x0002)
+#define SPI_I2S_DMAReq_Rx               ((uint16_t)0x0001)
+#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_NSS_internal_software_mangement 
+  * @{
+  */
+
+#define SPI_NSSInternalSoft_Set         ((uint16_t)0x0100)
+#define SPI_NSSInternalSoft_Reset       ((uint16_t)0xFEFF)
+#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \
+                                       ((INTERNAL) == SPI_NSSInternalSoft_Reset))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_CRC_Transmit_Receive 
+  * @{
+  */
+
+#define SPI_CRC_Tx                      ((uint8_t)0x00)
+#define SPI_CRC_Rx                      ((uint8_t)0x01)
+#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_direction_transmit_receive 
+  * @{
+  */
+
+#define SPI_Direction_Rx                ((uint16_t)0xBFFF)
+#define SPI_Direction_Tx                ((uint16_t)0x4000)
+#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \
+                                     ((DIRECTION) == SPI_Direction_Tx))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_interrupts_definition 
+  * @{
+  */
+
+#define SPI_I2S_IT_TXE                  ((uint8_t)0x71)
+#define SPI_I2S_IT_RXNE                 ((uint8_t)0x60)
+#define SPI_I2S_IT_ERR                  ((uint8_t)0x50)
+#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \
+                                 ((IT) == SPI_I2S_IT_RXNE) || \
+                                 ((IT) == SPI_I2S_IT_ERR))
+#define SPI_I2S_IT_OVR                  ((uint8_t)0x56)
+#define SPI_IT_MODF                     ((uint8_t)0x55)
+#define SPI_IT_CRCERR                   ((uint8_t)0x54)
+#define I2S_IT_UDR                      ((uint8_t)0x53)
+#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR))
+#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \
+                               ((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \
+                               ((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_flags_definition 
+  * @{
+  */
+
+#define SPI_I2S_FLAG_RXNE               ((uint16_t)0x0001)
+#define SPI_I2S_FLAG_TXE                ((uint16_t)0x0002)
+#define I2S_FLAG_CHSIDE                 ((uint16_t)0x0004)
+#define I2S_FLAG_UDR                    ((uint16_t)0x0008)
+#define SPI_FLAG_CRCERR                 ((uint16_t)0x0010)
+#define SPI_FLAG_MODF                   ((uint16_t)0x0020)
+#define SPI_I2S_FLAG_OVR                ((uint16_t)0x0040)
+#define SPI_I2S_FLAG_BSY                ((uint16_t)0x0080)
+#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR))
+#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \
+                                   ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \
+                                   ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \
+                                   ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_CRC_polynomial 
+  * @{
+  */
+
+#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1)
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Exported_Functions
+  * @{
+  */
+
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx);
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct);
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct);
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct);
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct);
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState);
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState);
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data);
+uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx);
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft);
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize);
+void SPI_TransmitCRC(SPI_TypeDef* SPIx);
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState);
+uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC);
+uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx);
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction);
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_SPI_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h
new file mode 100644
index 0000000000000000000000000000000000000000..6fa30b0ed7f1edc5ecd4b58086c6139709b48ecb
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h
@@ -0,0 +1,1040 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_tim.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the TIM firmware 
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_TIM_H
+#define __STM32F10x_TIM_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup TIM
+  * @{
+  */ 
+
+/** @defgroup TIM_Exported_Types
+  * @{
+  */ 
+
+/** 
+  * @brief  TIM Time Base Init structure definition
+  * @note   This sturcture is used with all TIMx except for TIM6 and TIM7.    
+  */
+
+typedef struct
+{
+  uint16_t TIM_Prescaler;         /*!< Specifies the prescaler value used to divide the TIM clock.
+                                       This parameter can be a number between 0x0000 and 0xFFFF */
+
+  uint16_t TIM_CounterMode;       /*!< Specifies the counter mode.
+                                       This parameter can be a value of @ref TIM_Counter_Mode */
+
+  uint16_t TIM_Period;            /*!< Specifies the period value to be loaded into the active
+                                       Auto-Reload Register at the next update event.
+                                       This parameter must be a number between 0x0000 and 0xFFFF.  */ 
+
+  uint16_t TIM_ClockDivision;     /*!< Specifies the clock division.
+                                      This parameter can be a value of @ref TIM_Clock_Division_CKD */
+
+  uint8_t TIM_RepetitionCounter;  /*!< Specifies the repetition counter value. Each time the RCR downcounter
+                                       reaches zero, an update event is generated and counting restarts
+                                       from the RCR value (N).
+                                       This means in PWM mode that (N+1) corresponds to:
+                                          - the number of PWM periods in edge-aligned mode
+                                          - the number of half PWM period in center-aligned mode
+                                       This parameter must be a number between 0x00 and 0xFF. 
+                                       @note This parameter is valid only for TIM1 and TIM8. */
+} TIM_TimeBaseInitTypeDef;       
+
+/** 
+  * @brief  TIM Output Compare Init structure definition  
+  */
+
+typedef struct
+{
+  uint16_t TIM_OCMode;        /*!< Specifies the TIM mode.
+                                   This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */
+
+  uint16_t TIM_OutputState;   /*!< Specifies the TIM Output Compare state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_state */
+
+  uint16_t TIM_OutputNState;  /*!< Specifies the TIM complementary Output Compare state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_N_state
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+
+  uint16_t TIM_Pulse;         /*!< Specifies the pulse value to be loaded into the Capture Compare Register. 
+                                   This parameter can be a number between 0x0000 and 0xFFFF */
+
+  uint16_t TIM_OCPolarity;    /*!< Specifies the output polarity.
+                                   This parameter can be a value of @ref TIM_Output_Compare_Polarity */
+
+  uint16_t TIM_OCNPolarity;   /*!< Specifies the complementary output polarity.
+                                   This parameter can be a value of @ref TIM_Output_Compare_N_Polarity
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+
+  uint16_t TIM_OCIdleState;   /*!< Specifies the TIM Output Compare pin state during Idle state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_Idle_State
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+
+  uint16_t TIM_OCNIdleState;  /*!< Specifies the TIM Output Compare pin state during Idle state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+} TIM_OCInitTypeDef;
+
+/** 
+  * @brief  TIM Input Capture Init structure definition  
+  */
+
+typedef struct
+{
+
+  uint16_t TIM_Channel;      /*!< Specifies the TIM channel.
+                                  This parameter can be a value of @ref TIM_Channel */
+
+  uint16_t TIM_ICPolarity;   /*!< Specifies the active edge of the input signal.
+                                  This parameter can be a value of @ref TIM_Input_Capture_Polarity */
+
+  uint16_t TIM_ICSelection;  /*!< Specifies the input.
+                                  This parameter can be a value of @ref TIM_Input_Capture_Selection */
+
+  uint16_t TIM_ICPrescaler;  /*!< Specifies the Input Capture Prescaler.
+                                  This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
+
+  uint16_t TIM_ICFilter;     /*!< Specifies the input capture filter.
+                                  This parameter can be a number between 0x0 and 0xF */
+} TIM_ICInitTypeDef;
+
+/** 
+  * @brief  BDTR structure definition 
+  * @note   This sturcture is used only with TIM1 and TIM8.    
+  */
+
+typedef struct
+{
+
+  uint16_t TIM_OSSRState;        /*!< Specifies the Off-State selection used in Run mode.
+                                      This parameter can be a value of @ref OSSR_Off_State_Selection_for_Run_mode_state */
+
+  uint16_t TIM_OSSIState;        /*!< Specifies the Off-State used in Idle state.
+                                      This parameter can be a value of @ref OSSI_Off_State_Selection_for_Idle_mode_state */
+
+  uint16_t TIM_LOCKLevel;        /*!< Specifies the LOCK level parameters.
+                                      This parameter can be a value of @ref Lock_level */ 
+
+  uint16_t TIM_DeadTime;         /*!< Specifies the delay time between the switching-off and the
+                                      switching-on of the outputs.
+                                      This parameter can be a number between 0x00 and 0xFF  */
+
+  uint16_t TIM_Break;            /*!< Specifies whether the TIM Break input is enabled or not. 
+                                      This parameter can be a value of @ref Break_Input_enable_disable */
+
+  uint16_t TIM_BreakPolarity;    /*!< Specifies the TIM Break Input pin polarity.
+                                      This parameter can be a value of @ref Break_Polarity */
+
+  uint16_t TIM_AutomaticOutput;  /*!< Specifies whether the TIM Automatic Output feature is enabled or not. 
+                                      This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */
+} TIM_BDTRInitTypeDef;
+
+/** @defgroup TIM_Exported_constants 
+  * @{
+  */
+
+#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                   ((PERIPH) == TIM2) || \
+                                   ((PERIPH) == TIM3) || \
+                                   ((PERIPH) == TIM4) || \
+                                   ((PERIPH) == TIM5) || \
+                                   ((PERIPH) == TIM6) || \
+                                   ((PERIPH) == TIM7) || \
+                                   ((PERIPH) == TIM8))
+
+#define IS_TIM_18_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                  ((PERIPH) == TIM8))
+
+#define IS_TIM_123458_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                      ((PERIPH) == TIM2) || \
+                                      ((PERIPH) == TIM3) || \
+                                      ((PERIPH) == TIM4) || \
+                                      ((PERIPH) == TIM5) || \
+                                      ((PERIPH) == TIM8))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_and_PWM_modes 
+  * @{
+  */
+
+#define TIM_OCMode_Timing                  ((uint16_t)0x0000)
+#define TIM_OCMode_Active                  ((uint16_t)0x0010)
+#define TIM_OCMode_Inactive                ((uint16_t)0x0020)
+#define TIM_OCMode_Toggle                  ((uint16_t)0x0030)
+#define TIM_OCMode_PWM1                    ((uint16_t)0x0060)
+#define TIM_OCMode_PWM2                    ((uint16_t)0x0070)
+#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \
+                              ((MODE) == TIM_OCMode_Active) || \
+                              ((MODE) == TIM_OCMode_Inactive) || \
+                              ((MODE) == TIM_OCMode_Toggle)|| \
+                              ((MODE) == TIM_OCMode_PWM1) || \
+                              ((MODE) == TIM_OCMode_PWM2))
+#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \
+                          ((MODE) == TIM_OCMode_Active) || \
+                          ((MODE) == TIM_OCMode_Inactive) || \
+                          ((MODE) == TIM_OCMode_Toggle)|| \
+                          ((MODE) == TIM_OCMode_PWM1) || \
+                          ((MODE) == TIM_OCMode_PWM2) ||	\
+                          ((MODE) == TIM_ForcedAction_Active) || \
+                          ((MODE) == TIM_ForcedAction_InActive))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_One_Pulse_Mode 
+  * @{
+  */
+
+#define TIM_OPMode_Single                  ((uint16_t)0x0008)
+#define TIM_OPMode_Repetitive              ((uint16_t)0x0000)
+#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \
+                               ((MODE) == TIM_OPMode_Repetitive))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Channel 
+  * @{
+  */
+
+#define TIM_Channel_1                      ((uint16_t)0x0000)
+#define TIM_Channel_2                      ((uint16_t)0x0004)
+#define TIM_Channel_3                      ((uint16_t)0x0008)
+#define TIM_Channel_4                      ((uint16_t)0x000C)
+#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+                                 ((CHANNEL) == TIM_Channel_2) || \
+                                 ((CHANNEL) == TIM_Channel_3) || \
+                                 ((CHANNEL) == TIM_Channel_4))
+#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+                                      ((CHANNEL) == TIM_Channel_2))
+#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+                                               ((CHANNEL) == TIM_Channel_2) || \
+                                               ((CHANNEL) == TIM_Channel_3))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Clock_Division_CKD 
+  * @{
+  */
+
+#define TIM_CKD_DIV1                       ((uint16_t)0x0000)
+#define TIM_CKD_DIV2                       ((uint16_t)0x0100)
+#define TIM_CKD_DIV4                       ((uint16_t)0x0200)
+#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \
+                             ((DIV) == TIM_CKD_DIV2) || \
+                             ((DIV) == TIM_CKD_DIV4))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Counter_Mode 
+  * @{
+  */
+
+#define TIM_CounterMode_Up                 ((uint16_t)0x0000)
+#define TIM_CounterMode_Down               ((uint16_t)0x0010)
+#define TIM_CounterMode_CenterAligned1     ((uint16_t)0x0020)
+#define TIM_CounterMode_CenterAligned2     ((uint16_t)0x0040)
+#define TIM_CounterMode_CenterAligned3     ((uint16_t)0x0060)
+#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) ||  \
+                                   ((MODE) == TIM_CounterMode_Down) || \
+                                   ((MODE) == TIM_CounterMode_CenterAligned1) || \
+                                   ((MODE) == TIM_CounterMode_CenterAligned2) || \
+                                   ((MODE) == TIM_CounterMode_CenterAligned3))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_Polarity 
+  * @{
+  */
+
+#define TIM_OCPolarity_High                ((uint16_t)0x0000)
+#define TIM_OCPolarity_Low                 ((uint16_t)0x0002)
+#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \
+                                      ((POLARITY) == TIM_OCPolarity_Low))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Output_Compare_N_Polarity 
+  * @{
+  */
+  
+#define TIM_OCNPolarity_High               ((uint16_t)0x0000)
+#define TIM_OCNPolarity_Low                ((uint16_t)0x0008)
+#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \
+                                       ((POLARITY) == TIM_OCNPolarity_Low))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Output_Compare_state 
+  * @{
+  */
+
+#define TIM_OutputState_Disable            ((uint16_t)0x0000)
+#define TIM_OutputState_Enable             ((uint16_t)0x0001)
+#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \
+                                    ((STATE) == TIM_OutputState_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_N_state 
+  * @{
+  */
+
+#define TIM_OutputNState_Disable           ((uint16_t)0x0000)
+#define TIM_OutputNState_Enable            ((uint16_t)0x0004)
+#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \
+                                     ((STATE) == TIM_OutputNState_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Capture_Compare_state 
+  * @{
+  */
+
+#define TIM_CCx_Enable                      ((uint16_t)0x0001)
+#define TIM_CCx_Disable                     ((uint16_t)0x0000)
+#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \
+                         ((CCX) == TIM_CCx_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Capture_Compare_N_state 
+  * @{
+  */
+
+#define TIM_CCxN_Enable                     ((uint16_t)0x0004)
+#define TIM_CCxN_Disable                    ((uint16_t)0x0000)
+#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \
+                           ((CCXN) == TIM_CCxN_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup Break_Input_enable_disable 
+  * @{
+  */
+
+#define TIM_Break_Enable                   ((uint16_t)0x1000)
+#define TIM_Break_Disable                  ((uint16_t)0x0000)
+#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \
+                                   ((STATE) == TIM_Break_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup Break_Polarity 
+  * @{
+  */
+
+#define TIM_BreakPolarity_Low              ((uint16_t)0x0000)
+#define TIM_BreakPolarity_High             ((uint16_t)0x2000)
+#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \
+                                         ((POLARITY) == TIM_BreakPolarity_High))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_AOE_Bit_Set_Reset 
+  * @{
+  */
+
+#define TIM_AutomaticOutput_Enable         ((uint16_t)0x4000)
+#define TIM_AutomaticOutput_Disable        ((uint16_t)0x0000)
+#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \
+                                              ((STATE) == TIM_AutomaticOutput_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup Lock_level 
+  * @{
+  */
+
+#define TIM_LOCKLevel_OFF                  ((uint16_t)0x0000)
+#define TIM_LOCKLevel_1                    ((uint16_t)0x0100)
+#define TIM_LOCKLevel_2                    ((uint16_t)0x0200)
+#define TIM_LOCKLevel_3                    ((uint16_t)0x0300)
+#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \
+                                  ((LEVEL) == TIM_LOCKLevel_1) || \
+                                  ((LEVEL) == TIM_LOCKLevel_2) || \
+                                  ((LEVEL) == TIM_LOCKLevel_3))
+/**
+  * @}
+  */ 
+
+/** @defgroup OSSI_Off_State_Selection_for_Idle_mode_state 
+  * @{
+  */
+
+#define TIM_OSSIState_Enable               ((uint16_t)0x0400)
+#define TIM_OSSIState_Disable              ((uint16_t)0x0000)
+#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \
+                                  ((STATE) == TIM_OSSIState_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup OSSR_Off_State_Selection_for_Run_mode_state 
+  * @{
+  */
+
+#define TIM_OSSRState_Enable               ((uint16_t)0x0800)
+#define TIM_OSSRState_Disable              ((uint16_t)0x0000)
+#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \
+                                  ((STATE) == TIM_OSSRState_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_Idle_State 
+  * @{
+  */
+
+#define TIM_OCIdleState_Set                ((uint16_t)0x0100)
+#define TIM_OCIdleState_Reset              ((uint16_t)0x0000)
+#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \
+                                    ((STATE) == TIM_OCIdleState_Reset))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_N_Idle_State 
+  * @{
+  */
+
+#define TIM_OCNIdleState_Set               ((uint16_t)0x0200)
+#define TIM_OCNIdleState_Reset             ((uint16_t)0x0000)
+#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \
+                                     ((STATE) == TIM_OCNIdleState_Reset))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Polarity 
+  * @{
+  */
+
+#define  TIM_ICPolarity_Rising             ((uint16_t)0x0000)
+#define  TIM_ICPolarity_Falling            ((uint16_t)0x0002)
+#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \
+                                      ((POLARITY) == TIM_ICPolarity_Falling))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Selection 
+  * @{
+  */
+
+#define TIM_ICSelection_DirectTI           ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be 
+                                                                   connected to IC1, IC2, IC3 or IC4, respectively */
+#define TIM_ICSelection_IndirectTI         ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be
+                                                                   connected to IC2, IC1, IC4 or IC3, respectively. */
+#define TIM_ICSelection_TRC                ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */
+#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \
+                                        ((SELECTION) == TIM_ICSelection_IndirectTI) || \
+                                        ((SELECTION) == TIM_ICSelection_TRC))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Prescaler 
+  * @{
+  */
+
+#define TIM_ICPSC_DIV1                     ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */
+#define TIM_ICPSC_DIV2                     ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */
+#define TIM_ICPSC_DIV4                     ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */
+#define TIM_ICPSC_DIV8                     ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */
+#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \
+                                        ((PRESCALER) == TIM_ICPSC_DIV2) || \
+                                        ((PRESCALER) == TIM_ICPSC_DIV4) || \
+                                        ((PRESCALER) == TIM_ICPSC_DIV8))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_interrupt_sources 
+  * @{
+  */
+
+#define TIM_IT_Update                      ((uint16_t)0x0001)
+#define TIM_IT_CC1                         ((uint16_t)0x0002)
+#define TIM_IT_CC2                         ((uint16_t)0x0004)
+#define TIM_IT_CC3                         ((uint16_t)0x0008)
+#define TIM_IT_CC4                         ((uint16_t)0x0010)
+#define TIM_IT_COM                         ((uint16_t)0x0020)
+#define TIM_IT_Trigger                     ((uint16_t)0x0040)
+#define TIM_IT_Break                       ((uint16_t)0x0080)
+#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000))
+
+#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \
+                           ((IT) == TIM_IT_CC1) || \
+                           ((IT) == TIM_IT_CC2) || \
+                           ((IT) == TIM_IT_CC3) || \
+                           ((IT) == TIM_IT_CC4) || \
+                           ((IT) == TIM_IT_COM) || \
+                           ((IT) == TIM_IT_Trigger) || \
+                           ((IT) == TIM_IT_Break))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_DMA_Base_address 
+  * @{
+  */
+
+#define TIM_DMABase_CR1                    ((uint16_t)0x0000)
+#define TIM_DMABase_CR2                    ((uint16_t)0x0001)
+#define TIM_DMABase_SMCR                   ((uint16_t)0x0002)
+#define TIM_DMABase_DIER                   ((uint16_t)0x0003)
+#define TIM_DMABase_SR                     ((uint16_t)0x0004)
+#define TIM_DMABase_EGR                    ((uint16_t)0x0005)
+#define TIM_DMABase_CCMR1                  ((uint16_t)0x0006)
+#define TIM_DMABase_CCMR2                  ((uint16_t)0x0007)
+#define TIM_DMABase_CCER                   ((uint16_t)0x0008)
+#define TIM_DMABase_CNT                    ((uint16_t)0x0009)
+#define TIM_DMABase_PSC                    ((uint16_t)0x000A)
+#define TIM_DMABase_ARR                    ((uint16_t)0x000B)
+#define TIM_DMABase_RCR                    ((uint16_t)0x000C)
+#define TIM_DMABase_CCR1                   ((uint16_t)0x000D)
+#define TIM_DMABase_CCR2                   ((uint16_t)0x000E)
+#define TIM_DMABase_CCR3                   ((uint16_t)0x000F)
+#define TIM_DMABase_CCR4                   ((uint16_t)0x0010)
+#define TIM_DMABase_BDTR                   ((uint16_t)0x0011)
+#define TIM_DMABase_DCR                    ((uint16_t)0x0012)
+#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \
+                               ((BASE) == TIM_DMABase_CR2) || \
+                               ((BASE) == TIM_DMABase_SMCR) || \
+                               ((BASE) == TIM_DMABase_DIER) || \
+                               ((BASE) == TIM_DMABase_SR) || \
+                               ((BASE) == TIM_DMABase_EGR) || \
+                               ((BASE) == TIM_DMABase_CCMR1) || \
+                               ((BASE) == TIM_DMABase_CCMR2) || \
+                               ((BASE) == TIM_DMABase_CCER) || \
+                               ((BASE) == TIM_DMABase_CNT) || \
+                               ((BASE) == TIM_DMABase_PSC) || \
+                               ((BASE) == TIM_DMABase_ARR) || \
+                               ((BASE) == TIM_DMABase_RCR) || \
+                               ((BASE) == TIM_DMABase_CCR1) || \
+                               ((BASE) == TIM_DMABase_CCR2) || \
+                               ((BASE) == TIM_DMABase_CCR3) || \
+                               ((BASE) == TIM_DMABase_CCR4) || \
+                               ((BASE) == TIM_DMABase_BDTR) || \
+                               ((BASE) == TIM_DMABase_DCR))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_DMA_Burst_Length 
+  * @{
+  */
+
+#define TIM_DMABurstLength_1Byte           ((uint16_t)0x0000)
+#define TIM_DMABurstLength_2Bytes          ((uint16_t)0x0100)
+#define TIM_DMABurstLength_3Bytes          ((uint16_t)0x0200)
+#define TIM_DMABurstLength_4Bytes          ((uint16_t)0x0300)
+#define TIM_DMABurstLength_5Bytes          ((uint16_t)0x0400)
+#define TIM_DMABurstLength_6Bytes          ((uint16_t)0x0500)
+#define TIM_DMABurstLength_7Bytes          ((uint16_t)0x0600)
+#define TIM_DMABurstLength_8Bytes          ((uint16_t)0x0700)
+#define TIM_DMABurstLength_9Bytes          ((uint16_t)0x0800)
+#define TIM_DMABurstLength_10Bytes         ((uint16_t)0x0900)
+#define TIM_DMABurstLength_11Bytes         ((uint16_t)0x0A00)
+#define TIM_DMABurstLength_12Bytes         ((uint16_t)0x0B00)
+#define TIM_DMABurstLength_13Bytes         ((uint16_t)0x0C00)
+#define TIM_DMABurstLength_14Bytes         ((uint16_t)0x0D00)
+#define TIM_DMABurstLength_15Bytes         ((uint16_t)0x0E00)
+#define TIM_DMABurstLength_16Bytes         ((uint16_t)0x0F00)
+#define TIM_DMABurstLength_17Bytes         ((uint16_t)0x1000)
+#define TIM_DMABurstLength_18Bytes         ((uint16_t)0x1100)
+#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Byte) || \
+                                   ((LENGTH) == TIM_DMABurstLength_2Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_3Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_4Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_5Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_6Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_7Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_8Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_9Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_10Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_11Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_12Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_13Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_14Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_15Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_16Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_17Bytes) || \
+                                   ((LENGTH) == TIM_DMABurstLength_18Bytes))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_DMA_sources 
+  * @{
+  */
+
+#define TIM_DMA_Update                     ((uint16_t)0x0100)
+#define TIM_DMA_CC1                        ((uint16_t)0x0200)
+#define TIM_DMA_CC2                        ((uint16_t)0x0400)
+#define TIM_DMA_CC3                        ((uint16_t)0x0800)
+#define TIM_DMA_CC4                        ((uint16_t)0x1000)
+#define TIM_DMA_COM                        ((uint16_t)0x2000)
+#define TIM_DMA_Trigger                    ((uint16_t)0x4000)
+#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_External_Trigger_Prescaler 
+  * @{
+  */
+
+#define TIM_ExtTRGPSC_OFF                  ((uint16_t)0x0000)
+#define TIM_ExtTRGPSC_DIV2                 ((uint16_t)0x1000)
+#define TIM_ExtTRGPSC_DIV4                 ((uint16_t)0x2000)
+#define TIM_ExtTRGPSC_DIV8                 ((uint16_t)0x3000)
+#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \
+                                         ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \
+                                         ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \
+                                         ((PRESCALER) == TIM_ExtTRGPSC_DIV8))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Internal_Trigger_Selection 
+  * @{
+  */
+
+#define TIM_TS_ITR0                        ((uint16_t)0x0000)
+#define TIM_TS_ITR1                        ((uint16_t)0x0010)
+#define TIM_TS_ITR2                        ((uint16_t)0x0020)
+#define TIM_TS_ITR3                        ((uint16_t)0x0030)
+#define TIM_TS_TI1F_ED                     ((uint16_t)0x0040)
+#define TIM_TS_TI1FP1                      ((uint16_t)0x0050)
+#define TIM_TS_TI2FP2                      ((uint16_t)0x0060)
+#define TIM_TS_ETRF                        ((uint16_t)0x0070)
+#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+                                             ((SELECTION) == TIM_TS_ITR1) || \
+                                             ((SELECTION) == TIM_TS_ITR2) || \
+                                             ((SELECTION) == TIM_TS_ITR3) || \
+                                             ((SELECTION) == TIM_TS_TI1F_ED) || \
+                                             ((SELECTION) == TIM_TS_TI1FP1) || \
+                                             ((SELECTION) == TIM_TS_TI2FP2) || \
+                                             ((SELECTION) == TIM_TS_ETRF))
+#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+                                                      ((SELECTION) == TIM_TS_ITR1) || \
+                                                      ((SELECTION) == TIM_TS_ITR2) || \
+                                                      ((SELECTION) == TIM_TS_ITR3))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_TIx_External_Clock_Source 
+  * @{
+  */
+
+#define TIM_TIxExternalCLK1Source_TI1      ((uint16_t)0x0050)
+#define TIM_TIxExternalCLK1Source_TI2      ((uint16_t)0x0060)
+#define TIM_TIxExternalCLK1Source_TI1ED    ((uint16_t)0x0040)
+#define IS_TIM_TIXCLK_SOURCE(SOURCE) (((SOURCE) == TIM_TIxExternalCLK1Source_TI1) || \
+                                      ((SOURCE) == TIM_TIxExternalCLK1Source_TI2) || \
+                                      ((SOURCE) == TIM_TIxExternalCLK1Source_TI1ED))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_External_Trigger_Polarity 
+  * @{
+  */ 
+#define TIM_ExtTRGPolarity_Inverted        ((uint16_t)0x8000)
+#define TIM_ExtTRGPolarity_NonInverted     ((uint16_t)0x0000)
+#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \
+                                       ((POLARITY) == TIM_ExtTRGPolarity_NonInverted))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Prescaler_Reload_Mode 
+  * @{
+  */
+
+#define TIM_PSCReloadMode_Update           ((uint16_t)0x0000)
+#define TIM_PSCReloadMode_Immediate        ((uint16_t)0x0001)
+#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \
+                                         ((RELOAD) == TIM_PSCReloadMode_Immediate))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Forced_Action 
+  * @{
+  */
+
+#define TIM_ForcedAction_Active            ((uint16_t)0x0050)
+#define TIM_ForcedAction_InActive          ((uint16_t)0x0040)
+#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \
+                                      ((ACTION) == TIM_ForcedAction_InActive))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Encoder_Mode 
+  * @{
+  */
+
+#define TIM_EncoderMode_TI1                ((uint16_t)0x0001)
+#define TIM_EncoderMode_TI2                ((uint16_t)0x0002)
+#define TIM_EncoderMode_TI12               ((uint16_t)0x0003)
+#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \
+                                   ((MODE) == TIM_EncoderMode_TI2) || \
+                                   ((MODE) == TIM_EncoderMode_TI12))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup TIM_Event_Source 
+  * @{
+  */
+
+#define TIM_EventSource_Update             ((uint16_t)0x0001)
+#define TIM_EventSource_CC1                ((uint16_t)0x0002)
+#define TIM_EventSource_CC2                ((uint16_t)0x0004)
+#define TIM_EventSource_CC3                ((uint16_t)0x0008)
+#define TIM_EventSource_CC4                ((uint16_t)0x0010)
+#define TIM_EventSource_COM                ((uint16_t)0x0020)
+#define TIM_EventSource_Trigger            ((uint16_t)0x0040)
+#define TIM_EventSource_Break              ((uint16_t)0x0080)
+#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Update_Source 
+  * @{
+  */
+
+#define TIM_UpdateSource_Global            ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow
+                                                                   or the setting of UG bit, or an update generation
+                                                                   through the slave mode controller. */
+#define TIM_UpdateSource_Regular           ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */
+#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \
+                                      ((SOURCE) == TIM_UpdateSource_Regular))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Ouput_Compare_Preload_State 
+  * @{
+  */
+
+#define TIM_OCPreload_Enable               ((uint16_t)0x0008)
+#define TIM_OCPreload_Disable              ((uint16_t)0x0000)
+#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \
+                                       ((STATE) == TIM_OCPreload_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Ouput_Compare_Fast_State 
+  * @{
+  */
+
+#define TIM_OCFast_Enable                  ((uint16_t)0x0004)
+#define TIM_OCFast_Disable                 ((uint16_t)0x0000)
+#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \
+                                    ((STATE) == TIM_OCFast_Disable))
+                                     
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Ouput_Compare_Clear_State 
+  * @{
+  */
+
+#define TIM_OCClear_Enable                 ((uint16_t)0x0080)
+#define TIM_OCClear_Disable                ((uint16_t)0x0000)
+#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \
+                                     ((STATE) == TIM_OCClear_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Trigger_Output_Source 
+  * @{
+  */
+
+#define TIM_TRGOSource_Reset               ((uint16_t)0x0000)
+#define TIM_TRGOSource_Enable              ((uint16_t)0x0010)
+#define TIM_TRGOSource_Update              ((uint16_t)0x0020)
+#define TIM_TRGOSource_OC1                 ((uint16_t)0x0030)
+#define TIM_TRGOSource_OC1Ref              ((uint16_t)0x0040)
+#define TIM_TRGOSource_OC2Ref              ((uint16_t)0x0050)
+#define TIM_TRGOSource_OC3Ref              ((uint16_t)0x0060)
+#define TIM_TRGOSource_OC4Ref              ((uint16_t)0x0070)
+#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \
+                                    ((SOURCE) == TIM_TRGOSource_Enable) || \
+                                    ((SOURCE) == TIM_TRGOSource_Update) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC1) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC1Ref) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC2Ref) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC3Ref) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC4Ref))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Slave_Mode 
+  * @{
+  */
+
+#define TIM_SlaveMode_Reset                ((uint16_t)0x0004)
+#define TIM_SlaveMode_Gated                ((uint16_t)0x0005)
+#define TIM_SlaveMode_Trigger              ((uint16_t)0x0006)
+#define TIM_SlaveMode_External1            ((uint16_t)0x0007)
+#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \
+                                 ((MODE) == TIM_SlaveMode_Gated) || \
+                                 ((MODE) == TIM_SlaveMode_Trigger) || \
+                                 ((MODE) == TIM_SlaveMode_External1))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Master_Slave_Mode 
+  * @{
+  */
+
+#define TIM_MasterSlaveMode_Enable         ((uint16_t)0x0080)
+#define TIM_MasterSlaveMode_Disable        ((uint16_t)0x0000)
+#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \
+                                 ((STATE) == TIM_MasterSlaveMode_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Flags 
+  * @{
+  */
+
+#define TIM_FLAG_Update                    ((uint16_t)0x0001)
+#define TIM_FLAG_CC1                       ((uint16_t)0x0002)
+#define TIM_FLAG_CC2                       ((uint16_t)0x0004)
+#define TIM_FLAG_CC3                       ((uint16_t)0x0008)
+#define TIM_FLAG_CC4                       ((uint16_t)0x0010)
+#define TIM_FLAG_COM                       ((uint16_t)0x0020)
+#define TIM_FLAG_Trigger                   ((uint16_t)0x0040)
+#define TIM_FLAG_Break                     ((uint16_t)0x0080)
+#define TIM_FLAG_CC1OF                     ((uint16_t)0x0200)
+#define TIM_FLAG_CC2OF                     ((uint16_t)0x0400)
+#define TIM_FLAG_CC3OF                     ((uint16_t)0x0800)
+#define TIM_FLAG_CC4OF                     ((uint16_t)0x1000)
+#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \
+                               ((FLAG) == TIM_FLAG_CC1) || \
+                               ((FLAG) == TIM_FLAG_CC2) || \
+                               ((FLAG) == TIM_FLAG_CC3) || \
+                               ((FLAG) == TIM_FLAG_CC4) || \
+                               ((FLAG) == TIM_FLAG_COM) || \
+                               ((FLAG) == TIM_FLAG_Trigger) || \
+                               ((FLAG) == TIM_FLAG_Break) || \
+                               ((FLAG) == TIM_FLAG_CC1OF) || \
+                               ((FLAG) == TIM_FLAG_CC2OF) || \
+                               ((FLAG) == TIM_FLAG_CC3OF) || \
+                               ((FLAG) == TIM_FLAG_CC4OF))
+                               
+                               
+#define IS_TIM_CLEAR_FLAG(TIM_FLAG) ((((TIM_FLAG) & (uint16_t)0xE100) == 0x0000) && ((TIM_FLAG) != 0x0000))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Filer_Value 
+  * @{
+  */
+
+#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) 
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_External_Trigger_Filter 
+  * @{
+  */
+
+#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF)
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Exported_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Exported_Functions
+  * @{
+  */
+
+void TIM_DeInit(TIM_TypeDef* TIMx);
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct);
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct);
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState);
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource);
+void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength);
+void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState);
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx);
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource);
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource,
+                                uint16_t TIM_ICPolarity, uint16_t ICFilter);
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity,
+                             uint16_t ExtTRGFilter);
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, 
+                             uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter);
+void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity,
+                   uint16_t ExtTRGFilter);
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode);
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode);
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource);
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode,
+                                uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity);
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity);
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity);
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity);
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx);
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN);
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode);
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource);
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode);
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource);
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode);
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode);
+void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter);
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload);
+void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1);
+void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2);
+void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3);
+void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4);
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD);
+uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx);
+uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx);
+uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx);
+uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx);
+uint16_t TIM_GetCounter(TIM_TypeDef* TIMx);
+uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx);
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG);
+void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG);
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT);
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F10x_TIM_H */
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h
new file mode 100644
index 0000000000000000000000000000000000000000..2c3ae4c2b5870a5c1586c94020615deae58b2ea7
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h
@@ -0,0 +1,409 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_usart.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the USART 
+  *          firmware library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_USART_H
+#define __STM32F10x_USART_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup USART
+  * @{
+  */ 
+
+/** @defgroup USART_Exported_Types
+  * @{
+  */ 
+
+/** 
+  * @brief  USART Init Structure definition  
+  */ 
+  
+typedef struct
+{
+  uint32_t USART_BaudRate;            /*!< This member configures the USART communication baud rate.
+                                           The baud rate is computed using the following formula:
+                                            - IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate)))
+                                            - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 16) + 0.5 */
+
+  uint16_t USART_WordLength;          /*!< Specifies the number of data bits transmitted or received in a frame.
+                                           This parameter can be a value of @ref USART_Word_Length */
+
+  uint16_t USART_StopBits;            /*!< Specifies the number of stop bits transmitted.
+                                           This parameter can be a value of @ref USART_Stop_Bits */
+
+  uint16_t USART_Parity;              /*!< Specifies the parity mode.
+                                           This parameter can be a value of @ref USART_Parity
+                                           @note When parity is enabled, the computed parity is inserted
+                                                 at the MSB position of the transmitted data (9th bit when
+                                                 the word length is set to 9 data bits; 8th bit when the
+                                                 word length is set to 8 data bits). */
+ 
+  uint16_t USART_Mode;                /*!< Specifies wether the Receive or Transmit mode is enabled or disabled.
+                                           This parameter can be a value of @ref USART_Mode */
+
+  uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled
+                                           or disabled.
+                                           This parameter can be a value of @ref USART_Hardware_Flow_Control */
+} USART_InitTypeDef;
+
+/** 
+  * @brief  USART Clock Init Structure definition  
+  */ 
+  
+typedef struct
+{
+
+  uint16_t USART_Clock;   /*!< Specifies whether the USART clock is enabled or disabled.
+                               This parameter can be a value of @ref USART_Clock */
+
+  uint16_t USART_CPOL;    /*!< Specifies the steady state value of the serial clock.
+                               This parameter can be a value of @ref USART_Clock_Polarity */
+
+  uint16_t USART_CPHA;    /*!< Specifies the clock transition on which the bit capture is made.
+                               This parameter can be a value of @ref USART_Clock_Phase */
+
+  uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted
+                               data bit (MSB) has to be output on the SCLK pin in synchronous mode.
+                               This parameter can be a value of @ref USART_Last_Bit */
+} USART_ClockInitTypeDef;
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Exported_Constants
+  * @{
+  */ 
+  
+#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \
+                                     ((PERIPH) == USART2) || \
+                                     ((PERIPH) == USART3) || \
+                                     ((PERIPH) == UART4) || \
+                                     ((PERIPH) == UART5))
+
+#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \
+                                     ((PERIPH) == USART2) || \
+                                     ((PERIPH) == USART3))
+
+#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \
+                                      ((PERIPH) == USART2) || \
+                                      ((PERIPH) == USART3) || \
+                                      ((PERIPH) == UART4))
+/** @defgroup USART_Word_Length 
+  * @{
+  */ 
+  
+#define USART_WordLength_8b                  ((uint16_t)0x0000)
+#define USART_WordLength_9b                  ((uint16_t)0x1000)
+                                    
+#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \
+                                      ((LENGTH) == USART_WordLength_9b))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Stop_Bits 
+  * @{
+  */ 
+  
+#define USART_StopBits_1                     ((uint16_t)0x0000)
+#define USART_StopBits_0_5                   ((uint16_t)0x1000)
+#define USART_StopBits_2                     ((uint16_t)0x2000)
+#define USART_StopBits_1_5                   ((uint16_t)0x3000)
+#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \
+                                     ((STOPBITS) == USART_StopBits_0_5) || \
+                                     ((STOPBITS) == USART_StopBits_2) || \
+                                     ((STOPBITS) == USART_StopBits_1_5))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Parity 
+  * @{
+  */ 
+  
+#define USART_Parity_No                      ((uint16_t)0x0000)
+#define USART_Parity_Even                    ((uint16_t)0x0400)
+#define USART_Parity_Odd                     ((uint16_t)0x0600) 
+#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \
+                                 ((PARITY) == USART_Parity_Even) || \
+                                 ((PARITY) == USART_Parity_Odd))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Mode 
+  * @{
+  */ 
+  
+#define USART_Mode_Rx                        ((uint16_t)0x0004)
+#define USART_Mode_Tx                        ((uint16_t)0x0008)
+#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Hardware_Flow_Control 
+  * @{
+  */ 
+#define USART_HardwareFlowControl_None       ((uint16_t)0x0000)
+#define USART_HardwareFlowControl_RTS        ((uint16_t)0x0100)
+#define USART_HardwareFlowControl_CTS        ((uint16_t)0x0200)
+#define USART_HardwareFlowControl_RTS_CTS    ((uint16_t)0x0300)
+#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\
+                              (((CONTROL) == USART_HardwareFlowControl_None) || \
+                               ((CONTROL) == USART_HardwareFlowControl_RTS) || \
+                               ((CONTROL) == USART_HardwareFlowControl_CTS) || \
+                               ((CONTROL) == USART_HardwareFlowControl_RTS_CTS))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Clock 
+  * @{
+  */ 
+#define USART_Clock_Disable                  ((uint16_t)0x0000)
+#define USART_Clock_Enable                   ((uint16_t)0x0800)
+#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \
+                               ((CLOCK) == USART_Clock_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Clock_Polarity 
+  * @{
+  */
+  
+#define USART_CPOL_Low                       ((uint16_t)0x0000)
+#define USART_CPOL_High                      ((uint16_t)0x0400)
+#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Clock_Phase
+  * @{
+  */
+
+#define USART_CPHA_1Edge                     ((uint16_t)0x0000)
+#define USART_CPHA_2Edge                     ((uint16_t)0x0200)
+#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge))
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Last_Bit
+  * @{
+  */
+
+#define USART_LastBit_Disable                ((uint16_t)0x0000)
+#define USART_LastBit_Enable                 ((uint16_t)0x0100)
+#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \
+                                   ((LASTBIT) == USART_LastBit_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Interrupt_definition 
+  * @{
+  */
+  
+#define USART_IT_PE                          ((uint16_t)0x0028)
+#define USART_IT_TXE                         ((uint16_t)0x0727)
+#define USART_IT_TC                          ((uint16_t)0x0626)
+#define USART_IT_RXNE                        ((uint16_t)0x0525)
+#define USART_IT_IDLE                        ((uint16_t)0x0424)
+#define USART_IT_LBD                         ((uint16_t)0x0846)
+#define USART_IT_CTS                         ((uint16_t)0x096A)
+#define USART_IT_ERR                         ((uint16_t)0x0060)
+#define USART_IT_ORE                         ((uint16_t)0x0360)
+#define USART_IT_NE                          ((uint16_t)0x0260)
+#define USART_IT_FE                          ((uint16_t)0x0160)
+#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+                               ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+                               ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+                               ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR))
+#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+                            ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+                            ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+                            ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \
+                            ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE))
+#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+                               ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS))
+/**
+  * @}
+  */
+
+/** @defgroup USART_DMA_Requests 
+  * @{
+  */
+
+#define USART_DMAReq_Tx                      ((uint16_t)0x0080)
+#define USART_DMAReq_Rx                      ((uint16_t)0x0040)
+#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_WakeUp_methods
+  * @{
+  */
+
+#define USART_WakeUp_IdleLine                ((uint16_t)0x0000)
+#define USART_WakeUp_AddressMark             ((uint16_t)0x0800)
+#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \
+                                 ((WAKEUP) == USART_WakeUp_AddressMark))
+/**
+  * @}
+  */
+
+/** @defgroup USART_LIN_Break_Detection_Length 
+  * @{
+  */
+  
+#define USART_LINBreakDetectLength_10b      ((uint16_t)0x0000)
+#define USART_LINBreakDetectLength_11b      ((uint16_t)0x0020)
+#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \
+                               (((LENGTH) == USART_LINBreakDetectLength_10b) || \
+                                ((LENGTH) == USART_LINBreakDetectLength_11b))
+/**
+  * @}
+  */
+
+/** @defgroup USART_IrDA_Low_Power 
+  * @{
+  */
+
+#define USART_IrDAMode_LowPower              ((uint16_t)0x0004)
+#define USART_IrDAMode_Normal                ((uint16_t)0x0000)
+#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \
+                                  ((MODE) == USART_IrDAMode_Normal))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Flags 
+  * @{
+  */
+
+#define USART_FLAG_CTS                       ((uint16_t)0x0200)
+#define USART_FLAG_LBD                       ((uint16_t)0x0100)
+#define USART_FLAG_TXE                       ((uint16_t)0x0080)
+#define USART_FLAG_TC                        ((uint16_t)0x0040)
+#define USART_FLAG_RXNE                      ((uint16_t)0x0020)
+#define USART_FLAG_IDLE                      ((uint16_t)0x0010)
+#define USART_FLAG_ORE                       ((uint16_t)0x0008)
+#define USART_FLAG_NE                        ((uint16_t)0x0004)
+#define USART_FLAG_FE                        ((uint16_t)0x0002)
+#define USART_FLAG_PE                        ((uint16_t)0x0001)
+#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \
+                             ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \
+                             ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \
+                             ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \
+                             ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE))
+                              
+#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00))
+#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(uint32_t*)&(PERIPH)) != UART4_BASE) &&\
+                                                  ((*(uint32_t*)&(PERIPH)) != UART5_BASE)) \
+                                                  || ((USART_FLAG) != USART_FLAG_CTS)) 
+#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21))
+#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF)
+#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF)
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Exported_Macros
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Exported_Functions
+  * @{
+  */
+
+void USART_DeInit(USART_TypeDef* USARTx);
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct);
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct);
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState);
+void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState);
+void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address);
+void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp);
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength);
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SendData(USART_TypeDef* USARTx, uint16_t Data);
+uint16_t USART_ReceiveData(USART_TypeDef* USARTx);
+void USART_SendBreak(USART_TypeDef* USARTx);
+void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime);
+void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler);
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode);
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState);
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG);
+void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG);
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT);
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_USART_H */
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h
new file mode 100644
index 0000000000000000000000000000000000000000..2cd7ccdc9bbebbff5200d56db38cae3eb04fa9ef
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h
@@ -0,0 +1,114 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_wwdg.h
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file contains all the functions prototypes for the WWDG firmware
+  *          library.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F10x_WWDG_H
+#define __STM32F10x_WWDG_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup WWDG
+  * @{
+  */ 
+
+/** @defgroup WWDG_Exported_Types
+  * @{
+  */ 
+  
+/**
+  * @}
+  */ 
+
+/** @defgroup WWDG_Exported_Constants
+  * @{
+  */ 
+  
+/** @defgroup WWDG_Prescaler 
+  * @{
+  */ 
+  
+#define WWDG_Prescaler_1    ((uint32_t)0x00000000)
+#define WWDG_Prescaler_2    ((uint32_t)0x00000080)
+#define WWDG_Prescaler_4    ((uint32_t)0x00000100)
+#define WWDG_Prescaler_8    ((uint32_t)0x00000180)
+#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \
+                                      ((PRESCALER) == WWDG_Prescaler_2) || \
+                                      ((PRESCALER) == WWDG_Prescaler_4) || \
+                                      ((PRESCALER) == WWDG_Prescaler_8))
+#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F)
+#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F))
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup WWDG_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup WWDG_Exported_Functions
+  * @{
+  */ 
+  
+void WWDG_DeInit(void);
+void WWDG_SetPrescaler(uint32_t WWDG_Prescaler);
+void WWDG_SetWindowValue(uint8_t WindowValue);
+void WWDG_EnableIT(void);
+void WWDG_SetCounter(uint8_t Counter);
+void WWDG_Enable(uint8_t Counter);
+FlagStatus WWDG_GetFlagStatus(void);
+void WWDG_ClearFlag(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F10x_WWDG_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/misc.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/misc.c
new file mode 100644
index 0000000000000000000000000000000000000000..fa3c212fa5c406bedc6a098ae92d136ad0906f43
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/misc.c
@@ -0,0 +1,223 @@
+/**
+  ******************************************************************************
+  * @file    misc.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the miscellaneous firmware functions (add-on
+  *          to CMSIS functions).
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "misc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup MISC 
+  * @brief MISC driver modules
+  * @{
+  */
+
+/** @defgroup MISC_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */ 
+
+/** @defgroup MISC_Private_Defines
+  * @{
+  */
+
+#define AIRCR_VECTKEY_MASK    ((uint32_t)0x05FA0000)
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Configures the priority grouping: pre-emption priority and subpriority.
+  * @param  NVIC_PriorityGroup: specifies the priority grouping bits length. 
+  *   This parameter can be one of the following values:
+  *     @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority
+  *                                4 bits for subpriority
+  *     @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority
+  *                                3 bits for subpriority
+  *     @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority
+  *                                2 bits for subpriority
+  *     @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority
+  *                                1 bits for subpriority
+  *     @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority
+  *                                0 bits for subpriority
+  * @retval None
+  */
+void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup)
+{
+  /* Check the parameters */
+  assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup));
+  
+  /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */
+  SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup;
+}
+
+/**
+  * @brief  Initializes the NVIC peripheral according to the specified
+  *   parameters in the NVIC_InitStruct.
+  * @param  NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains
+  *   the configuration information for the specified NVIC peripheral.
+  * @retval None
+  */
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct)
+{
+  uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F;
+  
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd));
+  assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority));  
+  assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority));
+    
+  if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE)
+  {
+    /* Compute the Corresponding IRQ Priority --------------------------------*/    
+    tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08;
+    tmppre = (0x4 - tmppriority);
+    tmpsub = tmpsub >> tmppriority;
+
+    tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre;
+    tmppriority |=  NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub;
+    tmppriority = tmppriority << 0x04;
+        
+    NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority;
+    
+    /* Enable the Selected IRQ Channels --------------------------------------*/
+    NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
+      (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
+  }
+  else
+  {
+    /* Disable the Selected IRQ Channels -------------------------------------*/
+    NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
+      (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
+  }
+}
+
+/**
+  * @brief  Sets the vector table location and Offset.
+  * @param  NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory.
+  *   This parameter can be one of the following values:
+  *     @arg NVIC_VectTab_RAM
+  *     @arg NVIC_VectTab_FLASH
+  * @param  Offset: Vector Table base offset field. This value must be a multiple of 0x100.
+  * @retval None
+  */
+void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset)
+{ 
+  /* Check the parameters */
+  assert_param(IS_NVIC_VECTTAB(NVIC_VectTab));
+  assert_param(IS_NVIC_OFFSET(Offset));  
+   
+  SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80);
+}
+
+/**
+  * @brief  Selects the condition for the system to enter low power mode.
+  * @param  LowPowerMode: Specifies the new mode for the system to enter low power mode.
+  *   This parameter can be one of the following values:
+  *     @arg NVIC_LP_SEVONPEND
+  *     @arg NVIC_LP_SLEEPDEEP
+  *     @arg NVIC_LP_SLEEPONEXIT
+  * @param  NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_NVIC_LP(LowPowerMode));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));  
+  
+  if (NewState != DISABLE)
+  {
+    SCB->SCR |= LowPowerMode;
+  }
+  else
+  {
+    SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode);
+  }
+}
+
+/**
+  * @brief  Configures the SysTick clock source.
+  * @param  SysTick_CLKSource: specifies the SysTick clock source.
+  *   This parameter can be one of the following values:
+  *     @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source.
+  *     @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source.
+  * @retval None
+  */
+void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
+  if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
+  {
+    SysTick->CTRL |= SysTick_CLKSource_HCLK;
+  }
+  else
+  {
+    SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
+  }
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c
new file mode 100644
index 0000000000000000000000000000000000000000..412d9a923ead3abe2466745b6dad3ced9a8d49e0
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c
@@ -0,0 +1,1306 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_adc.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the ADC firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_adc.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup ADC 
+  * @brief ADC driver modules
+  * @{
+  */
+
+/** @defgroup ADC_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Private_Defines
+  * @{
+  */
+
+/* ADC DISCNUM mask */
+#define CR1_DISCNUM_Reset           ((uint32_t)0xFFFF1FFF)
+
+/* ADC DISCEN mask */
+#define CR1_DISCEN_Set              ((uint32_t)0x00000800)
+#define CR1_DISCEN_Reset            ((uint32_t)0xFFFFF7FF)
+
+/* ADC JAUTO mask */
+#define CR1_JAUTO_Set               ((uint32_t)0x00000400)
+#define CR1_JAUTO_Reset             ((uint32_t)0xFFFFFBFF)
+
+/* ADC JDISCEN mask */
+#define CR1_JDISCEN_Set             ((uint32_t)0x00001000)
+#define CR1_JDISCEN_Reset           ((uint32_t)0xFFFFEFFF)
+
+/* ADC AWDCH mask */
+#define CR1_AWDCH_Reset             ((uint32_t)0xFFFFFFE0)
+
+/* ADC Analog watchdog enable mode mask */
+#define CR1_AWDMode_Reset           ((uint32_t)0xFF3FFDFF)
+
+/* CR1 register Mask */
+#define CR1_CLEAR_Mask              ((uint32_t)0xFFF0FEFF)
+
+/* ADC ADON mask */
+#define CR2_ADON_Set                ((uint32_t)0x00000001)
+#define CR2_ADON_Reset              ((uint32_t)0xFFFFFFFE)
+
+/* ADC DMA mask */
+#define CR2_DMA_Set                 ((uint32_t)0x00000100)
+#define CR2_DMA_Reset               ((uint32_t)0xFFFFFEFF)
+
+/* ADC RSTCAL mask */
+#define CR2_RSTCAL_Set              ((uint32_t)0x00000008)
+
+/* ADC CAL mask */
+#define CR2_CAL_Set                 ((uint32_t)0x00000004)
+
+/* ADC SWSTART mask */
+#define CR2_SWSTART_Set             ((uint32_t)0x00400000)
+
+/* ADC EXTTRIG mask */
+#define CR2_EXTTRIG_Set             ((uint32_t)0x00100000)
+#define CR2_EXTTRIG_Reset           ((uint32_t)0xFFEFFFFF)
+
+/* ADC Software start mask */
+#define CR2_EXTTRIG_SWSTART_Set     ((uint32_t)0x00500000)
+#define CR2_EXTTRIG_SWSTART_Reset   ((uint32_t)0xFFAFFFFF)
+
+/* ADC JEXTSEL mask */
+#define CR2_JEXTSEL_Reset           ((uint32_t)0xFFFF8FFF)
+
+/* ADC JEXTTRIG mask */
+#define CR2_JEXTTRIG_Set            ((uint32_t)0x00008000)
+#define CR2_JEXTTRIG_Reset          ((uint32_t)0xFFFF7FFF)
+
+/* ADC JSWSTART mask */
+#define CR2_JSWSTART_Set            ((uint32_t)0x00200000)
+
+/* ADC injected software start mask */
+#define CR2_JEXTTRIG_JSWSTART_Set   ((uint32_t)0x00208000)
+#define CR2_JEXTTRIG_JSWSTART_Reset ((uint32_t)0xFFDF7FFF)
+
+/* ADC TSPD mask */
+#define CR2_TSVREFE_Set             ((uint32_t)0x00800000)
+#define CR2_TSVREFE_Reset           ((uint32_t)0xFF7FFFFF)
+
+/* CR2 register Mask */
+#define CR2_CLEAR_Mask              ((uint32_t)0xFFF1F7FD)
+
+/* ADC SQx mask */
+#define SQR3_SQ_Set                 ((uint32_t)0x0000001F)
+#define SQR2_SQ_Set                 ((uint32_t)0x0000001F)
+#define SQR1_SQ_Set                 ((uint32_t)0x0000001F)
+
+/* SQR1 register Mask */
+#define SQR1_CLEAR_Mask             ((uint32_t)0xFF0FFFFF)
+
+/* ADC JSQx mask */
+#define JSQR_JSQ_Set                ((uint32_t)0x0000001F)
+
+/* ADC JL mask */
+#define JSQR_JL_Set                 ((uint32_t)0x00300000)
+#define JSQR_JL_Reset               ((uint32_t)0xFFCFFFFF)
+
+/* ADC SMPx mask */
+#define SMPR1_SMP_Set               ((uint32_t)0x00000007)
+#define SMPR2_SMP_Set               ((uint32_t)0x00000007)
+
+/* ADC JDRx registers offset */
+#define JDR_Offset                  ((uint8_t)0x28)
+
+/* ADC1 DR register base address */
+#define DR_ADDRESS                  ((uint32_t)0x4001244C)
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the ADCx peripheral registers to their default reset values.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval None
+  */
+void ADC_DeInit(ADC_TypeDef* ADCx)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  
+  if (ADCx == ADC1)
+  {
+    /* Enable ADC1 reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE);
+    /* Release ADC1 from reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE);
+  }
+  else if (ADCx == ADC2)
+  {
+    /* Enable ADC2 reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE);
+    /* Release ADC2 from reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE);
+  }
+  else
+  {
+    if (ADCx == ADC3)
+    {
+      /* Enable ADC3 reset state */
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE);
+      /* Release ADC3 from reset state */
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE);
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the ADCx peripheral according to the specified parameters
+  *   in the ADC_InitStruct.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains
+  *   the configuration information for the specified ADC peripheral.
+  * @retval None
+  */
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct)
+{
+  uint32_t tmpreg1 = 0;
+  uint8_t tmpreg2 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode));
+  assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode));
+  assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode));
+  assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv));   
+  assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); 
+  assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel));
+
+  /*---------------------------- ADCx CR1 Configuration -----------------*/
+  /* Get the ADCx CR1 value */
+  tmpreg1 = ADCx->CR1;
+  /* Clear DUALMOD and SCAN bits */
+  tmpreg1 &= CR1_CLEAR_Mask;
+  /* Configure ADCx: Dual mode and scan conversion mode */
+  /* Set DUALMOD bits according to ADC_Mode value */
+  /* Set SCAN bit according to ADC_ScanConvMode value */
+  tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_Mode | ((uint32_t)ADC_InitStruct->ADC_ScanConvMode << 8));
+  /* Write to ADCx CR1 */
+  ADCx->CR1 = tmpreg1;
+
+  /*---------------------------- ADCx CR2 Configuration -----------------*/
+  /* Get the ADCx CR2 value */
+  tmpreg1 = ADCx->CR2;
+  /* Clear CONT, ALIGN and EXTSEL bits */
+  tmpreg1 &= CR2_CLEAR_Mask;
+  /* Configure ADCx: external trigger event and continuous conversion mode */
+  /* Set ALIGN bit according to ADC_DataAlign value */
+  /* Set EXTSEL bits according to ADC_ExternalTrigConv value */
+  /* Set CONT bit according to ADC_ContinuousConvMode value */
+  tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv |
+            ((uint32_t)ADC_InitStruct->ADC_ContinuousConvMode << 1));
+  /* Write to ADCx CR2 */
+  ADCx->CR2 = tmpreg1;
+
+  /*---------------------------- ADCx SQR1 Configuration -----------------*/
+  /* Get the ADCx SQR1 value */
+  tmpreg1 = ADCx->SQR1;
+  /* Clear L bits */
+  tmpreg1 &= SQR1_CLEAR_Mask;
+  /* Configure ADCx: regular channel sequence length */
+  /* Set L bits according to ADC_NbrOfChannel value */
+  tmpreg2 |= (uint8_t) (ADC_InitStruct->ADC_NbrOfChannel - (uint8_t)1);
+  tmpreg1 |= (uint32_t)tmpreg2 << 20;
+  /* Write to ADCx SQR1 */
+  ADCx->SQR1 = tmpreg1;
+}
+
+/**
+  * @brief  Fills each ADC_InitStruct member with its default value.
+  * @param  ADC_InitStruct : pointer to an ADC_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct)
+{
+  /* Reset ADC init structure parameters values */
+  /* Initialize the ADC_Mode member */
+  ADC_InitStruct->ADC_Mode = ADC_Mode_Independent;
+  /* initialize the ADC_ScanConvMode member */
+  ADC_InitStruct->ADC_ScanConvMode = DISABLE;
+  /* Initialize the ADC_ContinuousConvMode member */
+  ADC_InitStruct->ADC_ContinuousConvMode = DISABLE;
+  /* Initialize the ADC_ExternalTrigConv member */
+  ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
+  /* Initialize the ADC_DataAlign member */
+  ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right;
+  /* Initialize the ADC_NbrOfChannel member */
+  ADC_InitStruct->ADC_NbrOfChannel = 1;
+}
+
+/**
+  * @brief  Enables or disables the specified ADC peripheral.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the ADCx peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the ADON bit to wake up the ADC from power down mode */
+    ADCx->CR2 |= CR2_ADON_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC peripheral */
+    ADCx->CR2 &= CR2_ADON_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified ADC DMA request.
+  * @param  ADCx: where x can be 1 or 3 to select the ADC peripheral.
+  *   Note: ADC2 hasn't a DMA capability.
+  * @param  NewState: new state of the selected ADC DMA transfer.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_DMA_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC DMA request */
+    ADCx->CR2 |= CR2_DMA_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC DMA request */
+    ADCx->CR2 &= CR2_DMA_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified ADC interrupts.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. 
+  *   This parameter can be any combination of the following values:
+  *     @arg ADC_IT_EOC: End of conversion interrupt mask
+  *     @arg ADC_IT_AWD: Analog watchdog interrupt mask
+  *     @arg ADC_IT_JEOC: End of injected conversion interrupt mask
+  * @param  NewState: new state of the specified ADC interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState)
+{
+  uint8_t itmask = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_ADC_IT(ADC_IT));
+  /* Get the ADC IT index */
+  itmask = (uint8_t)ADC_IT;
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC interrupts */
+    ADCx->CR1 |= itmask;
+  }
+  else
+  {
+    /* Disable the selected ADC interrupts */
+    ADCx->CR1 &= (~(uint32_t)itmask);
+  }
+}
+
+/**
+  * @brief  Resets the selected ADC calibration registers.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval None
+  */
+void ADC_ResetCalibration(ADC_TypeDef* ADCx)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Resets the selected ADC calibartion registers */  
+  ADCx->CR2 |= CR2_RSTCAL_Set;
+}
+
+/**
+  * @brief  Gets the selected ADC reset calibration registers status.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The new state of ADC reset calibration registers (SET or RESET).
+  */
+FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Check the status of RSTCAL bit */
+  if ((ADCx->CR2 & CR2_RSTCAL_Set) != (uint32_t)RESET)
+  {
+    /* RSTCAL bit is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* RSTCAL bit is reset */
+    bitstatus = RESET;
+  }
+  /* Return the RSTCAL bit status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Starts the selected ADC calibration process.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval None
+  */
+void ADC_StartCalibration(ADC_TypeDef* ADCx)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Enable the selected ADC calibration process */  
+  ADCx->CR2 |= CR2_CAL_Set;
+}
+
+/**
+  * @brief  Gets the selected ADC calibration status.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The new state of ADC calibration (SET or RESET).
+  */
+FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Check the status of CAL bit */
+  if ((ADCx->CR2 & CR2_CAL_Set) != (uint32_t)RESET)
+  {
+    /* CAL bit is set: calibration on going */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* CAL bit is reset: end of calibration */
+    bitstatus = RESET;
+  }
+  /* Return the CAL bit status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Enables or disables the selected ADC software start conversion .
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC software start conversion.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC conversion on external event and start the selected
+       ADC conversion */
+    ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC conversion on external event and stop the selected
+       ADC conversion */
+    ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset;
+  }
+}
+
+/**
+  * @brief  Gets the selected ADC Software start conversion Status.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The new state of ADC software start conversion (SET or RESET).
+  */
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Check the status of SWSTART bit */
+  if ((ADCx->CR2 & CR2_SWSTART_Set) != (uint32_t)RESET)
+  {
+    /* SWSTART bit is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SWSTART bit is reset */
+    bitstatus = RESET;
+  }
+  /* Return the SWSTART bit status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Configures the discontinuous mode for the selected ADC regular
+  *   group channel.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  Number: specifies the discontinuous mode regular channel
+  *   count value. This number must be between 1 and 8.
+  * @retval None
+  */
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number)
+{
+  uint32_t tmpreg1 = 0;
+  uint32_t tmpreg2 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number));
+  /* Get the old register value */
+  tmpreg1 = ADCx->CR1;
+  /* Clear the old discontinuous mode channel count */
+  tmpreg1 &= CR1_DISCNUM_Reset;
+  /* Set the discontinuous mode channel count */
+  tmpreg2 = Number - 1;
+  tmpreg1 |= tmpreg2 << 13;
+  /* Store the new register value */
+  ADCx->CR1 = tmpreg1;
+}
+
+/**
+  * @brief  Enables or disables the discontinuous mode on regular group
+  *   channel for the specified ADC
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC discontinuous mode
+  *   on regular group channel.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC regular discontinuous mode */
+    ADCx->CR1 |= CR1_DISCEN_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC regular discontinuous mode */
+    ADCx->CR1 &= CR1_DISCEN_Reset;
+  }
+}
+
+/**
+  * @brief  Configures for the selected ADC regular channel its corresponding
+  *   rank in the sequencer and its sample time.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_Channel: the ADC channel to configure. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_Channel_0: ADC Channel0 selected
+  *     @arg ADC_Channel_1: ADC Channel1 selected
+  *     @arg ADC_Channel_2: ADC Channel2 selected
+  *     @arg ADC_Channel_3: ADC Channel3 selected
+  *     @arg ADC_Channel_4: ADC Channel4 selected
+  *     @arg ADC_Channel_5: ADC Channel5 selected
+  *     @arg ADC_Channel_6: ADC Channel6 selected
+  *     @arg ADC_Channel_7: ADC Channel7 selected
+  *     @arg ADC_Channel_8: ADC Channel8 selected
+  *     @arg ADC_Channel_9: ADC Channel9 selected
+  *     @arg ADC_Channel_10: ADC Channel10 selected
+  *     @arg ADC_Channel_11: ADC Channel11 selected
+  *     @arg ADC_Channel_12: ADC Channel12 selected
+  *     @arg ADC_Channel_13: ADC Channel13 selected
+  *     @arg ADC_Channel_14: ADC Channel14 selected
+  *     @arg ADC_Channel_15: ADC Channel15 selected
+  *     @arg ADC_Channel_16: ADC Channel16 selected
+  *     @arg ADC_Channel_17: ADC Channel17 selected
+  * @param  Rank: The rank in the regular group sequencer. This parameter must be between 1 to 16.
+  * @param  ADC_SampleTime: The sample time value to be set for the selected channel. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles
+  *     @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles
+  *     @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles
+  *     @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles	
+  *     @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles	
+  *     @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles	
+  *     @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles	
+  *     @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles	
+  * @retval None
+  */
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime)
+{
+  uint32_t tmpreg1 = 0, tmpreg2 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CHANNEL(ADC_Channel));
+  assert_param(IS_ADC_REGULAR_RANK(Rank));
+  assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+  /* if ADC_Channel_10 ... ADC_Channel_17 is selected */
+  if (ADC_Channel > ADC_Channel_9)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR1;
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10));
+    /* Clear the old channel sample time */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10));
+    /* Set the new channel sample time */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SMPR1 = tmpreg1;
+  }
+  else /* ADC_Channel include in ADC_Channel_[0..9] */
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR2;
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel);
+    /* Clear the old channel sample time */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
+    /* Set the new channel sample time */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SMPR2 = tmpreg1;
+  }
+  /* For Rank 1 to 6 */
+  if (Rank < 7)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SQR3;
+    /* Calculate the mask to clear */
+    tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1));
+    /* Clear the old SQx bits for the selected rank */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1));
+    /* Set the SQx bits for the selected rank */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SQR3 = tmpreg1;
+  }
+  /* For Rank 7 to 12 */
+  else if (Rank < 13)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SQR2;
+    /* Calculate the mask to clear */
+    tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7));
+    /* Clear the old SQx bits for the selected rank */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7));
+    /* Set the SQx bits for the selected rank */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SQR2 = tmpreg1;
+  }
+  /* For Rank 13 to 16 */
+  else
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SQR1;
+    /* Calculate the mask to clear */
+    tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13));
+    /* Clear the old SQx bits for the selected rank */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13));
+    /* Set the SQx bits for the selected rank */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SQR1 = tmpreg1;
+  }
+}
+
+/**
+  * @brief  Enables or disables the ADCx conversion through external trigger.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC external trigger start of conversion.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC conversion on external event */
+    ADCx->CR2 |= CR2_EXTTRIG_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC conversion on external event */
+    ADCx->CR2 &= CR2_EXTTRIG_Reset;
+  }
+}
+
+/**
+  * @brief  Returns the last ADCx conversion result data for regular channel.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The Data conversion value.
+  */
+uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Return the selected ADC conversion value */
+  return (uint16_t) ADCx->DR;
+}
+
+/**
+  * @brief  Returns the last ADC1 and ADC2 conversion result data in dual mode.
+  * @retval The Data conversion value.
+  */
+uint32_t ADC_GetDualModeConversionValue(void)
+{
+  /* Return the dual mode conversion value */
+  return (*(__IO uint32_t *) DR_ADDRESS);
+}
+
+/**
+  * @brief  Enables or disables the selected ADC automatic injected group
+  *   conversion after regular one.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC auto injected conversion
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC automatic injected group conversion */
+    ADCx->CR1 |= CR1_JAUTO_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC automatic injected group conversion */
+    ADCx->CR1 &= CR1_JAUTO_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the discontinuous mode for injected group
+  *   channel for the specified ADC
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC discontinuous mode
+  *   on injected group channel.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC injected discontinuous mode */
+    ADCx->CR1 |= CR1_JDISCEN_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC injected discontinuous mode */
+    ADCx->CR1 &= CR1_JDISCEN_Reset;
+  }
+}
+
+/**
+  * @brief  Configures the ADCx external trigger for injected channels conversion.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_ExternalTrigInjecConv: specifies the ADC trigger to start injected conversion. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event selected (for ADC1, ADC2 and ADC3)
+  *     @arg ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture compare4 selected (for ADC1, ADC2 and ADC3)
+  *     @arg ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event selected (for ADC1 and ADC2)
+  *     @arg ADC_ExternalTrigInjecConv_T2_CC1: Timer2 capture compare1 selected (for ADC1 and ADC2)
+  *     @arg ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture compare4 selected (for ADC1 and ADC2)
+  *     @arg ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event selected (for ADC1 and ADC2)
+  *     @arg ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External interrupt line 15 or Timer8
+  *                                                       capture compare4 event selected (for ADC1 and ADC2)                       
+  *     @arg ADC_ExternalTrigInjecConv_T4_CC3: Timer4 capture compare3 selected (for ADC3 only)
+  *     @arg ADC_ExternalTrigInjecConv_T8_CC2: Timer8 capture compare2 selected (for ADC3 only)                         
+  *     @arg ADC_ExternalTrigInjecConv_T8_CC4: Timer8 capture compare4 selected (for ADC3 only)
+  *     @arg ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event selected (for ADC3 only)                         
+  *     @arg ADC_ExternalTrigInjecConv_T5_CC4: Timer5 capture compare4 selected (for ADC3 only)                        
+  *     @arg ADC_ExternalTrigInjecConv_None: Injected conversion started by software and not
+  *                                          by external trigger (for ADC1, ADC2 and ADC3)
+  * @retval None
+  */
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv));
+  /* Get the old register value */
+  tmpreg = ADCx->CR2;
+  /* Clear the old external event selection for injected group */
+  tmpreg &= CR2_JEXTSEL_Reset;
+  /* Set the external event selection for injected group */
+  tmpreg |= ADC_ExternalTrigInjecConv;
+  /* Store the new register value */
+  ADCx->CR2 = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the ADCx injected channels conversion through
+  *   external trigger
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC external trigger start of
+  *   injected conversion.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC external event selection for injected group */
+    ADCx->CR2 |= CR2_JEXTTRIG_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC external event selection for injected group */
+    ADCx->CR2 &= CR2_JEXTTRIG_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the selected ADC start of the injected 
+  *   channels conversion.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC software start injected conversion.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC conversion for injected group on external event and start the selected
+       ADC injected conversion */
+    ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set;
+  }
+  else
+  {
+    /* Disable the selected ADC conversion on external event for injected group and stop the selected
+       ADC injected conversion */
+    ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset;
+  }
+}
+
+/**
+  * @brief  Gets the selected ADC Software start injected conversion Status.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The new state of ADC software start injected conversion (SET or RESET).
+  */
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Check the status of JSWSTART bit */
+  if ((ADCx->CR2 & CR2_JSWSTART_Set) != (uint32_t)RESET)
+  {
+    /* JSWSTART bit is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* JSWSTART bit is reset */
+    bitstatus = RESET;
+  }
+  /* Return the JSWSTART bit status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Configures for the selected ADC injected channel its corresponding
+  *   rank in the sequencer and its sample time.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_Channel: the ADC channel to configure. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_Channel_0: ADC Channel0 selected
+  *     @arg ADC_Channel_1: ADC Channel1 selected
+  *     @arg ADC_Channel_2: ADC Channel2 selected
+  *     @arg ADC_Channel_3: ADC Channel3 selected
+  *     @arg ADC_Channel_4: ADC Channel4 selected
+  *     @arg ADC_Channel_5: ADC Channel5 selected
+  *     @arg ADC_Channel_6: ADC Channel6 selected
+  *     @arg ADC_Channel_7: ADC Channel7 selected
+  *     @arg ADC_Channel_8: ADC Channel8 selected
+  *     @arg ADC_Channel_9: ADC Channel9 selected
+  *     @arg ADC_Channel_10: ADC Channel10 selected
+  *     @arg ADC_Channel_11: ADC Channel11 selected
+  *     @arg ADC_Channel_12: ADC Channel12 selected
+  *     @arg ADC_Channel_13: ADC Channel13 selected
+  *     @arg ADC_Channel_14: ADC Channel14 selected
+  *     @arg ADC_Channel_15: ADC Channel15 selected
+  *     @arg ADC_Channel_16: ADC Channel16 selected
+  *     @arg ADC_Channel_17: ADC Channel17 selected
+  * @param  Rank: The rank in the injected group sequencer. This parameter must be between 1 and 4.
+  * @param  ADC_SampleTime: The sample time value to be set for the selected channel. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles
+  *     @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles
+  *     @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles
+  *     @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles	
+  *     @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles	
+  *     @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles	
+  *     @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles	
+  *     @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles	
+  * @retval None
+  */
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime)
+{
+  uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CHANNEL(ADC_Channel));
+  assert_param(IS_ADC_INJECTED_RANK(Rank));
+  assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+  /* if ADC_Channel_10 ... ADC_Channel_17 is selected */
+  if (ADC_Channel > ADC_Channel_9)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR1;
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10));
+    /* Clear the old channel sample time */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10));
+    /* Set the new channel sample time */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SMPR1 = tmpreg1;
+  }
+  else /* ADC_Channel include in ADC_Channel_[0..9] */
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR2;
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel);
+    /* Clear the old channel sample time */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
+    /* Set the new channel sample time */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SMPR2 = tmpreg1;
+  }
+  /* Rank configuration */
+  /* Get the old register value */
+  tmpreg1 = ADCx->JSQR;
+  /* Get JL value: Number = JL+1 */
+  tmpreg3 =  (tmpreg1 & JSQR_JL_Set)>> 20;
+  /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */
+  tmpreg2 = JSQR_JSQ_Set << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1)));
+  /* Clear the old JSQx bits for the selected rank */
+  tmpreg1 &= ~tmpreg2;
+  /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */
+  tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1)));
+  /* Set the JSQx bits for the selected rank */
+  tmpreg1 |= tmpreg2;
+  /* Store the new register value */
+  ADCx->JSQR = tmpreg1;
+}
+
+/**
+  * @brief  Configures the sequencer length for injected channels
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  Length: The sequencer length. 
+  *   This parameter must be a number between 1 to 4.
+  * @retval None
+  */
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length)
+{
+  uint32_t tmpreg1 = 0;
+  uint32_t tmpreg2 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_INJECTED_LENGTH(Length));
+  
+  /* Get the old register value */
+  tmpreg1 = ADCx->JSQR;
+  /* Clear the old injected sequnence lenght JL bits */
+  tmpreg1 &= JSQR_JL_Reset;
+  /* Set the injected sequnence lenght JL bits */
+  tmpreg2 = Length - 1; 
+  tmpreg1 |= tmpreg2 << 20;
+  /* Store the new register value */
+  ADCx->JSQR = tmpreg1;
+}
+
+/**
+  * @brief  Set the injected channels conversion value offset
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_InjectedChannel: the ADC injected channel to set its offset. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_InjectedChannel_1: Injected Channel1 selected
+  *     @arg ADC_InjectedChannel_2: Injected Channel2 selected
+  *     @arg ADC_InjectedChannel_3: Injected Channel3 selected
+  *     @arg ADC_InjectedChannel_4: Injected Channel4 selected
+  * @param  Offset: the offset value for the selected ADC injected channel
+  *   This parameter must be a 12bit value.
+  * @retval None
+  */
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset)
+{
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+  assert_param(IS_ADC_OFFSET(Offset));  
+  
+  tmp = (uint32_t)ADCx;
+  tmp += ADC_InjectedChannel;
+  
+  /* Set the selected injected channel data offset */
+  *(__IO uint32_t *) tmp = (uint32_t)Offset;
+}
+
+/**
+  * @brief  Returns the ADC injected channel conversion result
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_InjectedChannel: the converted ADC injected channel.
+  *   This parameter can be one of the following values:
+  *     @arg ADC_InjectedChannel_1: Injected Channel1 selected
+  *     @arg ADC_InjectedChannel_2: Injected Channel2 selected
+  *     @arg ADC_InjectedChannel_3: Injected Channel3 selected
+  *     @arg ADC_InjectedChannel_4: Injected Channel4 selected
+  * @retval The Data conversion value.
+  */
+uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel)
+{
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+
+  tmp = (uint32_t)ADCx;
+  tmp += ADC_InjectedChannel + JDR_Offset;
+  
+  /* Returns the selected injected channel conversion data value */
+  return (uint16_t) (*(__IO uint32_t*)  tmp);   
+}
+
+/**
+  * @brief  Enables or disables the analog watchdog on single/all regular
+  *   or injected channels
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_AnalogWatchdog: the ADC analog watchdog configuration.
+  *   This parameter can be one of the following values:
+  *     @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel
+  *     @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel
+  *     @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel
+  *     @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on  all regular channel
+  *     @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on  all injected channel
+  *     @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels
+  *     @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog
+  * @retval None	  
+  */
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog));
+  /* Get the old register value */
+  tmpreg = ADCx->CR1;
+  /* Clear AWDEN, AWDENJ and AWDSGL bits */
+  tmpreg &= CR1_AWDMode_Reset;
+  /* Set the analog watchdog enable mode */
+  tmpreg |= ADC_AnalogWatchdog;
+  /* Store the new register value */
+  ADCx->CR1 = tmpreg;
+}
+
+/**
+  * @brief  Configures the high and low thresholds of the analog watchdog.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  HighThreshold: the ADC analog watchdog High threshold value.
+  *   This parameter must be a 12bit value.
+  * @param  LowThreshold: the ADC analog watchdog Low threshold value.
+  *   This parameter must be a 12bit value.
+  * @retval None
+  */
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold,
+                                        uint16_t LowThreshold)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_THRESHOLD(HighThreshold));
+  assert_param(IS_ADC_THRESHOLD(LowThreshold));
+  /* Set the ADCx high threshold */
+  ADCx->HTR = HighThreshold;
+  /* Set the ADCx low threshold */
+  ADCx->LTR = LowThreshold;
+}
+
+/**
+  * @brief  Configures the analog watchdog guarded single channel
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_Channel: the ADC channel to configure for the analog watchdog. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_Channel_0: ADC Channel0 selected
+  *     @arg ADC_Channel_1: ADC Channel1 selected
+  *     @arg ADC_Channel_2: ADC Channel2 selected
+  *     @arg ADC_Channel_3: ADC Channel3 selected
+  *     @arg ADC_Channel_4: ADC Channel4 selected
+  *     @arg ADC_Channel_5: ADC Channel5 selected
+  *     @arg ADC_Channel_6: ADC Channel6 selected
+  *     @arg ADC_Channel_7: ADC Channel7 selected
+  *     @arg ADC_Channel_8: ADC Channel8 selected
+  *     @arg ADC_Channel_9: ADC Channel9 selected
+  *     @arg ADC_Channel_10: ADC Channel10 selected
+  *     @arg ADC_Channel_11: ADC Channel11 selected
+  *     @arg ADC_Channel_12: ADC Channel12 selected
+  *     @arg ADC_Channel_13: ADC Channel13 selected
+  *     @arg ADC_Channel_14: ADC Channel14 selected
+  *     @arg ADC_Channel_15: ADC Channel15 selected
+  *     @arg ADC_Channel_16: ADC Channel16 selected
+  *     @arg ADC_Channel_17: ADC Channel17 selected
+  * @retval None
+  */
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CHANNEL(ADC_Channel));
+  /* Get the old register value */
+  tmpreg = ADCx->CR1;
+  /* Clear the Analog watchdog channel select bits */
+  tmpreg &= CR1_AWDCH_Reset;
+  /* Set the Analog watchdog channel */
+  tmpreg |= ADC_Channel;
+  /* Store the new register value */
+  ADCx->CR1 = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the temperature sensor and Vrefint channel.
+  * @param  NewState: new state of the temperature sensor.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_TempSensorVrefintCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the temperature sensor and Vrefint channel*/
+    ADC1->CR2 |= CR2_TSVREFE_Set;
+  }
+  else
+  {
+    /* Disable the temperature sensor and Vrefint channel*/
+    ADC1->CR2 &= CR2_TSVREFE_Reset;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified ADC flag is set or not.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_FLAG: specifies the flag to check. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_FLAG_AWD: Analog watchdog flag
+  *     @arg ADC_FLAG_EOC: End of conversion flag
+  *     @arg ADC_FLAG_JEOC: End of injected group conversion flag
+  *     @arg ADC_FLAG_JSTRT: Start of injected group conversion flag
+  *     @arg ADC_FLAG_STRT: Start of regular group conversion flag
+  * @retval The new state of ADC_FLAG (SET or RESET).
+  */
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_GET_FLAG(ADC_FLAG));
+  /* Check the status of the specified ADC flag */
+  if ((ADCx->SR & ADC_FLAG) != (uint8_t)RESET)
+  {
+    /* ADC_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* ADC_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the ADC_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the ADCx's pending flags.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_FLAG: specifies the flag to clear. 
+  *   This parameter can be any combination of the following values:
+  *     @arg ADC_FLAG_AWD: Analog watchdog flag
+  *     @arg ADC_FLAG_EOC: End of conversion flag
+  *     @arg ADC_FLAG_JEOC: End of injected group conversion flag
+  *     @arg ADC_FLAG_JSTRT: Start of injected group conversion flag
+  *     @arg ADC_FLAG_STRT: Start of regular group conversion flag
+  * @retval None
+  */
+void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG));
+  /* Clear the selected ADC flags */
+  ADCx->SR = ~(uint32_t)ADC_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified ADC interrupt has occurred or not.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_IT: specifies the ADC interrupt source to check. 
+  *   This parameter can be one of the following values:
+  *     @arg ADC_IT_EOC: End of conversion interrupt mask
+  *     @arg ADC_IT_AWD: Analog watchdog interrupt mask
+  *     @arg ADC_IT_JEOC: End of injected conversion interrupt mask
+  * @retval The new state of ADC_IT (SET or RESET).
+  */
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t itmask = 0, enablestatus = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_GET_IT(ADC_IT));
+  /* Get the ADC IT index */
+  itmask = ADC_IT >> 8;
+  /* Get the ADC_IT enable bit status */
+  enablestatus = (ADCx->CR1 & (uint8_t)ADC_IT) ;
+  /* Check the status of the specified ADC interrupt */
+  if (((ADCx->SR & itmask) != (uint32_t)RESET) && enablestatus)
+  {
+    /* ADC_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* ADC_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the ADC_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the ADCx’s interrupt pending bits.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_IT: specifies the ADC interrupt pending bit to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg ADC_IT_EOC: End of conversion interrupt mask
+  *     @arg ADC_IT_AWD: Analog watchdog interrupt mask
+  *     @arg ADC_IT_JEOC: End of injected conversion interrupt mask
+  * @retval None
+  */
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT)
+{
+  uint8_t itmask = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_IT(ADC_IT));
+  /* Get the ADC IT index */
+  itmask = (uint8_t)(ADC_IT >> 8);
+  /* Clear the selected ADC interrupt pending bits */
+  ADCx->SR = ~(uint32_t)itmask;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c
new file mode 100644
index 0000000000000000000000000000000000000000..f4970f18c829ad5d313eb4f982c5743fd23b86be
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c
@@ -0,0 +1,311 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_bkp.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the BKP firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_bkp.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup BKP 
+  * @brief BKP driver modules
+  * @{
+  */
+
+/** @defgroup BKP_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup BKP_Private_Defines
+  * @{
+  */
+
+/* ------------ BKP registers bit address in the alias region --------------- */
+#define BKP_OFFSET        (BKP_BASE - PERIPH_BASE)
+
+/* --- CR Register ----*/
+
+/* Alias word address of TPAL bit */
+#define CR_OFFSET         (BKP_OFFSET + 0x30)
+#define TPAL_BitNumber    0x01
+#define CR_TPAL_BB        (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4))
+
+/* Alias word address of TPE bit */
+#define TPE_BitNumber     0x00
+#define CR_TPE_BB         (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4))
+
+/* --- CSR Register ---*/
+
+/* Alias word address of TPIE bit */
+#define CSR_OFFSET        (BKP_OFFSET + 0x34)
+#define TPIE_BitNumber    0x02
+#define CSR_TPIE_BB       (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4))
+
+/* Alias word address of TIF bit */
+#define TIF_BitNumber     0x09
+#define CSR_TIF_BB        (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4))
+
+/* Alias word address of TEF bit */
+#define TEF_BitNumber     0x08
+#define CSR_TEF_BB        (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4))
+
+/* ---------------------- BKP registers bit mask ------------------------ */
+
+/* RTCCR register bit mask */
+#define RTCCR_CAL_Mask    ((uint16_t)0xFF80)
+#define RTCCR_Mask        ((uint16_t)0xFC7F)
+
+/* CSR register bit mask */
+#define CSR_CTE_Set       ((uint16_t)0x0001)
+#define CSR_CTI_Set       ((uint16_t)0x0002)
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup BKP_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup BKP_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup BKP_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup BKP_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the BKP peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void BKP_DeInit(void)
+{
+  RCC_BackupResetCmd(ENABLE);
+  RCC_BackupResetCmd(DISABLE);
+}
+
+/**
+  * @brief  Configures the Tamper Pin active level.
+  * @param  BKP_TamperPinLevel: specifies the Tamper Pin active level.
+  *   This parameter can be one of the following values:
+  *     @arg BKP_TamperPinLevel_High: Tamper pin active on high level
+  *     @arg BKP_TamperPinLevel_Low: Tamper pin active on low level
+  * @retval None
+  */
+void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel)
+{
+  /* Check the parameters */
+  assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel));
+  *(__IO uint32_t *) CR_TPAL_BB = BKP_TamperPinLevel;
+}
+
+/**
+  * @brief  Enables or disables the Tamper Pin activation.
+  * @param  NewState: new state of the Tamper Pin activation.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void BKP_TamperPinCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_TPE_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the Tamper Pin Interrupt.
+  * @param  NewState: new state of the Tamper Pin Interrupt.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void BKP_ITConfig(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CSR_TPIE_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Select the RTC output source to output on the Tamper pin.
+  * @param  BKP_RTCOutputSource: specifies the RTC output source.
+  *   This parameter can be one of the following values:
+  *     @arg BKP_RTCOutputSource_None: no RTC output on the Tamper pin.
+  *     @arg BKP_RTCOutputSource_CalibClock: output the RTC clock with frequency
+  *                                          divided by 64 on the Tamper pin.
+  *     @arg BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse signal on
+  *                                     the Tamper pin.
+  *     @arg BKP_RTCOutputSource_Second: output the RTC Second pulse signal on
+  *                                      the Tamper pin.  
+  * @retval None
+  */
+void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource)
+{
+  uint16_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource));
+  tmpreg = BKP->RTCCR;
+  /* Clear CCO, ASOE and ASOS bits */
+  tmpreg &= RTCCR_Mask;
+  
+  /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */
+  tmpreg |= BKP_RTCOutputSource;
+  /* Store the new value */
+  BKP->RTCCR = tmpreg;
+}
+
+/**
+  * @brief  Sets RTC Clock Calibration value.
+  * @param  CalibrationValue: specifies the RTC Clock Calibration value.
+  *   This parameter must be a number between 0 and 0x7F.
+  * @retval None
+  */
+void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue)
+{
+  uint16_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue));
+  tmpreg = BKP->RTCCR;
+  /* Clear CAL[6:0] bits */
+  tmpreg &= RTCCR_CAL_Mask;
+  /* Set CAL[6:0] bits according to CalibrationValue value */
+  tmpreg |= CalibrationValue;
+  /* Store the new value */
+  BKP->RTCCR = tmpreg;
+}
+
+/**
+  * @brief  Writes user data to the specified Data Backup Register.
+  * @param  BKP_DR: specifies the Data Backup Register.
+  *   This parameter can be BKP_DRx where x:[1, 42]
+  * @param  Data: data to write
+  * @retval None
+  */
+void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_BKP_DR(BKP_DR));
+
+  tmp = (uint32_t)BKP_BASE; 
+  tmp += BKP_DR;
+
+  *(__IO uint32_t *) tmp = Data;
+}
+
+/**
+  * @brief  Reads data from the specified Data Backup Register.
+  * @param  BKP_DR: specifies the Data Backup Register.
+  *   This parameter can be BKP_DRx where x:[1, 42]
+  * @retval The content of the specified Data Backup Register
+  */
+uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_BKP_DR(BKP_DR));
+
+  tmp = (uint32_t)BKP_BASE; 
+  tmp += BKP_DR;
+
+  return (*(__IO uint16_t *) tmp);
+}
+
+/**
+  * @brief  Checks whether the Tamper Pin Event flag is set or not.
+  * @param  None
+  * @retval The new state of the Tamper Pin Event flag (SET or RESET).
+  */
+FlagStatus BKP_GetFlagStatus(void)
+{
+  return (FlagStatus)(*(__IO uint32_t *) CSR_TEF_BB);
+}
+
+/**
+  * @brief  Clears Tamper Pin Event pending flag.
+  * @param  None
+  * @retval None
+  */
+void BKP_ClearFlag(void)
+{
+  /* Set CTE bit to clear Tamper Pin Event flag */
+  BKP->CSR |= CSR_CTE_Set;
+}
+
+/**
+  * @brief  Checks whether the Tamper Pin Interrupt has occurred or not.
+  * @param  None
+  * @retval The new state of the Tamper Pin Interrupt (SET or RESET).
+  */
+ITStatus BKP_GetITStatus(void)
+{
+  return (ITStatus)(*(__IO uint32_t *) CSR_TIF_BB);
+}
+
+/**
+  * @brief  Clears Tamper Pin Interrupt pending bit.
+  * @param  None
+  * @retval None
+  */
+void BKP_ClearITPendingBit(void)
+{
+  /* Set CTI bit to clear Tamper Pin Interrupt pending bit */
+  BKP->CSR |= CSR_CTI_Set;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c
new file mode 100644
index 0000000000000000000000000000000000000000..3e2aa23bc917d860c315eaa515da9675b243c6ca
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c
@@ -0,0 +1,990 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_can.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the CAN firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_can.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CAN 
+  * @brief CAN driver modules
+  * @{
+  */ 
+
+/** @defgroup CAN_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Private_Defines
+  * @{
+  */
+
+/* CAN Master Control Register bits */
+#define MCR_INRQ     ((uint32_t)0x00000001) /* Initialization request */
+#define MCR_SLEEP    ((uint32_t)0x00000002) /* Sleep mode request */
+#define MCR_TXFP     ((uint32_t)0x00000004) /* Transmit FIFO priority */
+#define MCR_RFLM     ((uint32_t)0x00000008) /* Receive FIFO locked mode */
+#define MCR_NART     ((uint32_t)0x00000010) /* No automatic retransmission */
+#define MCR_AWUM     ((uint32_t)0x00000020) /* Automatic wake up mode */
+#define MCR_ABOM     ((uint32_t)0x00000040) /* Automatic bus-off management */
+#define MCR_TTCM     ((uint32_t)0x00000080) /* time triggered communication */
+#define MCR_RESET    ((uint32_t)0x00008000) /* time triggered communication */
+#define MCR_DBF      ((uint32_t)0x00010000) /* software master reset */
+
+/* CAN Master Status Register bits */
+#define MSR_INAK     ((uint32_t)0x00000001)    /* Initialization acknowledge */
+#define MSR_WKUI     ((uint32_t)0x00000008)    /* Wake-up interrupt */
+#define MSR_SLAKI    ((uint32_t)0x00000010)    /* Sleep acknowledge interrupt */
+
+/* CAN Transmit Status Register bits */
+#define TSR_RQCP0    ((uint32_t)0x00000001)    /* Request completed mailbox0 */
+#define TSR_TXOK0    ((uint32_t)0x00000002)    /* Transmission OK of mailbox0 */
+#define TSR_ABRQ0    ((uint32_t)0x00000080)    /* Abort request for mailbox0 */
+#define TSR_RQCP1    ((uint32_t)0x00000100)    /* Request completed mailbox1 */
+#define TSR_TXOK1    ((uint32_t)0x00000200)    /* Transmission OK of mailbox1 */
+#define TSR_ABRQ1    ((uint32_t)0x00008000)    /* Abort request for mailbox1 */
+#define TSR_RQCP2    ((uint32_t)0x00010000)    /* Request completed mailbox2 */
+#define TSR_TXOK2    ((uint32_t)0x00020000)    /* Transmission OK of mailbox2 */
+#define TSR_ABRQ2    ((uint32_t)0x00800000)    /* Abort request for mailbox2 */
+#define TSR_TME0     ((uint32_t)0x04000000)    /* Transmit mailbox 0 empty */
+#define TSR_TME1     ((uint32_t)0x08000000)    /* Transmit mailbox 1 empty */
+#define TSR_TME2     ((uint32_t)0x10000000)    /* Transmit mailbox 2 empty */
+
+/* CAN Receive FIFO 0 Register bits */
+#define RF0R_FULL0   ((uint32_t)0x00000008)    /* FIFO 0 full */
+#define RF0R_FOVR0   ((uint32_t)0x00000010)    /* FIFO 0 overrun */
+#define RF0R_RFOM0   ((uint32_t)0x00000020)    /* Release FIFO 0 output mailbox */
+
+/* CAN Receive FIFO 1 Register bits */
+#define RF1R_FULL1   ((uint32_t)0x00000008)    /* FIFO 1 full */
+#define RF1R_FOVR1   ((uint32_t)0x00000010)    /* FIFO 1 overrun */
+#define RF1R_RFOM1   ((uint32_t)0x00000020)    /* Release FIFO 1 output mailbox */
+
+/* CAN Error Status Register bits */
+#define ESR_EWGF     ((uint32_t)0x00000001)    /* Error warning flag */
+#define ESR_EPVF     ((uint32_t)0x00000002)    /* Error passive flag */
+#define ESR_BOFF     ((uint32_t)0x00000004)    /* Bus-off flag */
+
+/* CAN Mailbox Transmit Request */
+#define TMIDxR_TXRQ  ((uint32_t)0x00000001) /* Transmit mailbox request */
+
+/* CAN Filter Master Register bits */
+#define FMR_FINIT    ((uint32_t)0x00000001) /* Filter init mode */
+
+/* Time out for INAK bit */
+#define INAK_TimeOut        ((uint32_t)0x0000FFFF)
+
+/* Time out for SLAK bit */
+#define SLAK_TimeOut        ((uint32_t)0x0000FFFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Private_FunctionPrototypes
+  * @{
+  */
+
+static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit);
+
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the CAN peripheral registers to their default reset values.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @retval None.
+  */
+void CAN_DeInit(CAN_TypeDef* CANx)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+ 
+  if (CANx == CAN1)
+  {
+    /* Enable CAN1 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE);
+    /* Release CAN1 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE);
+  }
+  else
+  {  
+    /* Enable CAN2 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, ENABLE);
+    /* Release CAN2 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, DISABLE);
+  }
+}
+
+/**
+  * @brief  Initializes the CAN peripheral according to the specified
+  *   parameters in the CAN_InitStruct.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_InitStruct: pointer to a CAN_InitTypeDef structure that
+  *   contains the configuration information for the CAN peripheral.
+  * @retval Constant indicates initialization succeed which will be 
+  *   CANINITFAILED or CANINITOK.
+  */
+uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct)
+{
+  uint8_t InitStatus = CANINITFAILED;
+  uint32_t wait_ack = 0x00000000;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP));
+  assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode));
+  assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW));
+  assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1));
+  assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2));
+  assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler));
+
+  /* exit from sleep mode */
+  CANx->MCR &= ~MCR_SLEEP;
+
+  /* Request initialisation */
+  CANx->MCR |= MCR_INRQ ;
+
+  /* Wait the acknowledge */
+  while (((CANx->MSR & MSR_INAK) != MSR_INAK) && (wait_ack != INAK_TimeOut))
+  {
+    wait_ack++;
+  }
+
+  /* ...and check acknowledged */
+  if ((CANx->MSR & MSR_INAK) != MSR_INAK)
+  {
+    InitStatus = CANINITFAILED;
+  }
+  else 
+  {
+    /* Set the time triggered communication mode */
+    if (CAN_InitStruct->CAN_TTCM == ENABLE)
+    {
+      CANx->MCR |= MCR_TTCM;
+    }
+    else
+    {
+      CANx->MCR &= ~MCR_TTCM;
+    }
+
+    /* Set the automatic bus-off management */
+    if (CAN_InitStruct->CAN_ABOM == ENABLE)
+    {
+      CANx->MCR |= MCR_ABOM;
+    }
+    else
+    {
+      CANx->MCR &= ~MCR_ABOM;
+    }
+
+    /* Set the automatic wake-up mode */
+    if (CAN_InitStruct->CAN_AWUM == ENABLE)
+    {
+      CANx->MCR |= MCR_AWUM;
+    }
+    else
+    {
+      CANx->MCR &= ~MCR_AWUM;
+    }
+
+    /* Set the no automatic retransmission */
+    if (CAN_InitStruct->CAN_NART == ENABLE)
+    {
+      CANx->MCR |= MCR_NART;
+    }
+    else
+    {
+      CANx->MCR &= ~MCR_NART;
+    }
+
+    /* Set the receive FIFO locked mode */
+    if (CAN_InitStruct->CAN_RFLM == ENABLE)
+    {
+      CANx->MCR |= MCR_RFLM;
+    }
+    else
+    {
+      CANx->MCR &= ~MCR_RFLM;
+    }
+
+    /* Set the transmit FIFO priority */
+    if (CAN_InitStruct->CAN_TXFP == ENABLE)
+    {
+      CANx->MCR |= MCR_TXFP;
+    }
+    else
+    {
+      CANx->MCR &= ~MCR_TXFP;
+    }
+
+    /* Set the bit timing register */
+    CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | ((uint32_t)CAN_InitStruct->CAN_SJW << 24) |
+               ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) |
+               ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1);
+
+    /* Request leave initialisation */
+    CANx->MCR &= ~MCR_INRQ;
+
+   /* Wait the acknowledge */
+   wait_ack = 0x00;
+
+   while (((CANx->MSR & MSR_INAK) == MSR_INAK) && (wait_ack != INAK_TimeOut))
+   {
+     wait_ack++;
+   }
+
+    /* ...and check acknowledged */
+    if ((CANx->MSR & MSR_INAK) == MSR_INAK)
+    {
+      InitStatus = CANINITFAILED;
+    }
+    else
+    {
+      InitStatus = CANINITOK ;
+    }
+  }
+
+  /* At this step, return the status of initialization */
+  return InitStatus;
+}
+
+/**
+  * @brief  Initializes the CAN peripheral according to the specified
+  *   parameters in the CAN_FilterInitStruct.
+  * @param  CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef
+  *   structure that contains the configuration information.
+  * @retval None.
+  */
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct)
+{
+  uint32_t filter_number_bit_pos = 0;
+  /* Check the parameters */
+  assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber));
+  assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode));
+  assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale));
+  assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation));
+
+  filter_number_bit_pos = ((uint32_t)0x00000001) << CAN_FilterInitStruct->CAN_FilterNumber;
+
+  /* Initialisation mode for the filter */
+  CAN1->FMR |= FMR_FINIT;
+
+  /* Filter Deactivation */
+  CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos;
+
+  /* Filter Scale */
+  if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit)
+  {
+    /* 16-bit scale for the filter */
+    CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos;
+
+    /* First 16-bit identifier and First 16-bit mask */
+    /* Or First 16-bit identifier and Second 16-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = 
+    ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow);
+
+    /* Second 16-bit identifier and Second 16-bit mask */
+    /* Or Third 16-bit identifier and Fourth 16-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = 
+    ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh);
+  }
+
+  if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit)
+  {
+    /* 32-bit scale for the filter */
+    CAN1->FS1R |= filter_number_bit_pos;
+    /* 32-bit identifier or First 32-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = 
+    ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow);
+    /* 32-bit mask or Second 32-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = 
+    ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow);
+  }
+
+  /* Filter Mode */
+  if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask)
+  {
+    /*Id/Mask mode for the filter*/
+    CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos;
+  }
+  else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */
+  {
+    /*Identifier list mode for the filter*/
+    CAN1->FM1R |= (uint32_t)filter_number_bit_pos;
+  }
+
+  /* Filter FIFO assignment */
+  if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO0)
+  {
+    /* FIFO 0 assignation for the filter */
+    CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos;
+  }
+
+  if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO1)
+  {
+    /* FIFO 1 assignation for the filter */
+    CAN1->FFA1R |= (uint32_t)filter_number_bit_pos;
+  }
+  
+  /* Filter activation */
+  if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE)
+  {
+    CAN1->FA1R |= filter_number_bit_pos;
+  }
+
+  /* Leave the initialisation mode for the filter */
+  CAN1->FMR &= ~FMR_FINIT;
+}
+
+/**
+  * @brief  Fills each CAN_InitStruct member with its default value.
+  * @param  CAN_InitStruct: pointer to a CAN_InitTypeDef structure which
+  *   will be initialized.
+  * @retval None.
+  */
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct)
+{
+  /* Reset CAN init structure parameters values */
+  /* Initialize the time triggered communication mode */
+  CAN_InitStruct->CAN_TTCM = DISABLE;
+  /* Initialize the automatic bus-off management */
+  CAN_InitStruct->CAN_ABOM = DISABLE;
+  /* Initialize the automatic wake-up mode */
+  CAN_InitStruct->CAN_AWUM = DISABLE;
+  /* Initialize the no automatic retransmission */
+  CAN_InitStruct->CAN_NART = DISABLE;
+  /* Initialize the receive FIFO locked mode */
+  CAN_InitStruct->CAN_RFLM = DISABLE;
+  /* Initialize the transmit FIFO priority */
+  CAN_InitStruct->CAN_TXFP = DISABLE;
+  /* Initialize the CAN_Mode member */
+  CAN_InitStruct->CAN_Mode = CAN_Mode_Normal;
+  /* Initialize the CAN_SJW member */
+  CAN_InitStruct->CAN_SJW = CAN_SJW_1tq;
+  /* Initialize the CAN_BS1 member */
+  CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq;
+  /* Initialize the CAN_BS2 member */
+  CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq;
+  /* Initialize the CAN_Prescaler member */
+  CAN_InitStruct->CAN_Prescaler = 1;
+}
+
+/**
+  * @brief  Select the start bank filter for slave CAN.
+  * @note   This function applies only to STM32 Connectivity line devices.
+  * @param  CAN_BankNumber: Select the start slave bank filter from 1..27.
+  * @retval None.
+  */
+void CAN_SlaveStartBank(uint8_t CAN_BankNumber) 
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber));
+  /* enter Initialisation mode for the filter */
+  CAN1->FMR |= FMR_FINIT;
+  /* Select the start slave bank */
+  CAN1->FMR &= (uint32_t)0xFFFFC0F1 ;
+  CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8;
+  /* Leave Initialisation mode for the filter */
+  CAN1->FMR &= ~FMR_FINIT;
+}
+
+/**
+  * @brief  Enables or disables the specified CAN interrupts.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_IT: specifies the CAN interrupt sources to be enabled or disabled.
+  *   This parameter can be: CAN_IT_TME, CAN_IT_FMP0, CAN_IT_FF0,
+  *   CAN_IT_FOV0, CAN_IT_FMP1, CAN_IT_FF1,
+  *   CAN_IT_FOV1, CAN_IT_EWG, CAN_IT_EPV,
+  *   CAN_IT_LEC, CAN_IT_ERR, CAN_IT_WKU or
+  *   CAN_IT_SLK.
+  * @param  NewState: new state of the CAN interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_ITConfig(CAN_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected CAN interrupt */
+    CANx->IER |= CAN_IT;
+  }
+  else
+  {
+    /* Disable the selected CAN interrupt */
+    CANx->IER &= ~CAN_IT;
+  }
+}
+
+/**
+  * @brief  Initiates the transmission of a message.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  TxMessage: pointer to a structure which contains CAN Id, CAN
+  *   DLC and CAN datas.
+  * @retval The number of the mailbox that is used for transmission
+  *   or CAN_NO_MB if there is no empty mailbox.
+  */
+uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage)
+{
+  uint8_t transmit_mailbox = 0;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_IDTYPE(TxMessage->IDE));
+  assert_param(IS_CAN_RTR(TxMessage->RTR));
+  assert_param(IS_CAN_DLC(TxMessage->DLC));
+
+  /* Select one empty transmit mailbox */
+  if ((CANx->TSR&TSR_TME0) == TSR_TME0)
+  {
+    transmit_mailbox = 0;
+  }
+  else if ((CANx->TSR&TSR_TME1) == TSR_TME1)
+  {
+    transmit_mailbox = 1;
+  }
+  else if ((CANx->TSR&TSR_TME2) == TSR_TME2)
+  {
+    transmit_mailbox = 2;
+  }
+  else
+  {
+    transmit_mailbox = CAN_NO_MB;
+  }
+
+  if (transmit_mailbox != CAN_NO_MB)
+  {
+    /* Set up the Id */
+    CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ;
+    if (TxMessage->IDE == CAN_ID_STD)
+    {
+      assert_param(IS_CAN_STDID(TxMessage->StdId));  
+      CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | TxMessage->RTR);
+    }
+    else
+    {
+      assert_param(IS_CAN_EXTID(TxMessage->ExtId));
+      CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId<<3) | TxMessage->IDE | 
+                                               TxMessage->RTR);
+    }
+    
+
+    /* Set up the DLC */
+    TxMessage->DLC &= (uint8_t)0x0000000F;
+    CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0;
+    CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC;
+
+    /* Set up the data field */
+    CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | 
+                                             ((uint32_t)TxMessage->Data[2] << 16) |
+                                             ((uint32_t)TxMessage->Data[1] << 8) | 
+                                             ((uint32_t)TxMessage->Data[0]));
+    CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | 
+                                             ((uint32_t)TxMessage->Data[6] << 16) |
+                                             ((uint32_t)TxMessage->Data[5] << 8) |
+                                             ((uint32_t)TxMessage->Data[4]));
+    /* Request transmission */
+    CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ;
+  }
+  return transmit_mailbox;
+}
+
+/**
+  * @brief  Checks the transmission of a message.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  TransmitMailbox: the number of the mailbox that is used for transmission.
+  * @retval CANTXOK if the CAN driver transmits the message, CANTXFAILED in an other case.
+  */
+uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox)
+{
+  /* RQCP, TXOK and TME bits */
+  uint8_t state = 0;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox));
+  switch (TransmitMailbox)
+  {
+    case (0): state |= (uint8_t)((CANx->TSR & TSR_RQCP0) << 2);
+      state |= (uint8_t)((CANx->TSR & TSR_TXOK0) >> 0);
+      state |= (uint8_t)((CANx->TSR & TSR_TME0) >> 26);
+      break;
+    case (1): state |= (uint8_t)((CANx->TSR & TSR_RQCP1) >> 6);
+      state |= (uint8_t)((CANx->TSR & TSR_TXOK1) >> 8);
+      state |= (uint8_t)((CANx->TSR & TSR_TME1) >> 27);
+      break;
+    case (2): state |= (uint8_t)((CANx->TSR & TSR_RQCP2) >> 14);
+      state |= (uint8_t)((CANx->TSR & TSR_TXOK2) >> 16);
+      state |= (uint8_t)((CANx->TSR & TSR_TME2) >> 28);
+      break;
+    default:
+      state = CANTXFAILED;
+      break;
+  }
+  switch (state)
+  {
+      /* transmit pending  */
+    case (0x0): state = CANTXPENDING;
+      break;
+      /* transmit failed  */
+    case (0x5): state = CANTXFAILED;
+      break;
+      /* transmit succedeed  */
+    case (0x7): state = CANTXOK;
+      break;
+    default:
+      state = CANTXFAILED;
+      break;
+  }
+  return state;
+}
+
+/**
+  * @brief  Cancels a transmit request.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral. 
+  * @param  Mailbox: Mailbox number.
+  * @retval None.
+  */
+void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox));
+  /* abort transmission */
+  switch (Mailbox)
+  {
+    case (0): CANx->TSR |= TSR_ABRQ0;
+      break;
+    case (1): CANx->TSR |= TSR_ABRQ1;
+      break;
+    case (2): CANx->TSR |= TSR_ABRQ2;
+      break;
+    default:
+      break;
+  }
+}
+
+/**
+  * @brief  Releases a FIFO.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral. 
+  * @param  FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1.
+  * @retval None.
+  */
+void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FIFO(FIFONumber));
+  /* Release FIFO0 */
+  if (FIFONumber == CAN_FIFO0)
+  {
+    CANx->RF0R = RF0R_RFOM0;
+  }
+  /* Release FIFO1 */
+  else /* FIFONumber == CAN_FIFO1 */
+  {
+    CANx->RF1R = RF1R_RFOM1;
+  }
+}
+
+/**
+  * @brief  Returns the number of pending messages.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+  * @retval NbMessage which is the number of pending message.
+  */
+uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber)
+{
+  uint8_t message_pending=0;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FIFO(FIFONumber));
+  if (FIFONumber == CAN_FIFO0)
+  {
+    message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03);
+  }
+  else if (FIFONumber == CAN_FIFO1)
+  {
+    message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03);
+  }
+  else
+  {
+    message_pending = 0;
+  }
+  return message_pending;
+}
+
+/**
+  * @brief  Receives a message.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+  * @param  RxMessage: pointer to a structure receive message which 
+  *   contains CAN Id, CAN DLC, CAN datas and FMI number.
+  * @retval None.
+  */
+void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FIFO(FIFONumber));
+  /* Get the Id */
+  RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR;
+  if (RxMessage->IDE == CAN_ID_STD)
+  {
+    RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21);
+  }
+  else
+  {
+    RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3);
+  }
+  
+  RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR;
+  /* Get the DLC */
+  RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR;
+  /* Get the FMI */
+  RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8);
+  /* Get the data field */
+  RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR;
+  RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8);
+  RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16);
+  RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24);
+  RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR;
+  RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8);
+  RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16);
+  RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24);
+  /* Release the FIFO */
+  CAN_FIFORelease(CANx, FIFONumber);
+}
+
+/**
+  * @brief  Enables or disables the DBG Freeze for CAN.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  NewState: new state of the CAN peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable Debug Freeze  */
+    CANx->MCR |= MCR_DBF;
+  }
+  else
+  {
+    /* Disable Debug Freeze */
+    CANx->MCR &= ~MCR_DBF;
+  }
+}
+
+/**
+  * @brief  Enters the low power mode.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @retval CANSLEEPOK if sleep entered, CANSLEEPFAILED in an other case.
+  */
+uint8_t CAN_Sleep(CAN_TypeDef* CANx)
+{
+  uint8_t sleepstatus = CANSLEEPFAILED;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+    
+  /* Request Sleep mode */
+   CANx->MCR = (((CANx->MCR) & (uint32_t)(~MCR_INRQ)) | MCR_SLEEP);
+   
+  /* Sleep mode status */
+  if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK)
+  {
+    /* Sleep mode not entered */
+    sleepstatus =  CANSLEEPOK;
+  }
+  /* At this step, sleep mode status */
+   return (uint8_t)sleepstatus;
+}
+
+/**
+  * @brief  Wakes the CAN up.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @retval CANWAKEUPOK if sleep mode left, CANWAKEUPFAILED in an other case.
+  */
+uint8_t CAN_WakeUp(CAN_TypeDef* CANx)
+{
+  uint32_t wait_slak = SLAK_TimeOut	;
+  uint8_t wakeupstatus = CANWAKEUPFAILED;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+    
+  /* Wake up request */
+  CANx->MCR &= ~MCR_SLEEP;
+    
+  /* Sleep mode status */
+  while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00))
+  {
+   wait_slak--;
+  }
+  if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK)
+  {
+   /* Sleep mode exited */
+    wakeupstatus = CANWAKEUPOK;
+  }
+  /* At this step, sleep mode status */
+  return (uint8_t)wakeupstatus;
+}
+
+/**
+  * @brief  Checks whether the specified CAN flag is set or not.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_FLAG: specifies the flag to check.
+  *   This parameter can be: CAN_FLAG_EWG, CAN_FLAG_EPV or CAN_FLAG_BOF.
+  * @retval The new state of CAN_FLAG (SET or RESET).
+  */
+FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FLAG(CAN_FLAG));
+  /* Check the status of the specified CAN flag */
+  if ((CANx->ESR & CAN_FLAG) != (uint32_t)RESET)
+  {
+    /* CAN_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* CAN_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the CAN_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the CAN's pending flags.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_FLAG: specifies the flag to clear.
+  * @retval None.
+  */
+void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FLAG(CAN_FLAG));
+  /* Clear the selected CAN flags */
+  CANx->ESR &= ~CAN_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified CAN interrupt has occurred or not.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_IT: specifies the CAN interrupt source to check.
+  *   This parameter can be: CAN_IT_RQCP0, CAN_IT_RQCP1, CAN_IT_RQCP2,
+  *   CAN_IT_FF0, CAN_IT_FOV0, CAN_IT_FF1,
+  *   CAN_IT_FOV1, CAN_IT_EWG, CAN_IT_EPV, 
+  *   CAN_IT_BOF, CAN_IT_WKU or CAN_IT_SLK.
+  * @retval The new state of CAN_IT (SET or RESET).
+  */
+ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT)
+{
+  ITStatus pendingbitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_ITStatus(CAN_IT));
+  switch (CAN_IT)
+  {
+    case CAN_IT_RQCP0:
+      pendingbitstatus = CheckITStatus(CANx->TSR, TSR_RQCP0);
+      break;
+    case CAN_IT_RQCP1:
+      pendingbitstatus = CheckITStatus(CANx->TSR, TSR_RQCP1);
+      break;
+    case CAN_IT_RQCP2:
+      pendingbitstatus = CheckITStatus(CANx->TSR, TSR_RQCP2);
+      break;
+    case CAN_IT_FF0:
+      pendingbitstatus = CheckITStatus(CANx->RF0R, RF0R_FULL0);
+      break;
+    case CAN_IT_FOV0:
+      pendingbitstatus = CheckITStatus(CANx->RF0R, RF0R_FOVR0);
+      break;
+    case CAN_IT_FF1:
+      pendingbitstatus = CheckITStatus(CANx->RF1R, RF1R_FULL1);
+      break;
+    case CAN_IT_FOV1:
+      pendingbitstatus = CheckITStatus(CANx->RF1R, RF1R_FOVR1);
+      break;
+    case CAN_IT_EWG:
+      pendingbitstatus = CheckITStatus(CANx->ESR, ESR_EWGF);
+      break;
+    case CAN_IT_EPV:
+      pendingbitstatus = CheckITStatus(CANx->ESR, ESR_EPVF);
+      break;
+    case CAN_IT_BOF:
+      pendingbitstatus = CheckITStatus(CANx->ESR, ESR_BOFF);
+      break;
+    case CAN_IT_SLK:
+      pendingbitstatus = CheckITStatus(CANx->MSR, MSR_SLAKI);
+      break;
+    case CAN_IT_WKU:
+      pendingbitstatus = CheckITStatus(CANx->MSR, MSR_WKUI);
+      break;
+    default :
+      pendingbitstatus = RESET;
+      break;
+  }
+  /* Return the CAN_IT status */
+  return  pendingbitstatus;
+}
+
+/**
+  * @brief  Clears the CAN’s interrupt pending bits.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_IT: specifies the interrupt pending bit to clear.
+  * @retval None.
+  */
+void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_ITStatus(CAN_IT));
+  switch (CAN_IT)
+  {
+    case CAN_IT_RQCP0:
+      CANx->TSR = TSR_RQCP0; /* rc_w1*/
+      break;
+    case CAN_IT_RQCP1:
+      CANx->TSR = TSR_RQCP1; /* rc_w1*/
+      break;
+    case CAN_IT_RQCP2:
+      CANx->TSR = TSR_RQCP2; /* rc_w1*/
+      break;
+    case CAN_IT_FF0:
+      CANx->RF0R = RF0R_FULL0; /* rc_w1*/
+      break;
+    case CAN_IT_FOV0:
+      CANx->RF0R = RF0R_FOVR0; /* rc_w1*/
+      break;
+    case CAN_IT_FF1:
+      CANx->RF1R = RF1R_FULL1; /* rc_w1*/
+      break;
+    case CAN_IT_FOV1:
+      CANx->RF1R = RF1R_FOVR1; /* rc_w1*/
+      break;
+    case CAN_IT_EWG:
+      CANx->ESR &= ~ ESR_EWGF; /* rw */
+      break;
+    case CAN_IT_EPV:
+      CANx->ESR &= ~ ESR_EPVF; /* rw */
+      break;
+    case CAN_IT_BOF:
+      CANx->ESR &= ~ ESR_BOFF; /* rw */
+      break;
+    case CAN_IT_WKU:
+      CANx->MSR = MSR_WKUI;  /* rc_w1*/
+      break;
+    case CAN_IT_SLK:
+      CANx->MSR = MSR_SLAKI;  /* rc_w1*/
+      break;
+    default :
+      break;
+  }
+}
+
+/**
+  * @brief  Checks whether the CAN interrupt has occurred or not.
+  * @param  CAN_Reg: specifies the CAN interrupt register to check.
+  * @param  It_Bit: specifies the interrupt source bit to check.
+  * @retval The new state of the CAN Interrupt (SET or RESET).
+  */
+static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit)
+{
+  ITStatus pendingbitstatus = RESET;
+  
+  if ((CAN_Reg & It_Bit) != (uint32_t)RESET)
+  {
+    /* CAN_IT is set */
+    pendingbitstatus = SET;
+  }
+  else
+  {
+    /* CAN_IT is reset */
+    pendingbitstatus = RESET;
+  }
+  return pendingbitstatus;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c
new file mode 100644
index 0000000000000000000000000000000000000000..d0c8d7a73fe6528b91926a593ec5b20abf86ce46
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c
@@ -0,0 +1,163 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_crc.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the CRC firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_crc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CRC 
+  * @brief CRC driver modules
+  * @{
+  */
+
+/** @defgroup CRC_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Private_Defines
+  * @{
+  */
+
+/* CR register bit mask */
+
+#define CR_RESET_Set    ((uint32_t)0x00000001)
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup CRC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Resets the CRC Data register (DR).
+  * @param  None
+  * @retval None
+  */
+void CRC_ResetDR(void)
+{
+  /* Reset CRC generator */
+  CRC->CR = CR_RESET_Set;
+}
+
+/**
+  * @brief  Computes the 32-bit CRC of a given data word(32-bit).
+  * @param  Data: data word(32-bit) to compute its CRC
+  * @retval 32-bit CRC
+  */
+uint32_t CRC_CalcCRC(uint32_t Data)
+{
+  CRC->DR = Data;
+  
+  return (CRC->DR);
+}
+
+/**
+  * @brief  Computes the 32-bit CRC of a given buffer of data word(32-bit).
+  * @param  pBuffer: pointer to the buffer containing the data to be computed
+  * @param  BufferLength: length of the buffer to be computed					
+  * @retval 32-bit CRC
+  */
+uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength)
+{
+  uint32_t index = 0;
+  
+  for(index = 0; index < BufferLength; index++)
+  {
+    CRC->DR = pBuffer[index];
+  }
+  return (CRC->DR);
+}
+
+/**
+  * @brief  Returns the current CRC value.
+  * @param  None
+  * @retval 32-bit CRC
+  */
+uint32_t CRC_GetCRC(void)
+{
+  return (CRC->DR);
+}
+
+/**
+  * @brief  Stores a 8-bit data in the Independent Data(ID) register.
+  * @param  IDValue: 8-bit value to be stored in the ID register 					
+  * @retval None
+  */
+void CRC_SetIDRegister(uint8_t IDValue)
+{
+  CRC->IDR = IDValue;
+}
+
+/**
+  * @brief  Returns the 8-bit data stored in the Independent Data(ID) register
+  * @param  None
+  * @retval 8-bit value of the ID register 
+  */
+uint8_t CRC_GetIDRegister(void)
+{
+  return (CRC->IDR);
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c
new file mode 100644
index 0000000000000000000000000000000000000000..f07e937cf64a887d17280549e752e8c20132ed8e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c
@@ -0,0 +1,431 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_dac.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the DAC firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dac.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DAC 
+  * @brief DAC driver modules
+  * @{
+  */ 
+
+/** @defgroup DAC_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Private_Defines
+  * @{
+  */
+
+/* DAC EN mask */
+#define CR_EN_Set                  ((uint32_t)0x00000001)
+
+/* DAC DMAEN mask */
+#define CR_DMAEN_Set               ((uint32_t)0x00001000)
+
+/* CR register Mask */
+#define CR_CLEAR_Mask              ((uint32_t)0x00000FFE)
+
+/* DAC SWTRIG mask */
+#define SWTRIGR_SWTRIG_Set         ((uint32_t)0x00000001)
+
+/* DAC Dual Channels SWTRIG masks */
+#define DUAL_SWTRIG_Set            ((uint32_t)0x00000003)
+#define DUAL_SWTRIG_Reset          ((uint32_t)0xFFFFFFFC)
+
+/* DHR registers offsets */
+#define DHR12R1_Offset             ((uint32_t)0x00000008)
+#define DHR12R2_Offset             ((uint32_t)0x00000014)
+#define DHR12RD_Offset             ((uint32_t)0x00000020)
+
+/* DOR register offset */
+#define DOR_Offset                 ((uint32_t)0x0000002C)
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the DAC peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void DAC_DeInit(void)
+{
+  /* Enable DAC reset state */
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
+  /* Release DAC from reset state */
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
+}
+
+/**
+  * @brief  Initializes the DAC peripheral according to the specified 
+  *   parameters in the DAC_InitStruct.
+  * @param  DAC_Channel: the selected DAC channel. 
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Channel_1: DAC Channel1 selected
+  *     @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_InitStruct: pointer to a DAC_InitTypeDef structure that
+  *   contains the configuration information for the specified DAC channel.
+  * @retval None
+  */
+void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
+{
+  uint32_t tmpreg1 = 0, tmpreg2 = 0;
+  /* Check the DAC parameters */
+  assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
+  assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
+  assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
+  assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
+/*---------------------------- DAC CR Configuration --------------------------*/
+  /* Get the DAC CR value */
+  tmpreg1 = DAC->CR;
+  /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
+  tmpreg1 &= ~(CR_CLEAR_Mask << DAC_Channel);
+  /* Configure for the selected DAC channel: buffer output, trigger, wave genration,
+     mask/amplitude for wave genration */
+  /* Set TSELx and TENx bits according to DAC_Trigger value */
+  /* Set WAVEx bits according to DAC_WaveGeneration value */
+  /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ 
+  /* Set BOFFx bit according to DAC_OutputBuffer value */   
+  tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
+             DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer);
+  /* Calculate CR register value depending on DAC_Channel */
+  tmpreg1 |= tmpreg2 << DAC_Channel;
+  /* Write to DAC CR */
+  DAC->CR = tmpreg1;
+}
+
+/**
+  * @brief  Fills each DAC_InitStruct member with its default value.
+  * @param  DAC_InitStruct : pointer to a DAC_InitTypeDef structure which will
+  *   be initialized.
+  * @retval None
+  */
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
+{
+/*--------------- Reset DAC init structure parameters values -----------------*/
+  /* Initialize the DAC_Trigger member */
+  DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
+  /* Initialize the DAC_WaveGeneration member */
+  DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
+  /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
+  DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
+  /* Initialize the DAC_OutputBuffer member */
+  DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
+}
+
+/**
+  * @brief  Enables or disables the specified DAC channel.
+  * @param  DAC_Channel: the selected DAC channel. 
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Channel_1: DAC Channel1 selected
+  *     @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  NewState: new state of the DAC channel. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DAC channel */
+    DAC->CR |= CR_EN_Set << DAC_Channel;
+  }
+  else
+  {
+    /* Disable the selected DAC channel */
+    DAC->CR &= ~(CR_EN_Set << DAC_Channel);
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified DAC channel DMA request.
+  * @param  DAC_Channel: the selected DAC channel. 
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Channel_1: DAC Channel1 selected
+  *     @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  NewState: new state of the selected DAC channel DMA request.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DAC channel DMA request */
+    DAC->CR |= CR_DMAEN_Set << DAC_Channel;
+  }
+  else
+  {
+    /* Disable the selected DAC channel DMA request */
+    DAC->CR &= ~(CR_DMAEN_Set << DAC_Channel);
+  }
+}
+
+/**
+  * @brief  Enables or disables the selected DAC channel software trigger.
+  * @param  DAC_Channel: the selected DAC channel. 
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Channel_1: DAC Channel1 selected
+  *     @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  NewState: new state of the selected DAC channel software trigger.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable software trigger for the selected DAC channel */
+    DAC->SWTRIGR |= SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4);
+  }
+  else
+  {
+    /* Disable software trigger for the selected DAC channel */
+    DAC->SWTRIGR &= ~(SWTRIGR_SWTRIG_Set << (DAC_Channel >> 4));
+  }
+}
+
+/**
+  * @brief  Enables or disables simultaneously the two DAC channels software
+  *   triggers.
+  * @param  NewState: new state of the DAC channels software triggers.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable software trigger for both DAC channels */
+    DAC->SWTRIGR |= DUAL_SWTRIG_Set ;
+  }
+  else
+  {
+    /* Disable software trigger for both DAC channels */
+    DAC->SWTRIGR &= DUAL_SWTRIG_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the selected DAC channel wave generation.
+  * @param  DAC_Channel: the selected DAC channel. 
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Channel_1: DAC Channel1 selected
+  *     @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_Wave: Specifies the wave type to enable or disable.
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Wave_Noise: noise wave generation
+  *     @arg DAC_Wave_Triangle: triangle wave generation
+  * @param  NewState: new state of the selected DAC channel wave generation.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_DAC_WAVE(DAC_Wave)); 
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected wave generation for the selected DAC channel */
+    DAC->CR |= DAC_Wave << DAC_Channel;
+  }
+  else
+  {
+    /* Disable the selected wave generation for the selected DAC channel */
+    DAC->CR &= ~(DAC_Wave << DAC_Channel);
+  }
+}
+
+/**
+  * @brief  Set the specified data holding register value for DAC channel1.
+  * @param  DAC_Align: Specifies the data alignement for DAC channel1.
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Align_8b_R: 8bit right data alignement selected
+  *     @arg DAC_Align_12b_L: 12bit left data alignement selected
+  *     @arg DAC_Align_12b_R: 12bit right data alignement selected
+  * @param  Data : Data to be loaded in the selected data holding register.
+  * @retval None
+  */
+void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data)
+{  
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DAC_ALIGN(DAC_Align));
+  assert_param(IS_DAC_DATA(Data));
+  
+  tmp = (uint32_t)DAC_BASE; 
+  tmp += DHR12R1_Offset + DAC_Align;
+
+  /* Set the DAC channel1 selected data holding register */
+  *(__IO uint32_t *) tmp = Data;
+}
+
+/**
+  * @brief  Set the specified data holding register value for DAC channel2.
+  * @param  DAC_Align: Specifies the data alignement for DAC channel2.
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Align_8b_R: 8bit right data alignement selected
+  *     @arg DAC_Align_12b_L: 12bit left data alignement selected
+  *     @arg DAC_Align_12b_R: 12bit right data alignement selected
+  * @param  Data : Data to be loaded in the selected data holding register.
+  * @retval None
+  */
+void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DAC_ALIGN(DAC_Align));
+  assert_param(IS_DAC_DATA(Data));
+  
+  tmp = (uint32_t)DAC_BASE;
+  tmp += DHR12R2_Offset + DAC_Align;
+
+  /* Set the DAC channel2 selected data holding register */
+  *(__IO uint32_t *)tmp = Data;
+}
+
+/**
+  * @brief  Set the specified data holding register value for dual channel
+  *   DAC.
+  * @param  DAC_Align: Specifies the data alignement for dual channel DAC.
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Align_8b_R: 8bit right data alignement selected
+  *     @arg DAC_Align_12b_L: 12bit left data alignement selected
+  *     @arg DAC_Align_12b_R: 12bit right data alignement selected
+  * @param  Data2: Data for DAC Channel2 to be loaded in the selected data 
+  *   holding register.
+  * @param  Data1: Data for DAC Channel1 to be loaded in the selected data 
+  *   holding register.
+  * @retval None
+  */
+void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
+{
+  uint32_t data = 0, tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DAC_ALIGN(DAC_Align));
+  assert_param(IS_DAC_DATA(Data1));
+  assert_param(IS_DAC_DATA(Data2));
+  
+  /* Calculate and set dual DAC data holding register value */
+  if (DAC_Align == DAC_Align_8b_R)
+  {
+    data = ((uint32_t)Data2 << 8) | Data1; 
+  }
+  else
+  {
+    data = ((uint32_t)Data2 << 16) | Data1;
+  }
+  
+  tmp = (uint32_t)DAC_BASE;
+  tmp += DHR12RD_Offset + DAC_Align;
+
+  /* Set the dual DAC selected data holding register */
+  *(__IO uint32_t *)tmp = data;
+}
+
+/**
+  * @brief  Returns the last data output value of the selected DAC cahnnel.
+  * @param  DAC_Channel: the selected DAC channel. 
+  *   This parameter can be one of the following values:
+  *     @arg DAC_Channel_1: DAC Channel1 selected
+  *     @arg DAC_Channel_2: DAC Channel2 selected
+  * @retval The selected DAC channel data output value.
+  */
+uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel)
+{
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  
+  tmp = (uint32_t) DAC_BASE ;
+  tmp += DOR_Offset + ((uint32_t)DAC_Channel >> 2);
+  
+  /* Returns the DAC channel data output register value */
+  return (uint16_t) (*(__IO uint32_t*) tmp);
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c
new file mode 100644
index 0000000000000000000000000000000000000000..852f36527d44622aa44f379b486da790e9ca6771
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c
@@ -0,0 +1,152 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_dbgmcu.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the DBGMCU firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dbgmcu.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DBGMCU 
+  * @brief DBGMCU driver modules
+  * @{
+  */ 
+
+/** @defgroup DBGMCU_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DBGMCU_Private_Defines
+  * @{
+  */
+
+#define IDCODE_DEVID_Mask    ((uint32_t)0x00000FFF)
+/**
+  * @}
+  */
+
+/** @defgroup DBGMCU_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DBGMCU_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DBGMCU_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DBGMCU_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Returns the device revision identifier.
+  * @param  None
+  * @retval Device revision identifier
+  */
+uint32_t DBGMCU_GetREVID(void)
+{
+   return(DBGMCU->IDCODE >> 16);
+}
+
+/**
+  * @brief  Returns the device identifier.
+  * @param  None
+  * @retval Device identifier
+  */
+uint32_t DBGMCU_GetDEVID(void)
+{
+   return(DBGMCU->IDCODE & IDCODE_DEVID_Mask);
+}
+
+/**
+  * @brief  Configures the specified peripheral and low power mode behavior
+  *   when the MCU under Debug mode.
+  * @param  DBGMCU_Periph: specifies the peripheral and low power mode.
+  *   This parameter can be any combination of the following values:
+  *     @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode              
+  *     @arg DBGMCU_STOP: Keep debugger connection during STOP mode               
+  *     @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode            
+  *     @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted          
+  *     @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted          
+  *     @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted          
+  *     @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted           
+  *     @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when Core is halted
+  *     @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when Core is halted
+  *     @arg DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted
+  *     @arg DBGMCU_CAN2_STOP: Debug CAN2 stopped when Core is halted           
+  * @param  NewState: new state of the specified peripheral in Debug mode.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    DBGMCU->CR |= DBGMCU_Periph;
+  }
+  else
+  {
+    DBGMCU->CR &= ~DBGMCU_Periph;
+  }
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c
new file mode 100644
index 0000000000000000000000000000000000000000..f801b9bf1131b59a550eb837b9ccb2a9527deb3f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c
@@ -0,0 +1,693 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_dma.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the DMA firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_dma.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DMA 
+  * @brief DMA driver modules
+  * @{
+  */ 
+
+/** @defgroup DMA_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Private_Defines
+  * @{
+  */
+
+/* DMA ENABLE mask */
+#define CCR_ENABLE_Set          ((uint32_t)0x00000001)
+#define CCR_ENABLE_Reset        ((uint32_t)0xFFFFFFFE)
+
+/* DMA1 Channelx interrupt pending bit masks */
+#define DMA1_Channel1_IT_Mask    ((uint32_t)0x0000000F)
+#define DMA1_Channel2_IT_Mask    ((uint32_t)0x000000F0)
+#define DMA1_Channel3_IT_Mask    ((uint32_t)0x00000F00)
+#define DMA1_Channel4_IT_Mask    ((uint32_t)0x0000F000)
+#define DMA1_Channel5_IT_Mask    ((uint32_t)0x000F0000)
+#define DMA1_Channel6_IT_Mask    ((uint32_t)0x00F00000)
+#define DMA1_Channel7_IT_Mask    ((uint32_t)0x0F000000)
+
+/* DMA2 Channelx interrupt pending bit masks */
+#define DMA2_Channel1_IT_Mask    ((uint32_t)0x0000000F)
+#define DMA2_Channel2_IT_Mask    ((uint32_t)0x000000F0)
+#define DMA2_Channel3_IT_Mask    ((uint32_t)0x00000F00)
+#define DMA2_Channel4_IT_Mask    ((uint32_t)0x0000F000)
+#define DMA2_Channel5_IT_Mask    ((uint32_t)0x000F0000)
+
+/* DMA2 FLAG mask */
+#define FLAG_Mask                ((uint32_t)0x10000000)
+
+/* DMA registers Masks */
+#define CCR_CLEAR_Mask           ((uint32_t)0xFFFF800F)
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the DMAy Channelx registers to their default reset
+  *   values.
+  * @param  DMAy_Channelx: where y can be 1 or 2 to select the DMA and
+  *   x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
+  * @retval None
+  */
+void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+  /* Disable the selected DMAy Channelx */
+  DMAy_Channelx->CCR &= CCR_ENABLE_Reset;
+  /* Reset DMAy Channelx control register */
+  DMAy_Channelx->CCR  = 0;
+  
+  /* Reset DMAy Channelx remaining bytes register */
+  DMAy_Channelx->CNDTR = 0;
+  
+  /* Reset DMAy Channelx peripheral address register */
+  DMAy_Channelx->CPAR  = 0;
+  
+  /* Reset DMAy Channelx memory address register */
+  DMAy_Channelx->CMAR = 0;
+  
+  if (DMAy_Channelx == DMA1_Channel1)
+  {
+    /* Reset interrupt pending bits for DMA1 Channel1 */
+    DMA1->IFCR |= DMA1_Channel1_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA1_Channel2)
+  {
+    /* Reset interrupt pending bits for DMA1 Channel2 */
+    DMA1->IFCR |= DMA1_Channel2_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA1_Channel3)
+  {
+    /* Reset interrupt pending bits for DMA1 Channel3 */
+    DMA1->IFCR |= DMA1_Channel3_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA1_Channel4)
+  {
+    /* Reset interrupt pending bits for DMA1 Channel4 */
+    DMA1->IFCR |= DMA1_Channel4_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA1_Channel5)
+  {
+    /* Reset interrupt pending bits for DMA1 Channel5 */
+    DMA1->IFCR |= DMA1_Channel5_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA1_Channel6)
+  {
+    /* Reset interrupt pending bits for DMA1 Channel6 */
+    DMA1->IFCR |= DMA1_Channel6_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA1_Channel7)
+  {
+    /* Reset interrupt pending bits for DMA1 Channel7 */
+    DMA1->IFCR |= DMA1_Channel7_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA2_Channel1)
+  {
+    /* Reset interrupt pending bits for DMA2 Channel1 */
+    DMA2->IFCR |= DMA2_Channel1_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA2_Channel2)
+  {
+    /* Reset interrupt pending bits for DMA2 Channel2 */
+    DMA2->IFCR |= DMA2_Channel2_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA2_Channel3)
+  {
+    /* Reset interrupt pending bits for DMA2 Channel3 */
+    DMA2->IFCR |= DMA2_Channel3_IT_Mask;
+  }
+  else if (DMAy_Channelx == DMA2_Channel4)
+  {
+    /* Reset interrupt pending bits for DMA2 Channel4 */
+    DMA2->IFCR |= DMA2_Channel4_IT_Mask;
+  }
+  else
+  { 
+    if (DMAy_Channelx == DMA2_Channel5)
+    {
+      /* Reset interrupt pending bits for DMA2 Channel5 */
+      DMA2->IFCR |= DMA2_Channel5_IT_Mask;
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the DMAy Channelx according to the specified
+  *   parameters in the DMA_InitStruct.
+  * @param  DMAy_Channelx: where y can be 1 or 2 to select the DMA and 
+  *   x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
+  * @param  DMA_InitStruct: pointer to a DMA_InitTypeDef structure that
+  *   contains the configuration information for the specified DMA Channel.
+  * @retval None
+  */
+void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+  assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR));
+  assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize));
+  assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc));
+  assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc));   
+  assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize));
+  assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize));
+  assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode));
+  assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority));
+  assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M));
+
+/*--------------------------- DMAy Channelx CCR Configuration -----------------*/
+  /* Get the DMAy_Channelx CCR value */
+  tmpreg = DMAy_Channelx->CCR;
+  /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */
+  tmpreg &= CCR_CLEAR_Mask;
+  /* Configure DMAy Channelx: data transfer, data size, priority level and mode */
+  /* Set DIR bit according to DMA_DIR value */
+  /* Set CIRC bit according to DMA_Mode value */
+  /* Set PINC bit according to DMA_PeripheralInc value */
+  /* Set MINC bit according to DMA_MemoryInc value */
+  /* Set PSIZE bits according to DMA_PeripheralDataSize value */
+  /* Set MSIZE bits according to DMA_MemoryDataSize value */
+  /* Set PL bits according to DMA_Priority value */
+  /* Set the MEM2MEM bit according to DMA_M2M value */
+  tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode |
+            DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc |
+            DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize |
+            DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M;
+
+  /* Write to DMAy Channelx CCR */
+  DMAy_Channelx->CCR = tmpreg;
+
+/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/
+  /* Write to DMAy Channelx CNDTR */
+  DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize;
+
+/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/
+  /* Write to DMAy Channelx CPAR */
+  DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr;
+
+/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/
+  /* Write to DMAy Channelx CMAR */
+  DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr;
+}
+
+/**
+  * @brief  Fills each DMA_InitStruct member with its default value.
+  * @param  DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will
+  *   be initialized.
+  * @retval None
+  */
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct)
+{
+/*-------------- Reset DMA init structure parameters values ------------------*/
+  /* Initialize the DMA_PeripheralBaseAddr member */
+  DMA_InitStruct->DMA_PeripheralBaseAddr = 0;
+  /* Initialize the DMA_MemoryBaseAddr member */
+  DMA_InitStruct->DMA_MemoryBaseAddr = 0;
+  /* Initialize the DMA_DIR member */
+  DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC;
+  /* Initialize the DMA_BufferSize member */
+  DMA_InitStruct->DMA_BufferSize = 0;
+  /* Initialize the DMA_PeripheralInc member */
+  DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+  /* Initialize the DMA_MemoryInc member */
+  DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable;
+  /* Initialize the DMA_PeripheralDataSize member */
+  DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+  /* Initialize the DMA_MemoryDataSize member */
+  DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+  /* Initialize the DMA_Mode member */
+  DMA_InitStruct->DMA_Mode = DMA_Mode_Normal;
+  /* Initialize the DMA_Priority member */
+  DMA_InitStruct->DMA_Priority = DMA_Priority_Low;
+  /* Initialize the DMA_M2M member */
+  DMA_InitStruct->DMA_M2M = DMA_M2M_Disable;
+}
+
+/**
+  * @brief  Enables or disables the specified DMAy Channelx.
+  * @param  DMAy_Channelx: where y can be 1 or 2 to select the DMA and 
+  *   x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
+  * @param  NewState: new state of the DMAy Channelx. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DMAy Channelx */
+    DMAy_Channelx->CCR |= CCR_ENABLE_Set;
+  }
+  else
+  {
+    /* Disable the selected DMAy Channelx */
+    DMAy_Channelx->CCR &= CCR_ENABLE_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified DMAy Channelx interrupts.
+  * @param  DMAy_Channelx: where y can be 1 or 2 to select the DMA and 
+  *   x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
+  * @param  DMA_IT: specifies the DMA interrupts sources to be enabled
+  *   or disabled. 
+  *   This parameter can be any combination of the following values:
+  *     @arg DMA_IT_TC:  Transfer complete interrupt mask
+  *     @arg DMA_IT_HT:  Half transfer interrupt mask
+  *     @arg DMA_IT_TE:  Transfer error interrupt mask
+  * @param  NewState: new state of the specified DMA interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+  assert_param(IS_DMA_CONFIG_IT(DMA_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DMA interrupts */
+    DMAy_Channelx->CCR |= DMA_IT;
+  }
+  else
+  {
+    /* Disable the selected DMA interrupts */
+    DMAy_Channelx->CCR &= ~DMA_IT;
+  }
+}
+
+/**
+  * @brief  Returns the number of remaining data units in the current
+  *   DMAy Channelx transfer.
+  * @param  DMAy_Channelx: where y can be 1 or 2 to select the DMA and 
+  *   x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel.
+  * @retval The number of remaining data units in the current DMAy Channelx
+  *   transfer.
+  */
+uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx));
+  /* Return the number of remaining data units for DMAy Channelx */
+  return ((uint16_t)(DMAy_Channelx->CNDTR));
+}
+
+/**
+  * @brief  Checks whether the specified DMAy Channelx flag is set or not.
+  * @param  DMA_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
+  *     @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
+  *     @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
+  *     @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
+  *     @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
+  *     @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
+  *     @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
+  *     @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
+  *     @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
+  *     @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
+  *     @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
+  *     @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
+  *     @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
+  *     @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
+  *     @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
+  *     @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
+  *     @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
+  *     @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
+  *     @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
+  *     @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
+  *     @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
+  *     @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
+  *     @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
+  *     @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
+  *     @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
+  *     @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
+  *     @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
+  *     @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
+  *     @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
+  *     @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
+  *     @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
+  *     @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
+  *     @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
+  *     @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
+  *     @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
+  *     @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
+  *     @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
+  *     @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
+  *     @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
+  *     @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
+  *     @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
+  *     @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
+  *     @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
+  *     @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
+  *     @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
+  *     @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
+  *     @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
+  *     @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
+  * @retval The new state of DMA_FLAG (SET or RESET).
+  */
+FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_DMA_GET_FLAG(DMA_FLAG));
+
+  /* Calculate the used DMA */
+  if ((DMA_FLAG & FLAG_Mask) != (uint32_t)RESET)
+  {
+    /* Get DMA2 ISR register value */
+    tmpreg = DMA2->ISR ;
+  }
+  else
+  {
+    /* Get DMA1 ISR register value */
+    tmpreg = DMA1->ISR ;
+  }
+
+  /* Check the status of the specified DMA flag */
+  if ((tmpreg & DMA_FLAG) != (uint32_t)RESET)
+  {
+    /* DMA_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* DMA_FLAG is reset */
+    bitstatus = RESET;
+  }
+  
+  /* Return the DMA_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the DMAy Channelx's pending flags.
+  * @param  DMA_FLAG: specifies the flag to clear.
+  *   This parameter can be any combination (for the same DMA) of the following values:
+  *     @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag.
+  *     @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag.
+  *     @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag.
+  *     @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag.
+  *     @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag.
+  *     @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag.
+  *     @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag.
+  *     @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag.
+  *     @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag.
+  *     @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag.
+  *     @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag.
+  *     @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag.
+  *     @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag.
+  *     @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag.
+  *     @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag.
+  *     @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag.
+  *     @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag.
+  *     @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag.
+  *     @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag.
+  *     @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag.
+  *     @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag.
+  *     @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag.
+  *     @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag.
+  *     @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag.
+  *     @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag.
+  *     @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag.
+  *     @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag.
+  *     @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag.
+  *     @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag.
+  *     @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag.
+  *     @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag.
+  *     @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag.
+  *     @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag.
+  *     @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag.
+  *     @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag.
+  *     @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag.
+  *     @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag.
+  *     @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag.
+  *     @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag.
+  *     @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag.
+  *     @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag.
+  *     @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag.
+  *     @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag.
+  *     @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag.
+  *     @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag.
+  *     @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag.
+  *     @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag.
+  *     @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag.
+  * @retval None
+  */
+void DMA_ClearFlag(uint32_t DMA_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_CLEAR_FLAG(DMA_FLAG));
+  /* Calculate the used DMA */
+
+  if ((DMA_FLAG & FLAG_Mask) != (uint32_t)RESET)
+  {
+    /* Clear the selected DMA flags */
+    DMA2->IFCR = DMA_FLAG;
+  }
+  else
+  {
+    /* Clear the selected DMA flags */
+    DMA1->IFCR = DMA_FLAG;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified DMAy Channelx interrupt has occurred or not.
+  * @param  DMA_IT: specifies the DMA interrupt source to check. 
+  *   This parameter can be one of the following values:
+  *     @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt.
+  *     @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
+  *     @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
+  *     @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
+  *     @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt.
+  *     @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
+  *     @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
+  *     @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
+  *     @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt.
+  *     @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
+  *     @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
+  *     @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
+  *     @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt.
+  *     @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
+  *     @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
+  *     @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
+  *     @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt.
+  *     @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
+  *     @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
+  *     @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
+  *     @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt.
+  *     @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
+  *     @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
+  *     @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
+  *     @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt.
+  *     @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
+  *     @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
+  *     @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
+  *     @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt.
+  *     @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
+  *     @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
+  *     @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
+  *     @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt.
+  *     @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
+  *     @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
+  *     @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
+  *     @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt.
+  *     @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
+  *     @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
+  *     @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
+  *     @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt.
+  *     @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
+  *     @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
+  *     @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
+  *     @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt.
+  *     @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
+  *     @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
+  *     @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
+  * @retval The new state of DMA_IT (SET or RESET).
+  */
+ITStatus DMA_GetITStatus(uint32_t DMA_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_DMA_GET_IT(DMA_IT));
+
+  /* Calculate the used DMA */
+  if ((DMA_IT & FLAG_Mask) != (uint32_t)RESET)
+  {
+    /* Get DMA2 ISR register value */
+    tmpreg = DMA2->ISR ;
+  }
+  else
+  {
+    /* Get DMA1 ISR register value */
+    tmpreg = DMA1->ISR ;
+  }
+
+  /* Check the status of the specified DMA interrupt */
+  if ((tmpreg & DMA_IT) != (uint32_t)RESET)
+  {
+    /* DMA_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* DMA_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the DMA_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the DMAy Channelx’s interrupt pending bits.
+  * @param  DMA_IT: specifies the DMA interrupt pending bit to clear.
+  *   This parameter can be any combination (for the same DMA) of the following values:
+  *     @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt.
+  *     @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt.
+  *     @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt.
+  *     @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt.
+  *     @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt.
+  *     @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt.
+  *     @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt.
+  *     @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt.
+  *     @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt.
+  *     @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt.
+  *     @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt.
+  *     @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt.
+  *     @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt.
+  *     @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt.
+  *     @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt.
+  *     @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt.
+  *     @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt.
+  *     @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt.
+  *     @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt.
+  *     @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt.
+  *     @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt.
+  *     @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt.
+  *     @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt.
+  *     @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt.
+  *     @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt.
+  *     @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt.
+  *     @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt.
+  *     @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt.
+  *     @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt.
+  *     @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt.
+  *     @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt.
+  *     @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt.
+  *     @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt.
+  *     @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt.
+  *     @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt.
+  *     @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt.
+  *     @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt.
+  *     @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt.
+  *     @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt.
+  *     @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt.
+  *     @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt.
+  *     @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt.
+  *     @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt.
+  *     @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt.
+  *     @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt.
+  *     @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt.
+  *     @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt.
+  *     @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt.
+  * @retval None
+  */
+void DMA_ClearITPendingBit(uint32_t DMA_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_CLEAR_IT(DMA_IT));
+
+  /* Calculate the used DMA */
+  if ((DMA_IT & FLAG_Mask) != (uint32_t)RESET)
+  {
+    /* Clear the selected DMA interrupt pending bits */
+    DMA2->IFCR = DMA_IT;
+  }
+  else
+  {
+    /* Clear the selected DMA interrupt pending bits */
+    DMA1->IFCR = DMA_IT;
+  }
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c
new file mode 100644
index 0000000000000000000000000000000000000000..6963200a0587d6f0346437f2df2e949c314f9d87
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c
@@ -0,0 +1,268 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_exti.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the EXTI firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_exti.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup EXTI 
+  * @brief EXTI driver modules
+  * @{
+  */
+
+/** @defgroup EXTI_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Private_Defines
+  * @{
+  */
+
+#define EXTI_LineNone    ((uint32_t)0x00000)  /* No interrupt selected */
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the EXTI peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void EXTI_DeInit(void)
+{
+  EXTI->IMR = 0x00000000;
+  EXTI->EMR = 0x00000000;
+  EXTI->RTSR = 0x00000000; 
+  EXTI->FTSR = 0x00000000; 
+  EXTI->PR = 0x000FFFFF;
+}
+
+/**
+  * @brief  Initializes the EXTI peripheral according to the specified
+  *   parameters in the EXTI_InitStruct.
+  * @param  EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
+  *   that contains the configuration information for the EXTI peripheral.
+  * @retval None
+  */
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+  uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
+  assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
+  assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));  
+  assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
+
+  tmp = (uint32_t)EXTI_BASE;
+     
+  if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
+  {
+    /* Clear EXTI line configuration */
+    EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
+    EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
+    
+    tmp += EXTI_InitStruct->EXTI_Mode;
+
+    *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
+
+    /* Clear Rising Falling edge configuration */
+    EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
+    EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
+    
+    /* Select the trigger for the selected external interrupts */
+    if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
+    {
+      /* Rising Falling edge */
+      EXTI->RTSR |= EXTI_InitStruct->EXTI_Line;
+      EXTI->FTSR |= EXTI_InitStruct->EXTI_Line;
+    }
+    else
+    {
+      tmp = (uint32_t)EXTI_BASE;
+      tmp += EXTI_InitStruct->EXTI_Trigger;
+
+      *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
+    }
+  }
+  else
+  {
+    tmp += EXTI_InitStruct->EXTI_Mode;
+
+    /* Disable the selected external lines */
+    *(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line;
+  }
+}
+
+/**
+  * @brief  Fills each EXTI_InitStruct member with its reset value.
+  * @param  EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will
+  *   be initialized.
+  * @retval None
+  */
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+  EXTI_InitStruct->EXTI_Line = EXTI_LineNone;
+  EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt;
+  EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling;
+  EXTI_InitStruct->EXTI_LineCmd = DISABLE;
+}
+
+/**
+  * @brief  Generates a Software interrupt.
+  * @param  EXTI_Line: specifies the EXTI lines to be enabled or disabled.
+  *   This parameter can be any combination of EXTI_Linex where x can be (0..19).
+  * @retval None
+  */
+void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line)
+{
+  /* Check the parameters */
+  assert_param(IS_EXTI_LINE(EXTI_Line));
+  
+  EXTI->SWIER |= EXTI_Line;
+}
+
+/**
+  * @brief  Checks whether the specified EXTI line flag is set or not.
+  * @param  EXTI_Line: specifies the EXTI line flag to check.
+  *   This parameter can be:
+  *     @arg EXTI_Linex: External interrupt line x where x(0..19)
+  * @retval The new state of EXTI_Line (SET or RESET).
+  */
+FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+  
+  if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the EXTI’s line pending flags.
+  * @param  EXTI_Line: specifies the EXTI lines flags to clear.
+  *   This parameter can be any combination of EXTI_Linex where x can be (0..19).
+  * @retval None
+  */
+void EXTI_ClearFlag(uint32_t EXTI_Line)
+{
+  /* Check the parameters */
+  assert_param(IS_EXTI_LINE(EXTI_Line));
+  
+  EXTI->PR = EXTI_Line;
+}
+
+/**
+  * @brief  Checks whether the specified EXTI line is asserted or not.
+  * @param  EXTI_Line: specifies the EXTI line to check.
+  *   This parameter can be:
+  *     @arg EXTI_Linex: External interrupt line x where x(0..19)
+  * @retval The new state of EXTI_Line (SET or RESET).
+  */
+ITStatus EXTI_GetITStatus(uint32_t EXTI_Line)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t enablestatus = 0;
+  /* Check the parameters */
+  assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+  
+  enablestatus =  EXTI->IMR & EXTI_Line;
+  if (((EXTI->PR & EXTI_Line) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the EXTI’s line pending bits.
+  * @param  EXTI_Line: specifies the EXTI lines to clear.
+  *   This parameter can be any combination of EXTI_Linex where x can be (0..19).
+  * @retval None
+  */
+void EXTI_ClearITPendingBit(uint32_t EXTI_Line)
+{
+  /* Check the parameters */
+  assert_param(IS_EXTI_LINE(EXTI_Line));
+  
+  EXTI->PR = EXTI_Line;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c
new file mode 100644
index 0000000000000000000000000000000000000000..ec194dc9c9891dde7855dbb97d766d8e0066040c
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c
@@ -0,0 +1,878 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_flash.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the FLASH firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_flash.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup FLASH 
+  * @brief FLASH driver modules
+  * @{
+  */ 
+
+/** @defgroup FLASH_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Private_Defines
+  * @{
+  */ 
+
+/* Flash Access Control Register bits */
+#define ACR_LATENCY_Mask         ((uint32_t)0x00000038)
+#define ACR_HLFCYA_Mask          ((uint32_t)0xFFFFFFF7)
+#define ACR_PRFTBE_Mask          ((uint32_t)0xFFFFFFEF)
+
+/* Flash Access Control Register bits */
+#define ACR_PRFTBS_Mask          ((uint32_t)0x00000020) 
+
+/* Flash Control Register bits */
+#define CR_PG_Set                ((uint32_t)0x00000001)
+#define CR_PG_Reset              ((uint32_t)0x00001FFE) 
+#define CR_PER_Set               ((uint32_t)0x00000002)
+#define CR_PER_Reset             ((uint32_t)0x00001FFD)
+#define CR_MER_Set               ((uint32_t)0x00000004)
+#define CR_MER_Reset             ((uint32_t)0x00001FFB)
+#define CR_OPTPG_Set             ((uint32_t)0x00000010)
+#define CR_OPTPG_Reset           ((uint32_t)0x00001FEF)
+#define CR_OPTER_Set             ((uint32_t)0x00000020)
+#define CR_OPTER_Reset           ((uint32_t)0x00001FDF)
+#define CR_STRT_Set              ((uint32_t)0x00000040)
+#define CR_LOCK_Set              ((uint32_t)0x00000080)
+
+/* FLASH Mask */
+#define RDPRT_Mask               ((uint32_t)0x00000002)
+#define WRP0_Mask                ((uint32_t)0x000000FF)
+#define WRP1_Mask                ((uint32_t)0x0000FF00)
+#define WRP2_Mask                ((uint32_t)0x00FF0000)
+#define WRP3_Mask                ((uint32_t)0xFF000000)
+
+/* FLASH Keys */
+#define RDP_Key                  ((uint16_t)0x00A5)
+#define FLASH_KEY1               ((uint32_t)0x45670123)
+#define FLASH_KEY2               ((uint32_t)0xCDEF89AB)
+
+/* Delay definition */   
+#define EraseTimeout             ((uint32_t)0x00000FFF)
+#define ProgramTimeout           ((uint32_t)0x0000000F)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Private_FunctionPrototypes
+  * @{
+  */
+
+static void delay(void);
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Sets the code latency value.
+  * @param  FLASH_Latency: specifies the FLASH Latency value.
+  *   This parameter can be one of the following values:
+  *     @arg FLASH_Latency_0: FLASH Zero Latency cycle
+  *     @arg FLASH_Latency_1: FLASH One Latency cycle
+  *     @arg FLASH_Latency_2: FLASH Two Latency cycles
+  * @retval None
+  */
+void FLASH_SetLatency(uint32_t FLASH_Latency)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_FLASH_LATENCY(FLASH_Latency));
+  
+  /* Read the ACR register */
+  tmpreg = FLASH->ACR;  
+  
+  /* Sets the Latency value */
+  tmpreg &= ACR_LATENCY_Mask;
+  tmpreg |= FLASH_Latency;
+  
+  /* Write the ACR register */
+  FLASH->ACR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the Half cycle flash access.
+  * @param  FLASH_HalfCycleAccess: specifies the FLASH Half cycle Access mode.
+  *   This parameter can be one of the following values:
+  *     @arg FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable
+  *     @arg FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable
+  * @retval None
+  */
+void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess)
+{
+  /* Check the parameters */
+  assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess));
+  
+  /* Enable or disable the Half cycle access */
+  FLASH->ACR &= ACR_HLFCYA_Mask;
+  FLASH->ACR |= FLASH_HalfCycleAccess;
+}
+
+/**
+  * @brief  Enables or disables the Prefetch Buffer.
+  * @param  FLASH_PrefetchBuffer: specifies the Prefetch buffer status.
+  *   This parameter can be one of the following values:
+  *     @arg FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable
+  *     @arg FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable
+  * @retval None
+  */
+void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer)
+{
+  /* Check the parameters */
+  assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer));
+  
+  /* Enable or disable the Prefetch Buffer */
+  FLASH->ACR &= ACR_PRFTBE_Mask;
+  FLASH->ACR |= FLASH_PrefetchBuffer;
+}
+
+/**
+  * @brief  Unlocks the FLASH Program Erase Controller.
+  * @param  None
+  * @retval None
+  */
+void FLASH_Unlock(void)
+{
+  /* Authorize the FPEC Access */
+  FLASH->KEYR = FLASH_KEY1;
+  FLASH->KEYR = FLASH_KEY2;
+}
+
+/**
+  * @brief  Locks the FLASH Program Erase Controller.
+  * @param  None
+  * @retval None
+  */
+void FLASH_Lock(void)
+{
+  /* Set the Lock Bit to lock the FPEC and the FCR */
+  FLASH->CR |= CR_LOCK_Set;
+}
+
+/**
+  * @brief  Erases a specified FLASH page.
+  * @param  Page_Address: The page address to be erased.
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+  */
+FLASH_Status FLASH_ErasePage(uint32_t Page_Address)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+  /* Check the parameters */
+  assert_param(IS_FLASH_ADDRESS(Page_Address));
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation(EraseTimeout);
+  
+  if(status == FLASH_COMPLETE)
+  { 
+    /* if the previous operation is completed, proceed to erase the page */
+    FLASH->CR|= CR_PER_Set;
+    FLASH->AR = Page_Address; 
+    FLASH->CR|= CR_STRT_Set;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(EraseTimeout);
+    if(status != FLASH_TIMEOUT)
+    {
+      /* if the erase operation is completed, disable the PER Bit */
+      FLASH->CR &= CR_PER_Reset;
+    }
+  }
+  /* Return the Erase Status */
+  return status;
+}
+
+/**
+  * @brief  Erases all FLASH pages.
+  * @param  None
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+  */
+FLASH_Status FLASH_EraseAllPages(void)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation(EraseTimeout);
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to erase all pages */
+     FLASH->CR |= CR_MER_Set;
+     FLASH->CR |= CR_STRT_Set;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(EraseTimeout);
+    if(status != FLASH_TIMEOUT)
+    {
+      /* if the erase operation is completed, disable the MER Bit */
+      FLASH->CR &= CR_MER_Reset;
+    }
+  }	   
+  /* Return the Erase Status */
+  return status;
+}
+
+/**
+  * @brief  Erases the FLASH option bytes.
+  * @note   This functions erases all option bytes and then deactivates the Read
+  *         protection. If the user needs to keep the Read protection activated,
+  *         he has to enable it after this function call (using
+  *         FLASH_ReadOutProtection function)
+  * @param  None
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+  */
+FLASH_Status FLASH_EraseOptionBytes(void)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation(EraseTimeout);
+  if(status == FLASH_COMPLETE)
+  {
+    /* Authorize the small information block programming */
+    FLASH->OPTKEYR = FLASH_KEY1;
+    FLASH->OPTKEYR = FLASH_KEY2;
+    
+    /* if the previous operation is completed, proceed to erase the option bytes */
+    FLASH->CR |= CR_OPTER_Set;
+    FLASH->CR |= CR_STRT_Set;
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(EraseTimeout);
+    
+    if(status == FLASH_COMPLETE)
+    {
+      /* if the erase operation is completed, disable the OPTER Bit */
+      FLASH->CR &= CR_OPTER_Reset;
+       
+      /* Enable the Option Bytes Programming operation */
+      FLASH->CR |= CR_OPTPG_Set;
+      /* Disable the Read protection */
+      OB->RDP= RDP_Key; 
+      /* Wait for last operation to be completed */
+      status = FLASH_WaitForLastOperation(ProgramTimeout);
+ 
+      if(status != FLASH_TIMEOUT)
+      {
+        /* if the program operation is completed, disable the OPTPG Bit */
+        FLASH->CR &= CR_OPTPG_Reset;
+      }
+    }
+    else
+    {
+      if (status != FLASH_TIMEOUT)
+      {
+        /* Disable the OPTPG Bit */
+        FLASH->CR &= CR_OPTPG_Reset;
+      }
+    }  
+  }
+  /* Return the erase status */
+  return status;
+}
+
+/**
+  * @brief  Programs a word at a specified address.
+  * @param  Address: specifies the address to be programmed.
+  * @param  Data: specifies the data to be programmed.
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. 
+  */
+FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_FLASH_ADDRESS(Address));
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation(ProgramTimeout);
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to program the new first 
+    half word */
+    FLASH->CR |= CR_PG_Set;
+  
+    *(__IO uint16_t*)Address = (uint16_t)Data;
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(ProgramTimeout);
+ 
+    if(status == FLASH_COMPLETE)
+    {
+      /* if the previous operation is completed, proceed to program the new second 
+      half word */
+      tmp = Address + 2;
+
+      *(__IO uint16_t*) tmp = Data >> 16;
+    
+      /* Wait for last operation to be completed */
+      status = FLASH_WaitForLastOperation(ProgramTimeout);
+        
+      if(status != FLASH_TIMEOUT)
+      {
+        /* Disable the PG Bit */
+        FLASH->CR &= CR_PG_Reset;
+      }
+    }
+    else
+    {
+      if (status != FLASH_TIMEOUT)
+      {
+        /* Disable the PG Bit */
+        FLASH->CR &= CR_PG_Reset;
+      }
+     }
+  }
+  /* Return the Program Status */
+  return status;
+}
+
+/**
+  * @brief  Programs a half word at a specified address.
+  * @param  Address: specifies the address to be programmed.
+  * @param  Data: specifies the data to be programmed.
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. 
+  */
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+  /* Check the parameters */
+  assert_param(IS_FLASH_ADDRESS(Address));
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation(ProgramTimeout);
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to program the new data */
+    FLASH->CR |= CR_PG_Set;
+  
+    *(__IO uint16_t*)Address = Data;
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(ProgramTimeout);
+    if(status != FLASH_TIMEOUT)
+    {
+      /* if the program operation is completed, disable the PG Bit */
+      FLASH->CR &= CR_PG_Reset;
+    }
+  } 
+  /* Return the Program Status */
+  return status;
+}
+
+/**
+  * @brief  Programs a half word at a specified Option Byte Data address.
+  * @param  Address: specifies the address to be programmed.
+  *   This parameter can be 0x1FFFF804 or 0x1FFFF806. 
+  * @param  Data: specifies the data to be programmed.
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. 
+  */
+FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+  /* Check the parameters */
+  assert_param(IS_OB_DATA_ADDRESS(Address));
+  status = FLASH_WaitForLastOperation(ProgramTimeout);
+  if(status == FLASH_COMPLETE)
+  {
+    /* Authorize the small information block programming */
+    FLASH->OPTKEYR = FLASH_KEY1;
+    FLASH->OPTKEYR = FLASH_KEY2;
+    /* Enables the Option Bytes Programming operation */
+    FLASH->CR |= CR_OPTPG_Set; 
+    *(__IO uint16_t*)Address = Data;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(ProgramTimeout);
+    if(status != FLASH_TIMEOUT)
+    {
+      /* if the program operation is completed, disable the OPTPG Bit */
+      FLASH->CR &= CR_OPTPG_Reset;
+    }
+  }    
+  /* Return the Option Byte Data Program Status */
+  return status;
+}
+
+/**
+  * @brief  Write protects the desired pages
+  * @param  FLASH_Pages: specifies the address of the pages to be write protected.
+  *   This parameter can be:
+  *     @arg For @b STM32_Low-density_devices: value between FLASH_WRProt_Pages0to3 and FLASH_WRProt_Pages28to31  
+  *     @arg For @b STM32_Medium-density_devices: value between FLASH_WRProt_Pages0to3
+  *       and FLASH_WRProt_Pages124to127
+  *     @arg For @b STM32_High-density_devices: value between FLASH_WRProt_Pages0to1 and
+  *       FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to255
+  *     @arg For @b STM32_Connectivity_line_devices: value between FLASH_WRProt_Pages0to1 and
+  *       FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to127    
+  *     @arg FLASH_WRProt_AllPages
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+  */
+FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages)
+{
+  uint16_t WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF, WRP2_Data = 0xFFFF, WRP3_Data = 0xFFFF;
+  
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Check the parameters */
+  assert_param(IS_FLASH_WRPROT_PAGE(FLASH_Pages));
+  
+  FLASH_Pages = (uint32_t)(~FLASH_Pages);
+  WRP0_Data = (uint16_t)(FLASH_Pages & WRP0_Mask);
+  WRP1_Data = (uint16_t)((FLASH_Pages & WRP1_Mask) >> 8);
+  WRP2_Data = (uint16_t)((FLASH_Pages & WRP2_Mask) >> 16);
+  WRP3_Data = (uint16_t)((FLASH_Pages & WRP3_Mask) >> 24);
+  
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation(ProgramTimeout);
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* Authorizes the small information block programming */
+    FLASH->OPTKEYR = FLASH_KEY1;
+    FLASH->OPTKEYR = FLASH_KEY2;
+    FLASH->CR |= CR_OPTPG_Set;
+    if(WRP0_Data != 0xFF)
+    {
+      OB->WRP0 = WRP0_Data;
+      
+      /* Wait for last operation to be completed */
+      status = FLASH_WaitForLastOperation(ProgramTimeout);
+    }
+    if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF))
+    {
+      OB->WRP1 = WRP1_Data;
+      
+      /* Wait for last operation to be completed */
+      status = FLASH_WaitForLastOperation(ProgramTimeout);
+    }
+    if((status == FLASH_COMPLETE) && (WRP2_Data != 0xFF))
+    {
+      OB->WRP2 = WRP2_Data;
+      
+      /* Wait for last operation to be completed */
+      status = FLASH_WaitForLastOperation(ProgramTimeout);
+    }
+    
+    if((status == FLASH_COMPLETE)&& (WRP3_Data != 0xFF))
+    {
+      OB->WRP3 = WRP3_Data;
+     
+      /* Wait for last operation to be completed */
+      status = FLASH_WaitForLastOperation(ProgramTimeout);
+    }
+          
+    if(status != FLASH_TIMEOUT)
+    {
+      /* if the program operation is completed, disable the OPTPG Bit */
+      FLASH->CR &= CR_OPTPG_Reset;
+    }
+  } 
+  /* Return the write protection operation Status */
+  return status;       
+}
+
+/**
+  * @brief  Enables or disables the read out protection.
+  * @note   If the user has already programmed the other option bytes before calling 
+  *   this function, he must re-program them since this function erases all option bytes.
+  * @param  Newstate: new state of the ReadOut Protection.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+  */
+FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  status = FLASH_WaitForLastOperation(EraseTimeout);
+  if(status == FLASH_COMPLETE)
+  {
+    /* Authorizes the small information block programming */
+    FLASH->OPTKEYR = FLASH_KEY1;
+    FLASH->OPTKEYR = FLASH_KEY2;
+    FLASH->CR |= CR_OPTER_Set;
+    FLASH->CR |= CR_STRT_Set;
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(EraseTimeout);
+    if(status == FLASH_COMPLETE)
+    {
+      /* if the erase operation is completed, disable the OPTER Bit */
+      FLASH->CR &= CR_OPTER_Reset;
+      /* Enable the Option Bytes Programming operation */
+      FLASH->CR |= CR_OPTPG_Set; 
+      if(NewState != DISABLE)
+      {
+        OB->RDP = 0x00;
+      }
+      else
+      {
+        OB->RDP = RDP_Key;  
+      }
+      /* Wait for last operation to be completed */
+      status = FLASH_WaitForLastOperation(EraseTimeout); 
+    
+      if(status != FLASH_TIMEOUT)
+      {
+        /* if the program operation is completed, disable the OPTPG Bit */
+        FLASH->CR &= CR_OPTPG_Reset;
+      }
+    }
+    else 
+    {
+      if(status != FLASH_TIMEOUT)
+      {
+        /* Disable the OPTER Bit */
+        FLASH->CR &= CR_OPTER_Reset;
+      }
+    }
+  }
+  /* Return the protection operation Status */
+  return status;      
+}
+
+/**
+  * @brief  Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY.
+  * @param  OB_IWDG: Selects the IWDG mode
+  *   This parameter can be one of the following values:
+  *     @arg OB_IWDG_SW: Software IWDG selected
+  *     @arg OB_IWDG_HW: Hardware IWDG selected
+  * @param  OB_STOP: Reset event when entering STOP mode.
+  *   This parameter can be one of the following values:
+  *     @arg OB_STOP_NoRST: No reset generated when entering in STOP
+  *     @arg OB_STOP_RST: Reset generated when entering in STOP
+  * @param  OB_STDBY: Reset event when entering Standby mode.
+  *   This parameter can be one of the following values:
+  *     @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY
+  *     @arg OB_STDBY_RST: Reset generated when entering in STANDBY
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, 
+  * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+  */
+FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY)
+{
+  FLASH_Status status = FLASH_COMPLETE; 
+
+  /* Check the parameters */
+  assert_param(IS_OB_IWDG_SOURCE(OB_IWDG));
+  assert_param(IS_OB_STOP_SOURCE(OB_STOP));
+  assert_param(IS_OB_STDBY_SOURCE(OB_STDBY));
+
+  /* Authorize the small information block programming */
+  FLASH->OPTKEYR = FLASH_KEY1;
+  FLASH->OPTKEYR = FLASH_KEY2;
+  
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation(ProgramTimeout);
+  
+  if(status == FLASH_COMPLETE)
+  {  
+    /* Enable the Option Bytes Programming operation */
+    FLASH->CR |= CR_OPTPG_Set; 
+           
+    OB->USER = OB_IWDG | (uint16_t)(OB_STOP | (uint16_t)(OB_STDBY | ((uint16_t)0xF8))); 
+  
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation(ProgramTimeout);
+    if(status != FLASH_TIMEOUT)
+    {
+      /* if the program operation is completed, disable the OPTPG Bit */
+      FLASH->CR &= CR_OPTPG_Reset;
+    }
+  }    
+  /* Return the Option Byte program Status */
+  return status;
+}
+
+/**
+  * @brief  Returns the FLASH User Option Bytes values.
+  * @param  None
+  * @retval The FLASH User Option Bytes values:IWDG_SW(Bit0), RST_STOP(Bit1)
+  *   and RST_STDBY(Bit2).
+  */
+uint32_t FLASH_GetUserOptionByte(void)
+{
+  /* Return the User Option Byte */
+  return (uint32_t)(FLASH->OBR >> 2);
+}
+
+/**
+  * @brief  Returns the FLASH Write Protection Option Bytes Register value.
+  * @param  None
+  * @retval The FLASH Write Protection  Option Bytes Register value
+  */
+uint32_t FLASH_GetWriteProtectionOptionByte(void)
+{
+  /* Return the Falsh write protection Register value */
+  return (uint32_t)(FLASH->WRPR);
+}
+
+/**
+  * @brief  Checks whether the FLASH Read Out Protection Status is set or not.
+  * @param  None
+  * @retval FLASH ReadOut Protection Status(SET or RESET)
+  */
+FlagStatus FLASH_GetReadOutProtectionStatus(void)
+{
+  FlagStatus readoutstatus = RESET;
+  if ((FLASH->OBR & RDPRT_Mask) != (uint32_t)RESET)
+  {
+    readoutstatus = SET;
+  }
+  else
+  {
+    readoutstatus = RESET;
+  }
+  return readoutstatus;
+}
+
+/**
+  * @brief  Checks whether the FLASH Prefetch Buffer status is set or not.
+  * @param  None
+  * @retval FLASH Prefetch Buffer Status (SET or RESET).
+  */
+FlagStatus FLASH_GetPrefetchBufferStatus(void)
+{
+  FlagStatus bitstatus = RESET;
+  
+  if ((FLASH->ACR & ACR_PRFTBS_Mask) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the new state of FLASH Prefetch Buffer Status (SET or RESET) */
+  return bitstatus; 
+}
+
+/**
+  * @brief  Enables or disables the specified FLASH interrupts.
+  * @param  FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled.
+  *   This parameter can be any combination of the following values:
+  *     @arg FLASH_IT_ERROR: FLASH Error Interrupt
+  *     @arg FLASH_IT_EOP: FLASH end of operation Interrupt
+  * @param  NewState: new state of the specified Flash interrupts.
+  *   This parameter can be: ENABLE or DISABLE.      
+  * @retval None 
+  */
+void FLASH_ITConfig(uint16_t FLASH_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FLASH_IT(FLASH_IT)); 
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if(NewState != DISABLE)
+  {
+    /* Enable the interrupt sources */
+    FLASH->CR |= FLASH_IT;
+  }
+  else
+  {
+    /* Disable the interrupt sources */
+    FLASH->CR &= ~(uint32_t)FLASH_IT;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified FLASH flag is set or not.
+  * @param  FLASH_FLAG: specifies the FLASH flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg FLASH_FLAG_BSY: FLASH Busy flag           
+  *     @arg FLASH_FLAG_PGERR: FLASH Program error flag       
+  *     @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag      
+  *     @arg FLASH_FLAG_EOP: FLASH End of Operation flag           
+  *     @arg FLASH_FLAG_OPTERR:  FLASH Option Byte error flag     
+  * @retval The new state of FLASH_FLAG (SET or RESET).
+  */
+FlagStatus FLASH_GetFlagStatus(uint16_t FLASH_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ;
+  if(FLASH_FLAG == FLASH_FLAG_OPTERR) 
+  {
+    if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET)
+    {
+      bitstatus = SET;
+    }
+    else
+    {
+      bitstatus = RESET;
+    }
+  }
+  else
+  {
+   if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET)
+    {
+      bitstatus = SET;
+    }
+    else
+    {
+      bitstatus = RESET;
+    }
+  }
+  /* Return the new state of FLASH_FLAG (SET or RESET) */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the FLASH’s pending flags.
+  * @param  FLASH_FLAG: specifies the FLASH flags to clear.
+  *   This parameter can be any combination of the following values:         
+  *     @arg FLASH_FLAG_PGERR: FLASH Program error flag       
+  *     @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag      
+  *     @arg FLASH_FLAG_EOP: FLASH End of Operation flag           
+  * @retval None
+  */
+void FLASH_ClearFlag(uint16_t FLASH_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ;
+  
+  /* Clear the flags */
+  FLASH->SR = FLASH_FLAG;
+}
+
+/**
+  * @brief  Returns the FLASH Status.
+  * @param  None
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP or FLASH_COMPLETE
+  */
+FLASH_Status FLASH_GetStatus(void)
+{
+  FLASH_Status flashstatus = FLASH_COMPLETE;
+  
+  if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) 
+  {
+    flashstatus = FLASH_BUSY;
+  }
+  else 
+  {  
+    if((FLASH->SR & FLASH_FLAG_PGERR) != 0)
+    { 
+      flashstatus = FLASH_ERROR_PG;
+    }
+    else 
+    {
+      if((FLASH->SR & FLASH_FLAG_WRPRTERR) != 0 )
+      {
+        flashstatus = FLASH_ERROR_WRP;
+      }
+      else
+      {
+        flashstatus = FLASH_COMPLETE;
+      }
+    }
+  }
+  /* Return the Flash Status */
+  return flashstatus;
+}
+
+/**
+  * @brief  Waits for a Flash operation to complete or a TIMEOUT to occur.
+  * @param  Timeout: FLASH progamming Timeout
+  * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG,
+  *   FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
+  */
+FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout)
+{ 
+  FLASH_Status status = FLASH_COMPLETE;
+   
+  /* Check for the Flash Status */
+  status = FLASH_GetStatus();
+  /* Wait for a Flash operation to complete or a TIMEOUT to occur */
+  while((status == FLASH_BUSY) && (Timeout != 0x00))
+  {
+    delay();
+    status = FLASH_GetStatus();
+    Timeout--;
+  }
+  if(Timeout == 0x00 )
+  {
+    status = FLASH_TIMEOUT;
+  }
+  /* Return the operation status */
+  return status;
+}
+
+/**
+  * @brief  Inserts a time delay.
+  * @param  None
+  * @retval None
+  */
+static void delay(void)
+{
+  __IO uint32_t i = 0;
+  for(i = 0xFF; i != 0; i--)
+  {
+  }
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c
new file mode 100644
index 0000000000000000000000000000000000000000..9b7b0776314f5aee59af0365efba026fd1f77a9a
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c
@@ -0,0 +1,858 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_fsmc.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the FSMC firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_fsmc.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup FSMC 
+  * @brief FSMC driver modules
+  * @{
+  */ 
+
+/** @defgroup FSMC_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Private_Defines
+  * @{
+  */
+
+/* --------------------- FSMC registers bit mask ---------------------------- */
+
+/* FSMC BCRx Mask */
+#define BCR_MBKEN_Set                       ((uint32_t)0x00000001)
+#define BCR_MBKEN_Reset                     ((uint32_t)0x000FFFFE)
+#define BCR_FACCEN_Set                      ((uint32_t)0x00000040)
+
+/* FSMC PCRx Mask */
+#define PCR_PBKEN_Set                       ((uint32_t)0x00000004)
+#define PCR_PBKEN_Reset                     ((uint32_t)0x000FFFFB)
+#define PCR_ECCEN_Set                       ((uint32_t)0x00000040)
+#define PCR_ECCEN_Reset                     ((uint32_t)0x000FFFBF)
+#define PCR_MemoryType_NAND                 ((uint32_t)0x00000008)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the FSMC NOR/SRAM Banks registers to their default 
+  *   reset values.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1  
+  *     @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 
+  *     @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 
+  *     @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 
+  * @retval None
+  */
+void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank)
+{
+  /* Check the parameter */
+  assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+  
+  /* FSMC_Bank1_NORSRAM1 */
+  if(FSMC_Bank == FSMC_Bank1_NORSRAM1)
+  {
+    FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB;    
+  }
+  /* FSMC_Bank1_NORSRAM2,  FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */
+  else
+  {   
+    FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2; 
+  }
+  FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF;
+  FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF;  
+}
+
+/**
+  * @brief  Deinitializes the FSMC NAND Banks registers to their default reset values.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND 
+  * @retval None
+  */
+void FSMC_NANDDeInit(uint32_t FSMC_Bank)
+{
+  /* Check the parameter */
+  assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    /* Set the FSMC_Bank2 registers to their reset values */
+    FSMC_Bank2->PCR2 = 0x00000018;
+    FSMC_Bank2->SR2 = 0x00000040;
+    FSMC_Bank2->PMEM2 = 0xFCFCFCFC;
+    FSMC_Bank2->PATT2 = 0xFCFCFCFC;  
+  }
+  /* FSMC_Bank3_NAND */  
+  else
+  {
+    /* Set the FSMC_Bank3 registers to their reset values */
+    FSMC_Bank3->PCR3 = 0x00000018;
+    FSMC_Bank3->SR3 = 0x00000040;
+    FSMC_Bank3->PMEM3 = 0xFCFCFCFC;
+    FSMC_Bank3->PATT3 = 0xFCFCFCFC; 
+  }  
+}
+
+/**
+  * @brief  Deinitializes the FSMC PCCARD Bank registers to their default reset values.
+  * @param  None                       
+  * @retval None
+  */
+void FSMC_PCCARDDeInit(void)
+{
+  /* Set the FSMC_Bank4 registers to their reset values */
+  FSMC_Bank4->PCR4 = 0x00000018; 
+  FSMC_Bank4->SR4 = 0x00000000;	
+  FSMC_Bank4->PMEM4 = 0xFCFCFCFC;
+  FSMC_Bank4->PATT4 = 0xFCFCFCFC;
+  FSMC_Bank4->PIO4 = 0xFCFCFCFC;
+}
+
+/**
+  * @brief  Initializes the FSMC NOR/SRAM Banks according to the specified
+  *   parameters in the FSMC_NORSRAMInitStruct.
+  * @param  FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef
+  *   structure that contains the configuration information for 
+  *   the FSMC NOR/SRAM specified Banks.                       
+  * @retval None
+  */
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank));
+  assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux));
+  assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType));
+  assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth));
+  assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode));
+  assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity));
+  assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode));
+  assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive));
+  assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation));
+  assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal));
+  assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode));
+  assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst));  
+  assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime));
+  assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime));
+  assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime));
+  assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration));
+  assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision));
+  assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency));
+  assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode)); 
+  
+  /* Bank1 NOR/SRAM control register configuration */ 
+  FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 
+            (uint32_t)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux |
+            FSMC_NORSRAMInitStruct->FSMC_MemoryType |
+            FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth |
+            FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode |
+            FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity |
+            FSMC_NORSRAMInitStruct->FSMC_WrapMode |
+            FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive |
+            FSMC_NORSRAMInitStruct->FSMC_WriteOperation |
+            FSMC_NORSRAMInitStruct->FSMC_WaitSignal |
+            FSMC_NORSRAMInitStruct->FSMC_ExtendedMode |
+            FSMC_NORSRAMInitStruct->FSMC_WriteBurst;
+  if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR)
+  {
+    FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (uint32_t)BCR_FACCEN_Set;
+  }
+  /* Bank1 NOR/SRAM timing register configuration */
+  FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] = 
+            (uint32_t)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) |
+             FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode;
+            
+    
+  /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */
+  if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable)
+  {
+    assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime));
+    assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime));
+    assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime));
+    assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision));
+    assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency));
+    assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode));
+    FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 
+              (uint32_t)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime |
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )|
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) |
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) |
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) |
+               FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode;
+  }
+  else
+  {
+    FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF;
+  }
+}
+
+/**
+  * @brief  Initializes the FSMC NAND Banks according to the specified 
+  *   parameters in the FSMC_NANDInitStruct.
+  * @param  FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef 
+  *   structure that contains the configuration information for the FSMC NAND specified Banks.                       
+  * @retval None
+  */
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{
+  uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; 
+    
+  /* Check the parameters */
+  assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank));
+  assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature));
+  assert_param( IS_FSMC_MEMORY_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth));
+  assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC));
+  assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize));
+  assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime));
+  assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime));
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+  
+  /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */
+  tmppcr = (uint32_t)FSMC_NANDInitStruct->FSMC_Waitfeature |
+            PCR_MemoryType_NAND |
+            FSMC_NANDInitStruct->FSMC_MemoryDataWidth |
+            FSMC_NANDInitStruct->FSMC_ECC |
+            FSMC_NANDInitStruct->FSMC_ECCPageSize |
+            (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )|
+            (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13);
+            
+  /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */
+  tmppmem = (uint32_t)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+            (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+            (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+            (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); 
+            
+  /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */
+  tmppatt = (uint32_t)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+            (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+            (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+            (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+  
+  if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    /* FSMC_Bank2_NAND registers configuration */
+    FSMC_Bank2->PCR2 = tmppcr;
+    FSMC_Bank2->PMEM2 = tmppmem;
+    FSMC_Bank2->PATT2 = tmppatt;
+  }
+  else
+  {
+    /* FSMC_Bank3_NAND registers configuration */
+    FSMC_Bank3->PCR3 = tmppcr;
+    FSMC_Bank3->PMEM3 = tmppmem;
+    FSMC_Bank3->PATT3 = tmppatt;
+  }
+}
+
+/**
+  * @brief  Initializes the FSMC PCCARD Bank according to the specified 
+  *   parameters in the FSMC_PCCARDInitStruct.
+  * @param  FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef
+  *   structure that contains the configuration information for the FSMC PCCARD Bank.                       
+  * @retval None
+  */
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature));
+  assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime));
+  assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime));
+ 
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+  
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime));
+  
+  /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */
+  FSMC_Bank4->PCR4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_Waitfeature |
+                     FSMC_MemoryDataWidth_16b |  
+                     (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) |
+                     (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13);
+            
+  /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */
+  FSMC_Bank4->PMEM4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+                      (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+                      (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+                      (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); 
+            
+  /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */
+  FSMC_Bank4->PATT4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+                      (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+                      (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+                      (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);	
+            
+  /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */
+  FSMC_Bank4->PIO4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime |
+                     (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+                     (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+                     (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24);             
+}
+
+/**
+  * @brief  Fills each FSMC_NORSRAMInitStruct member with its default value.
+  * @param  FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef 
+  *   structure which will be initialized.
+  * @retval None
+  */
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{  
+  /* Reset NOR/SRAM Init structure parameters values */
+  FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1;
+  FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable;
+  FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM;
+  FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+  FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+  FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+  FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+  FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable;
+  FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; 
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A;
+}
+
+/**
+  * @brief  Fills each FSMC_NANDInitStruct member with its default value.
+  * @param  FSMC_NANDInitStruct: pointer to a FSMC_NANDInitTypeDef 
+  *   structure which will be initialized.
+  * @retval None
+  */
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{ 
+  /* Reset NAND Init structure parameters values */
+  FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND;
+  FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+  FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+  FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable;
+  FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes;
+  FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0;
+  FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;	  
+}
+
+/**
+  * @brief  Fills each FSMC_PCCARDInitStruct member with its default value.
+  * @param  FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef 
+  *   structure which will be initialized.
+  * @retval None
+  */
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+  /* Reset PCCARD Init structure parameters values */
+  FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+  FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0;
+  FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;	
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+}
+
+/**
+  * @brief  Enables or disables the specified NOR/SRAM Memory Bank.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1  
+  *     @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 
+  *     @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 
+  *     @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 
+  * @param  NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */
+    FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_Set;
+  }
+  else
+  {
+    /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */
+    FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified NAND Memory Bank.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  * @param  NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 |= PCR_PBKEN_Set;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 |= PCR_PBKEN_Set;
+    }
+  }
+  else
+  {
+    /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 &= PCR_PBKEN_Reset;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 &= PCR_PBKEN_Reset;
+    }
+  }
+}
+
+/**
+  * @brief  Enables or disables the PCCARD Memory Bank.
+  * @param  NewState: new state of the PCCARD Memory Bank.  
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_PCCARDCmd(FunctionalState NewState)
+{
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */
+    FSMC_Bank4->PCR4 |= PCR_PBKEN_Set;
+  }
+  else
+  {
+    /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */
+    FSMC_Bank4->PCR4 &= PCR_PBKEN_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the FSMC NAND ECC feature.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  * @param  NewState: new state of the FSMC NAND ECC feature.  
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 |= PCR_ECCEN_Set;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 |= PCR_ECCEN_Set;
+    }
+  }
+  else
+  {
+    /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 &= PCR_ECCEN_Reset;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 &= PCR_ECCEN_Reset;
+    }
+  }
+}
+
+/**
+  * @brief  Returns the error correction code register value.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  * @retval The Error Correction Code (ECC) value.
+  */
+uint32_t FSMC_GetECC(uint32_t FSMC_Bank)
+{
+  uint32_t eccval = 0x00000000;
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    /* Get the ECCR2 register value */
+    eccval = FSMC_Bank2->ECCR2;
+  }
+  else
+  {
+    /* Get the ECCR3 register value */
+    eccval = FSMC_Bank3->ECCR3;
+  }
+  /* Return the error correction code value */
+  return(eccval);
+}
+
+/**
+  * @brief  Enables or disables the specified FSMC interrupts.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *     @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_IT: specifies the FSMC interrupt sources to be enabled or disabled.
+  *   This parameter can be any combination of the following values:
+  *     @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *     @arg FSMC_IT_Level: Level edge detection interrupt.
+  *     @arg FSMC_IT_FallingEdge: Falling edge detection interrupt.
+  * @param  NewState: new state of the specified FSMC interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_IT(FSMC_IT));	
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected FSMC_Bank2 interrupts */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->SR2 |= FSMC_IT;
+    }
+    /* Enable the selected FSMC_Bank3 interrupts */
+    else if (FSMC_Bank == FSMC_Bank3_NAND)
+    {
+      FSMC_Bank3->SR3 |= FSMC_IT;
+    }
+    /* Enable the selected FSMC_Bank4 interrupts */
+    else
+    {
+      FSMC_Bank4->SR4 |= FSMC_IT;    
+    }
+  }
+  else
+  {
+    /* Disable the selected FSMC_Bank2 interrupts */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      
+      FSMC_Bank2->SR2 &= (uint32_t)~FSMC_IT;
+    }
+    /* Disable the selected FSMC_Bank3 interrupts */
+    else if (FSMC_Bank == FSMC_Bank3_NAND)
+    {
+      FSMC_Bank3->SR3 &= (uint32_t)~FSMC_IT;
+    }
+    /* Disable the selected FSMC_Bank4 interrupts */
+    else
+    {
+      FSMC_Bank4->SR4 &= (uint32_t)~FSMC_IT;    
+    }
+  }
+}
+
+/**
+  * @brief  Checks whether the specified FSMC flag is set or not.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *     @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag.
+  *     @arg FSMC_FLAG_Level: Level detection Flag.
+  *     @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag.
+  *     @arg FSMC_FLAG_FEMPT: Fifo empty Flag. 
+  * @retval The new state of FSMC_FLAG (SET or RESET).
+  */
+FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t tmpsr = 0x00000000;
+  
+  /* Check the parameters */
+  assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG));
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    tmpsr = FSMC_Bank2->SR2;
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    tmpsr = FSMC_Bank3->SR3;
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    tmpsr = FSMC_Bank4->SR4;
+  } 
+  
+  /* Get the flag status */
+  if ((tmpsr & FSMC_FLAG) != (uint16_t)RESET )
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the FSMC’s pending flags.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *     @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_FLAG: specifies the flag to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag.
+  *     @arg FSMC_FLAG_Level: Level detection Flag.
+  *     @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag.
+  * @retval None
+  */
+void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG)
+{
+ /* Check the parameters */
+  assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ;
+    
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    FSMC_Bank2->SR2 &= ~FSMC_FLAG; 
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    FSMC_Bank3->SR3 &= ~FSMC_FLAG;
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    FSMC_Bank4->SR4 &= ~FSMC_FLAG;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified FSMC interrupt has occurred or not.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *     @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_IT: specifies the FSMC interrupt source to check.
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *     @arg FSMC_IT_Level: Level edge detection interrupt.
+  *     @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. 
+  * @retval The new state of FSMC_IT (SET or RESET).
+  */
+ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t tmpsr = 0x0, itstatus = 0x0, itenable = 0x0; 
+  
+  /* Check the parameters */
+  assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_GET_IT(FSMC_IT));
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    tmpsr = FSMC_Bank2->SR2;
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    tmpsr = FSMC_Bank3->SR3;
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    tmpsr = FSMC_Bank4->SR4;
+  } 
+  
+  itstatus = tmpsr & FSMC_IT;
+  
+  itenable = tmpsr & (FSMC_IT >> 3);
+  if ((itstatus != (uint32_t)RESET)  && (itenable != (uint32_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus; 
+}
+
+/**
+  * @brief  Clears the FSMC’s interrupt pending bits.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *   This parameter can be one of the following values:
+  *     @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *     @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *     @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_IT: specifies the interrupt pending bit to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *     @arg FSMC_IT_Level: Level edge detection interrupt.
+  *     @arg FSMC_IT_FallingEdge: Falling edge detection interrupt.
+  * @retval None
+  */
+void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_IT(FSMC_IT));
+    
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3); 
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3);
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3);
+  }
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c
new file mode 100644
index 0000000000000000000000000000000000000000..262992e0dfd84bd932b38a95b1607a9c62c4e3e3
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c
@@ -0,0 +1,617 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_gpio.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the GPIO firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_gpio.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup GPIO 
+  * @brief GPIO driver modules
+  * @{
+  */ 
+
+/** @defgroup GPIO_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Private_Defines
+  * @{
+  */
+
+/* ------------ RCC registers bit address in the alias region ----------------*/
+#define AFIO_OFFSET                 (AFIO_BASE - PERIPH_BASE)
+
+/* --- EVENTCR Register -----*/
+
+/* Alias word address of EVOE bit */
+#define EVCR_OFFSET                 (AFIO_OFFSET + 0x00)
+#define EVOE_BitNumber              ((uint8_t)0x07)
+#define EVCR_EVOE_BB                (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4))
+
+
+/* ---  MAPR Register ---*/ 
+/* Alias word address of MII_RMII_SEL bit */ 
+#define MAPR_OFFSET                 (AFIO_OFFSET + 0x04) 
+#define MII_RMII_SEL_BitNumber      ((uint8_t)0x17) 
+#define MAPR_MII_RMII_SEL_BB        (PERIPH_BB_BASE + (MAPR_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4))
+
+
+#define EVCR_PORTPINCONFIG_MASK     ((uint16_t)0xFF80)
+#define LSB_MASK                    ((uint16_t)0xFFFF)
+#define DBGAFR_POSITION_MASK        ((uint32_t)0x000F0000)
+#define DBGAFR_SWJCFG_MASK          ((uint32_t)0xF0FFFFFF)
+#define DBGAFR_LOCATION_MASK        ((uint32_t)0x00200000)
+#define DBGAFR_NUMBITS_MASK         ((uint32_t)0x00100000)
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the GPIOx peripheral registers to their default reset values.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @retval None
+  */
+void GPIO_DeInit(GPIO_TypeDef* GPIOx)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  
+  if (GPIOx == GPIOA)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE);
+  }
+  else if (GPIOx == GPIOB)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE);
+  }
+  else if (GPIOx == GPIOC)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE);
+  }
+  else if (GPIOx == GPIOD)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE);
+  }    
+  else if (GPIOx == GPIOE)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE);
+  } 
+  else if (GPIOx == GPIOF)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE);
+  }
+  else
+  {
+    if (GPIOx == GPIOG)
+    {
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE);
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE);
+    }
+  }
+}
+
+/**
+  * @brief  Deinitializes the Alternate Functions (remap, event control
+  *   and EXTI configuration) registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void GPIO_AFIODeInit(void)
+{
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE);
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE);
+}
+
+/**
+  * @brief  Initializes the GPIOx peripheral according to the specified
+  *   parameters in the GPIO_InitStruct.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that
+  *   contains the configuration information for the specified GPIO peripheral.
+  * @retval None
+  */
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
+{
+  uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00;
+  uint32_t tmpreg = 0x00, pinmask = 0x00;
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode));
+  assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));  
+  
+/*---------------------------- GPIO Mode Configuration -----------------------*/
+  currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F);
+  if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00)
+  { 
+    /* Check the parameters */
+    assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed));
+    /* Output mode */
+    currentmode |= (uint32_t)GPIO_InitStruct->GPIO_Speed;
+  }
+/*---------------------------- GPIO CRL Configuration ------------------------*/
+  /* Configure the eight low port pins */
+  if (((uint32_t)GPIO_InitStruct->GPIO_Pin & ((uint32_t)0x00FF)) != 0x00)
+  {
+    tmpreg = GPIOx->CRL;
+    for (pinpos = 0x00; pinpos < 0x08; pinpos++)
+    {
+      pos = ((uint32_t)0x01) << pinpos;
+      /* Get the port pins position */
+      currentpin = (GPIO_InitStruct->GPIO_Pin) & pos;
+      if (currentpin == pos)
+      {
+        pos = pinpos << 2;
+        /* Clear the corresponding low control register bits */
+        pinmask = ((uint32_t)0x0F) << pos;
+        tmpreg &= ~pinmask;
+        /* Write the mode configuration in the corresponding bits */
+        tmpreg |= (currentmode << pos);
+        /* Reset the corresponding ODR bit */
+        if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
+        {
+          GPIOx->BRR = (((uint32_t)0x01) << pinpos);
+        }
+        else
+        {
+          /* Set the corresponding ODR bit */
+          if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
+          {
+            GPIOx->BSRR = (((uint32_t)0x01) << pinpos);
+          }
+        }
+      }
+    }
+    GPIOx->CRL = tmpreg;
+  }
+/*---------------------------- GPIO CRH Configuration ------------------------*/
+  /* Configure the eight high port pins */
+  if (GPIO_InitStruct->GPIO_Pin > 0x00FF)
+  {
+    tmpreg = GPIOx->CRH;
+    for (pinpos = 0x00; pinpos < 0x08; pinpos++)
+    {
+      pos = (((uint32_t)0x01) << (pinpos + 0x08));
+      /* Get the port pins position */
+      currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos);
+      if (currentpin == pos)
+      {
+        pos = pinpos << 2;
+        /* Clear the corresponding high control register bits */
+        pinmask = ((uint32_t)0x0F) << pos;
+        tmpreg &= ~pinmask;
+        /* Write the mode configuration in the corresponding bits */
+        tmpreg |= (currentmode << pos);
+        /* Reset the corresponding ODR bit */
+        if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD)
+        {
+          GPIOx->BRR = (((uint32_t)0x01) << (pinpos + 0x08));
+        }
+        /* Set the corresponding ODR bit */
+        if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU)
+        {
+          GPIOx->BSRR = (((uint32_t)0x01) << (pinpos + 0x08));
+        }
+      }
+    }
+    GPIOx->CRH = tmpreg;
+  }
+}
+
+/**
+  * @brief  Fills each GPIO_InitStruct member with its default value.
+  * @param  GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will
+  *   be initialized.
+  * @retval None
+  */
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct)
+{
+  /* Reset GPIO init structure parameters values */
+  GPIO_InitStruct->GPIO_Pin  = GPIO_Pin_All;
+  GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz;
+  GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING;
+}
+
+/**
+  * @brief  Reads the specified input port pin.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  GPIO_Pin:  specifies the port bit to read.
+  *   This parameter can be GPIO_Pin_x where x can be (0..15).
+  * @retval The input port pin value.
+  */
+uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  uint8_t bitstatus = 0x00;
+  
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); 
+  
+  if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET)
+  {
+    bitstatus = (uint8_t)Bit_SET;
+  }
+  else
+  {
+    bitstatus = (uint8_t)Bit_RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Reads the specified GPIO input data port.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @retval GPIO input data port value.
+  */
+uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  
+  return ((uint16_t)GPIOx->IDR);
+}
+
+/**
+  * @brief  Reads the specified output data port bit.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  GPIO_Pin:  specifies the port bit to read.
+  *   This parameter can be GPIO_Pin_x where x can be (0..15).
+  * @retval The output port pin value.
+  */
+uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  uint8_t bitstatus = 0x00;
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); 
+  
+  if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET)
+  {
+    bitstatus = (uint8_t)Bit_SET;
+  }
+  else
+  {
+    bitstatus = (uint8_t)Bit_RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Reads the specified GPIO output data port.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @retval GPIO output data port value.
+  */
+uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+    
+  return ((uint16_t)GPIOx->ODR);
+}
+
+/**
+  * @brief  Sets the selected data port bits.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  GPIO_Pin: specifies the port bits to be written.
+  *   This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
+  * @retval None
+  */
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN(GPIO_Pin));
+  
+  GPIOx->BSRR = GPIO_Pin;
+}
+
+/**
+  * @brief  Clears the selected data port bits.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  GPIO_Pin: specifies the port bits to be written.
+  *   This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
+  * @retval None
+  */
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN(GPIO_Pin));
+  
+  GPIOx->BRR = GPIO_Pin;
+}
+
+/**
+  * @brief  Sets or clears the selected data port bit.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  GPIO_Pin: specifies the port bit to be written.
+  *   This parameter can be one of GPIO_Pin_x where x can be (0..15).
+  * @param  BitVal: specifies the value to be written to the selected bit.
+  *   This parameter can be one of the BitAction enum values:
+  *     @arg Bit_RESET: to clear the port pin
+  *     @arg Bit_SET: to set the port pin
+  * @retval None
+  */
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+  assert_param(IS_GPIO_BIT_ACTION(BitVal)); 
+  
+  if (BitVal != Bit_RESET)
+  {
+    GPIOx->BSRR = GPIO_Pin;
+  }
+  else
+  {
+    GPIOx->BRR = GPIO_Pin;
+  }
+}
+
+/**
+  * @brief  Writes data to the specified GPIO data port.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  PortVal: specifies the value to be written to the port output data register.
+  * @retval None
+  */
+void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  
+  GPIOx->ODR = PortVal;
+}
+
+/**
+  * @brief  Locks GPIO Pins configuration registers.
+  * @param  GPIOx: where x can be (A..G) to select the GPIO peripheral.
+  * @param  GPIO_Pin: specifies the port bit to be written.
+  *   This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
+  * @retval None
+  */
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  uint32_t tmp = 0x00010000;
+  
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN(GPIO_Pin));
+  
+  tmp |= GPIO_Pin;
+  /* Set LCKK bit */
+  GPIOx->LCKR = tmp;
+  /* Reset LCKK bit */
+  GPIOx->LCKR =  GPIO_Pin;
+  /* Set LCKK bit */
+  GPIOx->LCKR = tmp;
+  /* Read LCKK bit*/
+  tmp = GPIOx->LCKR;
+  /* Read LCKK bit*/
+  tmp = GPIOx->LCKR;
+}
+
+/**
+  * @brief  Selects the GPIO pin used as Event output.
+  * @param  GPIO_PortSource: selects the GPIO port to be used as source
+  *   for Event output.
+  *   This parameter can be GPIO_PortSourceGPIOx where x can be (A..E).
+  * @param  GPIO_PinSource: specifies the pin for the Event output.
+  *   This parameter can be GPIO_PinSourcex where x can be (0..15).
+  * @retval None
+  */
+void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
+{
+  uint32_t tmpreg = 0x00;
+  /* Check the parameters */
+  assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource));
+  assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
+    
+  tmpreg = AFIO->EVCR;
+  /* Clear the PORT[6:4] and PIN[3:0] bits */
+  tmpreg &= EVCR_PORTPINCONFIG_MASK;
+  tmpreg |= (uint32_t)GPIO_PortSource << 0x04;
+  tmpreg |= GPIO_PinSource;
+  AFIO->EVCR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the Event Output.
+  * @param  NewState: new state of the Event output.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void GPIO_EventOutputCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) EVCR_EVOE_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Changes the mapping of the specified pin.
+  * @param  GPIO_Remap: selects the pin to remap.
+  *   This parameter can be one of the following values:
+  *     @arg GPIO_Remap_SPI1
+  *     @arg GPIO_Remap_I2C1
+  *     @arg GPIO_Remap_USART1
+  *     @arg GPIO_Remap_USART2
+  *     @arg GPIO_PartialRemap_USART3
+  *     @arg GPIO_FullRemap_USART3
+  *     @arg GPIO_PartialRemap_TIM1
+  *     @arg GPIO_FullRemap_TIM1
+  *     @arg GPIO_PartialRemap1_TIM2
+  *     @arg GPIO_PartialRemap2_TIM2
+  *     @arg GPIO_FullRemap_TIM2
+  *     @arg GPIO_PartialRemap_TIM3
+  *     @arg GPIO_FullRemap_TIM3
+  *     @arg GPIO_Remap_TIM4
+  *     @arg GPIO_Remap1_CAN1
+  *     @arg GPIO_Remap2_CAN1
+  *     @arg GPIO_Remap_PD01
+  *     @arg GPIO_Remap_TIM5CH4_LSI
+  *     @arg GPIO_Remap_ADC1_ETRGINJ
+  *     @arg GPIO_Remap_ADC1_ETRGREG
+  *     @arg GPIO_Remap_ADC2_ETRGINJ
+  *     @arg GPIO_Remap_ADC2_ETRGREG
+  *     @arg GPIO_Remap_ETH
+  *     @arg GPIO_Remap_CAN2  
+  *     @arg GPIO_Remap_SWJ_NoJTRST
+  *     @arg GPIO_Remap_SWJ_JTAGDisable
+  *     @arg GPIO_Remap_SWJ_Disable
+  *     @arg GPIO_Remap_SPI3
+  *     @arg GPIO_Remap_TIM2ITR1_PTP_SOF
+  *     @arg GPIO_Remap_PTP_PPS  
+  * @note  If the GPIO_Remap_TIM2ITR1_PTP_SOF is enabled the TIM2 ITR1 is connected 
+  *        to Ethernet PTP output. When Reset TIM2 ITR1 is connected to USB OTG SOF output.       
+  * @param  NewState: new state of the port pin remapping.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState)
+{
+  uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00;
+
+  /* Check the parameters */
+  assert_param(IS_GPIO_REMAP(GPIO_Remap));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));  
+  
+  tmpreg = AFIO->MAPR;
+
+  tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10;
+  tmp = GPIO_Remap & LSB_MASK;
+
+  if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK))
+  {
+    tmpreg &= DBGAFR_SWJCFG_MASK;
+    AFIO->MAPR &= DBGAFR_SWJCFG_MASK;
+  }
+  else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK)
+  {
+    tmp1 = ((uint32_t)0x03) << tmpmask;
+    tmpreg &= ~tmp1;
+    tmpreg |= ~DBGAFR_SWJCFG_MASK;
+  }
+  else
+  {
+    tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10));
+    tmpreg |= ~DBGAFR_SWJCFG_MASK;
+  }
+
+  if (NewState != DISABLE)
+  {
+    tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10));
+  }
+
+  AFIO->MAPR = tmpreg;
+}
+
+/**
+  * @brief  Selects the GPIO pin used as EXTI Line.
+  * @param  GPIO_PortSource: selects the GPIO port to be used as source for EXTI lines.
+  *   This parameter can be GPIO_PortSourceGPIOx where x can be (A..G).
+  * @param  GPIO_PinSource: specifies the EXTI line to be configured.
+  *   This parameter can be GPIO_PinSourcex where x can be (0..15).
+  * @retval None
+  */
+void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource)
+{
+  uint32_t tmp = 0x00;
+  /* Check the parameters */
+  assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource));
+  assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
+  
+  tmp = ((uint32_t)0x0F) << (0x04 * (GPIO_PinSource & (uint8_t)0x03));
+  AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp;
+  AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((uint32_t)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (uint8_t)0x03)));
+}
+
+/**
+  * @brief  Selects the Ethernet media interface.
+  * @note   This function applies only to STM32 Connectivity line devices.  
+  * @param  GPIO_ETH_MediaInterface: specifies the Media Interface mode.
+  *   This parameter can be one of the following values:
+  *     @arg GPIO_ETH_MediaInterface_MII: MII mode
+  *     @arg GPIO_ETH_MediaInterface_RMII: RMII mode    
+  * @retval None
+  */
+void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface) 
+{ 
+  assert_param(IS_GPIO_ETH_MEDIA_INTERFACE(GPIO_ETH_MediaInterface)); 
+
+  /* Configure MII_RMII selection bit */ 
+  *(__IO uint32_t *) MAPR_MII_RMII_SEL_BB = GPIO_ETH_MediaInterface; 
+}
+  
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c
new file mode 100644
index 0000000000000000000000000000000000000000..efcb211ee40432722b155ff215f660a4658b92cf
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c
@@ -0,0 +1,1152 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_i2c.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the I2C firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_i2c.h"
+#include "stm32f10x_rcc.h"
+
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup I2C 
+  * @brief I2C driver modules
+  * @{
+  */ 
+
+/** @defgroup I2C_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Private_Defines
+  * @{
+  */
+
+/* I2C SPE mask */
+#define CR1_PE_Set              ((uint16_t)0x0001)
+#define CR1_PE_Reset            ((uint16_t)0xFFFE)
+
+/* I2C START mask */
+#define CR1_START_Set           ((uint16_t)0x0100)
+#define CR1_START_Reset         ((uint16_t)0xFEFF)
+
+/* I2C STOP mask */
+#define CR1_STOP_Set            ((uint16_t)0x0200)
+#define CR1_STOP_Reset          ((uint16_t)0xFDFF)
+
+/* I2C ACK mask */
+#define CR1_ACK_Set             ((uint16_t)0x0400)
+#define CR1_ACK_Reset           ((uint16_t)0xFBFF)
+
+/* I2C ENGC mask */
+#define CR1_ENGC_Set            ((uint16_t)0x0040)
+#define CR1_ENGC_Reset          ((uint16_t)0xFFBF)
+
+/* I2C SWRST mask */
+#define CR1_SWRST_Set           ((uint16_t)0x8000)
+#define CR1_SWRST_Reset         ((uint16_t)0x7FFF)
+
+/* I2C PEC mask */
+#define CR1_PEC_Set             ((uint16_t)0x1000)
+#define CR1_PEC_Reset           ((uint16_t)0xEFFF)
+
+/* I2C ENPEC mask */
+#define CR1_ENPEC_Set           ((uint16_t)0x0020)
+#define CR1_ENPEC_Reset         ((uint16_t)0xFFDF)
+
+/* I2C ENARP mask */
+#define CR1_ENARP_Set           ((uint16_t)0x0010)
+#define CR1_ENARP_Reset         ((uint16_t)0xFFEF)
+
+/* I2C NOSTRETCH mask */
+#define CR1_NOSTRETCH_Set       ((uint16_t)0x0080)
+#define CR1_NOSTRETCH_Reset     ((uint16_t)0xFF7F)
+
+/* I2C registers Masks */
+#define CR1_CLEAR_Mask          ((uint16_t)0xFBF5)
+
+/* I2C DMAEN mask */
+#define CR2_DMAEN_Set           ((uint16_t)0x0800)
+#define CR2_DMAEN_Reset         ((uint16_t)0xF7FF)
+
+/* I2C LAST mask */
+#define CR2_LAST_Set            ((uint16_t)0x1000)
+#define CR2_LAST_Reset          ((uint16_t)0xEFFF)
+
+/* I2C FREQ mask */
+#define CR2_FREQ_Reset          ((uint16_t)0xFFC0)
+
+/* I2C ADD0 mask */
+#define OAR1_ADD0_Set           ((uint16_t)0x0001)
+#define OAR1_ADD0_Reset         ((uint16_t)0xFFFE)
+
+/* I2C ENDUAL mask */
+#define OAR2_ENDUAL_Set         ((uint16_t)0x0001)
+#define OAR2_ENDUAL_Reset       ((uint16_t)0xFFFE)
+
+/* I2C ADD2 mask */
+#define OAR2_ADD2_Reset         ((uint16_t)0xFF01)
+
+/* I2C F/S mask */
+#define CCR_FS_Set              ((uint16_t)0x8000)
+
+/* I2C CCR mask */
+#define CCR_CCR_Set             ((uint16_t)0x0FFF)
+
+/* I2C FLAG mask */
+#define FLAG_Mask               ((uint32_t)0x00FFFFFF)
+
+/* I2C Interrupt Enable mask */
+#define ITEN_Mask               ((uint32_t)0x07000000)
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the I2Cx peripheral registers to their default reset values.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @retval None
+  */
+void I2C_DeInit(I2C_TypeDef* I2Cx)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+  if (I2Cx == I2C1)
+  {
+    /* Enable I2C1 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE);
+    /* Release I2C1 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE);
+  }
+  else
+  {
+    /* Enable I2C2 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE);
+    /* Release I2C2 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE);
+  }
+}
+
+/**
+  * @brief  Initializes the I2Cx peripheral according to the specified 
+  *   parameters in the I2C_InitStruct.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_InitStruct: pointer to a I2C_InitTypeDef structure that
+  *   contains the configuration information for the specified I2C peripheral.
+  * @retval None
+  */
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
+{
+  uint16_t tmpreg = 0, freqrange = 0;
+  uint16_t result = 0x04;
+  uint32_t pclk1 = 8000000;
+  RCC_ClocksTypeDef  rcc_clocks;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed));
+  assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode));
+  assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle));
+  assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1));
+  assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack));
+  assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress));
+
+/*---------------------------- I2Cx CR2 Configuration ------------------------*/
+  /* Get the I2Cx CR2 value */
+  tmpreg = I2Cx->CR2;
+  /* Clear frequency FREQ[5:0] bits */
+  tmpreg &= CR2_FREQ_Reset;
+  /* Get pclk1 frequency value */
+  RCC_GetClocksFreq(&rcc_clocks);
+  pclk1 = rcc_clocks.PCLK1_Frequency;
+  /* Set frequency bits depending on pclk1 value */
+  freqrange = (uint16_t)(pclk1 / 1000000);
+  tmpreg |= freqrange;
+  /* Write to I2Cx CR2 */
+  I2Cx->CR2 = tmpreg;
+
+/*---------------------------- I2Cx CCR Configuration ------------------------*/
+  /* Disable the selected I2C peripheral to configure TRISE */
+  I2Cx->CR1 &= CR1_PE_Reset;
+  /* Reset tmpreg value */
+  /* Clear F/S, DUTY and CCR[11:0] bits */
+  tmpreg = 0;
+
+  /* Configure speed in standard mode */
+  if (I2C_InitStruct->I2C_ClockSpeed <= 100000)
+  {
+    /* Standard mode speed calculate */
+    result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1));
+    /* Test if CCR value is under 0x4*/
+    if (result < 0x04)
+    {
+      /* Set minimum allowed value */
+      result = 0x04;  
+    }
+    /* Set speed value for standard mode */
+    tmpreg |= result;	  
+    /* Set Maximum Rise Time for standard mode */
+    I2Cx->TRISE = freqrange + 1; 
+  }
+  /* Configure speed in fast mode */
+  else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/
+  {
+    if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2)
+    {
+      /* Fast mode speed calculate: Tlow/Thigh = 2 */
+      result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3));
+    }
+    else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/
+    {
+      /* Fast mode speed calculate: Tlow/Thigh = 16/9 */
+      result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25));
+      /* Set DUTY bit */
+      result |= I2C_DutyCycle_16_9;
+    }
+
+    /* Test if CCR value is under 0x1*/
+    if ((result & CCR_CCR_Set) == 0)
+    {
+      /* Set minimum allowed value */
+      result |= (uint16_t)0x0001;  
+    }
+    /* Set speed value and set F/S bit for fast mode */
+    tmpreg |= (uint16_t)(result | CCR_FS_Set);
+    /* Set Maximum Rise Time for fast mode */
+    I2Cx->TRISE = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1);  
+  }
+
+  /* Write to I2Cx CCR */
+  I2Cx->CCR = tmpreg;
+  /* Enable the selected I2C peripheral */
+  I2Cx->CR1 |= CR1_PE_Set;
+
+/*---------------------------- I2Cx CR1 Configuration ------------------------*/
+  /* Get the I2Cx CR1 value */
+  tmpreg = I2Cx->CR1;
+  /* Clear ACK, SMBTYPE and  SMBUS bits */
+  tmpreg &= CR1_CLEAR_Mask;
+  /* Configure I2Cx: mode and acknowledgement */
+  /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */
+  /* Set ACK bit according to I2C_Ack value */
+  tmpreg |= (uint16_t)((uint32_t)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack);
+  /* Write to I2Cx CR1 */
+  I2Cx->CR1 = tmpreg;
+
+/*---------------------------- I2Cx OAR1 Configuration -----------------------*/
+  /* Set I2Cx Own Address1 and acknowledged address */
+  I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1);
+}
+
+/**
+  * @brief  Fills each I2C_InitStruct member with its default value.
+  * @param  I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct)
+{
+/*---------------- Reset I2C init structure parameters values ----------------*/
+  /* initialize the I2C_ClockSpeed member */
+  I2C_InitStruct->I2C_ClockSpeed = 5000;
+  /* Initialize the I2C_Mode member */
+  I2C_InitStruct->I2C_Mode = I2C_Mode_I2C;
+  /* Initialize the I2C_DutyCycle member */
+  I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2;
+  /* Initialize the I2C_OwnAddress1 member */
+  I2C_InitStruct->I2C_OwnAddress1 = 0;
+  /* Initialize the I2C_Ack member */
+  I2C_InitStruct->I2C_Ack = I2C_Ack_Disable;
+  /* Initialize the I2C_AcknowledgedAddress member */
+  I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+}
+
+/**
+  * @brief  Enables or disables the specified I2C peripheral.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx peripheral. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C peripheral */
+    I2Cx->CR1 |= CR1_PE_Set;
+  }
+  else
+  {
+    /* Disable the selected I2C peripheral */
+    I2Cx->CR1 &= CR1_PE_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C DMA requests.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C DMA transfer.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C DMA requests */
+    I2Cx->CR2 |= CR2_DMAEN_Set;
+  }
+  else
+  {
+    /* Disable the selected I2C DMA requests */
+    I2Cx->CR2 &= CR2_DMAEN_Reset;
+  }
+}
+
+/**
+  * @brief  Specifies that the next DMA transfer is the last one.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C DMA last transfer.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Next DMA transfer is the last transfer */
+    I2Cx->CR2 |= CR2_LAST_Set;
+  }
+  else
+  {
+    /* Next DMA transfer is not the last transfer */
+    I2Cx->CR2 &= CR2_LAST_Reset;
+  }
+}
+
+/**
+  * @brief  Generates I2Cx communication START condition.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C START condition generation.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Generate a START condition */
+    I2Cx->CR1 |= CR1_START_Set;
+  }
+  else
+  {
+    /* Disable the START condition generation */
+    I2Cx->CR1 &= CR1_START_Reset;
+  }
+}
+
+/**
+  * @brief  Generates I2Cx communication STOP condition.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C STOP condition generation.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Generate a STOP condition */
+    I2Cx->CR1 |= CR1_STOP_Set;
+  }
+  else
+  {
+    /* Disable the STOP condition generation */
+    I2Cx->CR1 &= CR1_STOP_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C acknowledge feature.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C Acknowledgement.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the acknowledgement */
+    I2Cx->CR1 |= CR1_ACK_Set;
+  }
+  else
+  {
+    /* Disable the acknowledgement */
+    I2Cx->CR1 &= CR1_ACK_Reset;
+  }
+}
+
+/**
+  * @brief  Configures the specified I2C own address2.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  Address: specifies the 7bit I2C own address2.
+  * @retval None.
+  */
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address)
+{
+  uint16_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+  /* Get the old register value */
+  tmpreg = I2Cx->OAR2;
+
+  /* Reset I2Cx Own address2 bit [7:1] */
+  tmpreg &= OAR2_ADD2_Reset;
+
+  /* Set I2Cx Own address2 */
+  tmpreg |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE);
+
+  /* Store the new register value */
+  I2Cx->OAR2 = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the specified I2C dual addressing mode.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C dual addressing mode.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable dual addressing mode */
+    I2Cx->OAR2 |= OAR2_ENDUAL_Set;
+  }
+  else
+  {
+    /* Disable dual addressing mode */
+    I2Cx->OAR2 &= OAR2_ENDUAL_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C general call feature.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C General call.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable generall call */
+    I2Cx->CR1 |= CR1_ENGC_Set;
+  }
+  else
+  {
+    /* Disable generall call */
+    I2Cx->CR1 &= CR1_ENGC_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C interrupts.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. 
+  *   This parameter can be any combination of the following values:
+  *     @arg I2C_IT_BUF: Buffer interrupt mask
+  *     @arg I2C_IT_EVT: Event interrupt mask
+  *     @arg I2C_IT_ERR: Error interrupt mask
+  * @param  NewState: new state of the specified I2C interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_I2C_CONFIG_IT(I2C_IT));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C interrupts */
+    I2Cx->CR2 |= I2C_IT;
+  }
+  else
+  {
+    /* Disable the selected I2C interrupts */
+    I2Cx->CR2 &= (uint16_t)~I2C_IT;
+  }
+}
+
+/**
+  * @brief  Sends a data byte through the I2Cx peripheral.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  Data: Byte to be transmitted..
+  * @retval None
+  */
+void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  /* Write in the DR register the data to be sent */
+  I2Cx->DR = Data;
+}
+
+/**
+  * @brief  Returns the most recent received data by the I2Cx peripheral.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @retval The value of the received data.
+  */
+uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  /* Return the data in the DR register */
+  return (uint8_t)I2Cx->DR;
+}
+
+/**
+  * @brief  Transmits the address byte to select the slave device.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  Address: specifies the slave address which will be transmitted
+  * @param  I2C_Direction: specifies whether the I2C device will be a
+  *   Transmitter or a Receiver. This parameter can be one of the following values
+  *     @arg I2C_Direction_Transmitter: Transmitter mode
+  *     @arg I2C_Direction_Receiver: Receiver mode
+  * @retval None.
+  */
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_DIRECTION(I2C_Direction));
+  /* Test on the direction to set/reset the read/write bit */
+  if (I2C_Direction != I2C_Direction_Transmitter)
+  {
+    /* Set the address bit0 for read */
+    Address |= OAR1_ADD0_Set;
+  }
+  else
+  {
+    /* Reset the address bit0 for write */
+    Address &= OAR1_ADD0_Reset;
+  }
+  /* Send the address */
+  I2Cx->DR = Address;
+}
+
+/**
+  * @brief  Reads the specified I2C register and returns its value.
+  * @param  I2C_Register: specifies the register to read.
+  *   This parameter can be one of the following values:
+  *     @arg I2C_Register_CR1:  CR1 register.
+  *     @arg I2C_Register_CR2:   CR2 register.
+  *     @arg I2C_Register_OAR1:  OAR1 register.
+  *     @arg I2C_Register_OAR2:  OAR2 register.
+  *     @arg I2C_Register_DR:    DR register.
+  *     @arg I2C_Register_SR1:   SR1 register.
+  *     @arg I2C_Register_SR2:   SR2 register.
+  *     @arg I2C_Register_CCR:   CCR register.
+  *     @arg I2C_Register_TRISE: TRISE register.
+  * @retval The value of the read register.
+  */
+uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_REGISTER(I2C_Register));
+
+  tmp = (uint32_t) I2Cx;
+  tmp += I2C_Register;
+
+  /* Return the selected register value */
+  return (*(__IO uint16_t *) tmp);
+}
+
+/**
+  * @brief  Enables or disables the specified I2C software reset.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C software reset.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Peripheral under reset */
+    I2Cx->CR1 |= CR1_SWRST_Set;
+  }
+  else
+  {
+    /* Peripheral not under reset */
+    I2Cx->CR1 &= CR1_SWRST_Reset;
+  }
+}
+
+/**
+  * @brief  Drives the SMBusAlert pin high or low for the specified I2C.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_SMBusAlert: specifies SMBAlert pin level. 
+  *   This parameter can be one of the following values:
+  *     @arg I2C_SMBusAlert_Low: SMBAlert pin driven low
+  *     @arg I2C_SMBusAlert_High: SMBAlert pin driven high
+  * @retval None
+  */
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert));
+  if (I2C_SMBusAlert == I2C_SMBusAlert_Low)
+  {
+    /* Drive the SMBusAlert pin Low */
+    I2Cx->CR1 |= I2C_SMBusAlert_Low;
+  }
+  else
+  {
+    /* Drive the SMBusAlert pin High  */
+    I2Cx->CR1 &= I2C_SMBusAlert_High;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C PEC transfer.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C PEC transmission.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C PEC transmission */
+    I2Cx->CR1 |= CR1_PEC_Set;
+  }
+  else
+  {
+    /* Disable the selected I2C PEC transmission */
+    I2Cx->CR1 &= CR1_PEC_Reset;
+  }
+}
+
+/**
+  * @brief  Selects the specified I2C PEC position.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_PECPosition: specifies the PEC position. 
+  *   This parameter can be one of the following values:
+  *     @arg I2C_PECPosition_Next: indicates that the next byte is PEC
+  *     @arg I2C_PECPosition_Current: indicates that current byte is PEC
+  * @retval None
+  */
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition));
+  if (I2C_PECPosition == I2C_PECPosition_Next)
+  {
+    /* Next byte in shift register is PEC */
+    I2Cx->CR1 |= I2C_PECPosition_Next;
+  }
+  else
+  {
+    /* Current byte in shift register is PEC */
+    I2Cx->CR1 &= I2C_PECPosition_Current;
+  }
+}
+
+/**
+  * @brief  Enables or disables the PEC value calculation of the transfered bytes.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx PEC value calculation.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C PEC calculation */
+    I2Cx->CR1 |= CR1_ENPEC_Set;
+  }
+  else
+  {
+    /* Disable the selected I2C PEC calculation */
+    I2Cx->CR1 &= CR1_ENPEC_Reset;
+  }
+}
+
+/**
+  * @brief  Returns the PEC value for the specified I2C.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @retval The PEC value.
+  */
+uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  /* Return the selected I2C PEC value */
+  return ((I2Cx->SR2) >> 8);
+}
+
+/**
+  * @brief  Enables or disables the specified I2C ARP.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx ARP. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C ARP */
+    I2Cx->CR1 |= CR1_ENARP_Set;
+  }
+  else
+  {
+    /* Disable the selected I2C ARP */
+    I2Cx->CR1 &= CR1_ENARP_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C Clock stretching.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx Clock stretching.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState == DISABLE)
+  {
+    /* Enable the selected I2C Clock stretching */
+    I2Cx->CR1 |= CR1_NOSTRETCH_Set;
+  }
+  else
+  {
+    /* Disable the selected I2C Clock stretching */
+    I2Cx->CR1 &= CR1_NOSTRETCH_Reset;
+  }
+}
+
+/**
+  * @brief  Selects the specified I2C fast mode duty cycle.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_DutyCycle: specifies the fast mode duty cycle.
+  *   This parameter can be one of the following values:
+  *     @arg I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2
+  *     @arg I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9
+  * @retval None
+  */
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle));
+  if (I2C_DutyCycle != I2C_DutyCycle_16_9)
+  {
+    /* I2C fast mode Tlow/Thigh=2 */
+    I2Cx->CCR &= I2C_DutyCycle_2;
+  }
+  else
+  {
+    /* I2C fast mode Tlow/Thigh=16/9 */
+    I2Cx->CCR |= I2C_DutyCycle_16_9;
+  }
+}
+
+/**
+  * @brief  Returns the last I2Cx Event.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @retval The last event
+  */
+uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx)
+{
+  uint32_t lastevent = 0;
+  uint32_t flag1 = 0, flag2 = 0;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  /* Read the I2Cx status register */
+  flag1 = I2Cx->SR1;
+  flag2 = I2Cx->SR2;
+  flag2 = flag2 << 16;
+  /* Get the last event value from I2C status register */
+  lastevent = (flag1 | flag2) & FLAG_Mask;
+  /* Return status */
+  return lastevent;
+}
+
+/**
+  * @brief  Checks whether the last I2Cx Event is equal to the one passed
+  *   as parameter.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_EVENT: specifies the event to be checked. 
+  *   This parameter can be one of the following values:
+  *     @arg I2C_EVENT_SLAVE_ADDRESS_MATCHED   : EV1
+  *     @arg I2C_EVENT_SLAVE_BYTE_RECEIVED     : EV2
+  *     @arg I2C_EVENT_SLAVE_BYTE_TRANSMITTED  : EV3
+  *     @arg I2C_EVENT_SLAVE_ACK_FAILURE       : EV3-2
+  *     @arg I2C_EVENT_MASTER_MODE_SELECT      : EV5
+  *     @arg I2C_EVENT_MASTER_MODE_SELECTED    : EV6
+  *     @arg I2C_EVENT_MASTER_BYTE_RECEIVED    : EV7
+  *     @arg I2C_EVENT_MASTER_BYTE_TRANSMITTED : EV8
+  *     @arg I2C_EVENT_MASTER_MODE_ADDRESS10   : EV9
+  *     @arg I2C_EVENT_SLAVE_STOP_DETECTED     : EV4
+  * @retval An ErrorStatus enumuration value:
+  * - SUCCESS: Last event is equal to the I2C_EVENT
+  * - ERROR: Last event is different from the I2C_EVENT
+  */
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT)
+{
+  uint32_t lastevent = 0;
+  uint32_t flag1 = 0, flag2 = 0;
+  ErrorStatus status = ERROR;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_EVENT(I2C_EVENT));
+  /* Read the I2Cx status register */
+  flag1 = I2Cx->SR1;
+  flag2 = I2Cx->SR2;
+  flag2 = flag2 << 16;
+  /* Get the last event value from I2C status register */
+  lastevent = (flag1 | flag2) & FLAG_Mask;
+  /* Check whether the last event is equal to I2C_EVENT */
+  if (lastevent == I2C_EVENT )
+  {
+    /* SUCCESS: last event is equal to I2C_EVENT */
+    status = SUCCESS;
+  }
+  else
+  {
+    /* ERROR: last event is different from I2C_EVENT */
+    status = ERROR;
+  }
+  /* Return status */
+  return status;
+}
+
+/**
+  * @brief  Checks whether the specified I2C flag is set or not.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_FLAG: specifies the flag to check. 
+  *   This parameter can be one of the following values:
+  *     @arg I2C_FLAG_DUALF: Dual flag (Slave mode)
+  *     @arg I2C_FLAG_SMBHOST: SMBus host header (Slave mode)
+  *     @arg I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode)
+  *     @arg I2C_FLAG_GENCALL: General call header flag (Slave mode)
+  *     @arg I2C_FLAG_TRA: Transmitter/Receiver flag
+  *     @arg I2C_FLAG_BUSY: Bus busy flag
+  *     @arg I2C_FLAG_MSL: Master/Slave flag
+  *     @arg I2C_FLAG_SMBALERT: SMBus Alert flag
+  *     @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+  *     @arg I2C_FLAG_PECERR: PEC error in reception flag
+  *     @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+  *     @arg I2C_FLAG_AF: Acknowledge failure flag
+  *     @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+  *     @arg I2C_FLAG_BERR: Bus error flag
+  *     @arg I2C_FLAG_TXE: Data register empty flag (Transmitter)
+  *     @arg I2C_FLAG_RXNE: Data register not empty (Receiver) flag
+  *     @arg I2C_FLAG_STOPF: Stop detection flag (Slave mode)
+  *     @arg I2C_FLAG_ADD10: 10-bit header sent flag (Master mode)
+  *     @arg I2C_FLAG_BTF: Byte transfer finished flag
+  *     @arg I2C_FLAG_ADDR: Address sent flag (Master mode) “ADSL”
+  *   Address matched flag (Slave mode)”ENDAD”
+  *     @arg I2C_FLAG_SB: Start bit flag (Master mode)
+  * @retval The new state of I2C_FLAG (SET or RESET).
+  */
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  __IO uint32_t i2creg = 0, i2cxbase = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_GET_FLAG(I2C_FLAG));
+
+  /* Get the I2Cx peripheral base address */
+  i2cxbase = (uint32_t)I2Cx;
+  
+  /* Read flag register index */
+  i2creg = I2C_FLAG >> 28;
+  
+  /* Get bit[23:0] of the flag */
+  I2C_FLAG &= FLAG_Mask;
+  
+  if(i2creg != 0)
+  {
+    /* Get the I2Cx SR1 register address */
+    i2cxbase += 0x14;
+  }
+  else
+  {
+    /* Flag in I2Cx SR2 Register */
+    I2C_FLAG = (uint32_t)(I2C_FLAG >> 16);
+    /* Get the I2Cx SR2 register address */
+    i2cxbase += 0x18;
+  }
+  
+  if(((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET)
+  {
+    /* I2C_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* I2C_FLAG is reset */
+    bitstatus = RESET;
+  }
+  
+  /* Return the I2C_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the I2Cx's pending flags.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_FLAG: specifies the flag to clear. 
+  *   This parameter can be any combination of the following values:
+  *     @arg I2C_FLAG_SMBALERT: SMBus Alert flag
+  *     @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+  *     @arg I2C_FLAG_PECERR: PEC error in reception flag
+  *     @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+  *     @arg I2C_FLAG_AF: Acknowledge failure flag
+  *     @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+  *     @arg I2C_FLAG_BERR: Bus error flag
+  *   
+  * @note
+  *   - STOPF (STOP detection) is cleared by software sequence: a read operation 
+  *     to I2C_SR1 register (I2C_GetFlagStatus()) followed by a write operation 
+  *     to I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral).
+  *   - ADD10 (10-bit header sent) is cleared by software sequence: a read 
+  *     operation to I2C_SR1 (I2C_GetFlagStatus()) followed by writing the 
+  *     second byte of the address in DR register.
+  *   - BTF (Byte Transfer Finished) is cleared by software sequence: a read 
+  *     operation to I2C_SR1 register (I2C_GetFlagStatus()) followed by a 
+  *     read/write to I2C_DR register (I2C_SendData()).
+  *   - ADDR (Address sent) is cleared by software sequence: a read operation to 
+  *     I2C_SR1 register (I2C_GetFlagStatus()) followed by a read operation to 
+  *     I2C_SR2 register ((void)(I2Cx->SR2)).
+  *   - SB (Start Bit) is cleared software sequence: a read operation to I2C_SR1
+  *     register (I2C_GetFlagStatus()) followed by a write operation to I2C_DR
+  *     register  (I2C_SendData()).
+  * @retval None
+  */
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
+{
+  uint32_t flagpos = 0;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG));
+  /* Get the I2C flag position */
+  flagpos = I2C_FLAG & FLAG_Mask;
+  /* Clear the selected I2C flag */
+  I2Cx->SR1 = (uint16_t)~flagpos;
+}
+
+/**
+  * @brief  Checks whether the specified I2C interrupt has occurred or not.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_IT: specifies the interrupt source to check. 
+  *   This parameter can be one of the following values:
+  *     @arg I2C_IT_SMBALERT: SMBus Alert flag
+  *     @arg I2C_IT_TIMEOUT: Timeout or Tlow error flag
+  *     @arg I2C_IT_PECERR: PEC error in reception flag
+  *     @arg I2C_IT_OVR: Overrun/Underrun flag (Slave mode)
+  *     @arg I2C_IT_AF: Acknowledge failure flag
+  *     @arg I2C_IT_ARLO: Arbitration lost flag (Master mode)
+  *     @arg I2C_IT_BERR: Bus error flag
+  *     @arg I2C_IT_TXE: Data register empty flag (Transmitter)
+  *     @arg I2C_IT_RXNE: Data register not empty (Receiver) flag
+  *     @arg I2C_IT_STOPF: Stop detection flag (Slave mode)
+  *     @arg I2C_IT_ADD10: 10-bit header sent flag (Master mode)
+  *     @arg I2C_IT_BTF: Byte transfer finished flag
+  *     @arg I2C_IT_ADDR: Address sent flag (Master mode) “ADSL”
+  *                       Address matched flag (Slave mode)”ENDAD”
+  *     @arg I2C_IT_SB: Start bit flag (Master mode)
+  * @retval The new state of I2C_IT (SET or RESET).
+  */
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t enablestatus = 0;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_GET_IT(I2C_IT));
+  /* Check if the interrupt source is enabled or not */
+  enablestatus = (uint32_t)(((I2C_IT & ITEN_Mask) >> 16) & (I2Cx->CR2)) ;  
+  /* Get bit[23:0] of the flag */
+  I2C_IT &= FLAG_Mask;
+  /* Check the status of the specified I2C flag */
+  if (((I2Cx->SR1 & I2C_IT) != (uint32_t)RESET) && enablestatus)
+  {
+    /* I2C_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* I2C_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the I2C_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the I2Cx’s interrupt pending bits.
+  * @param  I2Cx: where x can be 1 or 2 to select the I2C peripheral.
+  * @param  I2C_IT: specifies the interrupt pending bit to clear. 
+  *   This parameter can be any combination of the following values:
+  *     @arg I2C_IT_SMBALERT: SMBus Alert interrupt
+  *     @arg I2C_IT_TIMEOUT: Timeout or Tlow error interrupt
+  *     @arg I2C_IT_PECERR: PEC error in reception  interrupt
+  *     @arg I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode)
+  *     @arg I2C_IT_AF: Acknowledge failure interrupt
+  *     @arg I2C_IT_ARLO: Arbitration lost interrupt (Master mode)
+  *     @arg I2C_IT_BERR: Bus error interrupt
+  *   
+  * @note
+  *   - STOPF (STOP detection) is cleared by software sequence: a read operation 
+  *     to I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to 
+  *     I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral).
+  *   - ADD10 (10-bit header sent) is cleared by software sequence: a read 
+  *     operation to I2C_SR1 (I2C_GetITStatus()) followed by writing the second 
+  *     byte of the address in I2C_DR register.
+  *   - BTF (Byte Transfer Finished) is cleared by software sequence: a read 
+  *     operation to I2C_SR1 register (I2C_GetITStatus()) followed by a 
+  *     read/write to I2C_DR register (I2C_SendData()).
+  *   - ADDR (Address sent) is cleared by software sequence: a read operation to 
+  *     I2C_SR1 register (I2C_GetITStatus()) followed by a read operation to 
+  *     I2C_SR2 register ((void)(I2Cx->SR2)).
+  *   - SB (Start Bit) is cleared by software sequence: a read operation to 
+  *     I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to 
+  *     I2C_DR register (I2C_SendData()).
+  * @retval None
+  */
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
+{
+  uint32_t flagpos = 0;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_CLEAR_IT(I2C_IT));
+  /* Get the I2C flag position */
+  flagpos = I2C_IT & FLAG_Mask;
+  /* Clear the selected I2C flag */
+  I2Cx->SR1 = (uint16_t)~flagpos;
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c
new file mode 100644
index 0000000000000000000000000000000000000000..11f6dbc0e3f80a3157845a86bb6f61f435e89a76
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c
@@ -0,0 +1,189 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_iwdg.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the IWDG firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_iwdg.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup IWDG 
+  * @brief IWDG driver modules
+  * @{
+  */ 
+
+/** @defgroup IWDG_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Private_Defines
+  * @{
+  */ 
+
+/* ---------------------- IWDG registers bit mask ----------------------------*/
+
+/* KR register bit mask */
+#define KR_KEY_Reload    ((uint16_t)0xAAAA)
+#define KR_KEY_Enable    ((uint16_t)0xCCCC)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup IWDG_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables write access to IWDG_PR and IWDG_RLR registers.
+  * @param  IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers.
+  *   This parameter can be one of the following values:
+  *     @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers
+  *     @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers
+  * @retval None
+  */
+void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess)
+{
+  /* Check the parameters */
+  assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
+  IWDG->KR = IWDG_WriteAccess;
+}
+
+/**
+  * @brief  Sets IWDG Prescaler value.
+  * @param  IWDG_Prescaler: specifies the IWDG Prescaler value.
+  *   This parameter can be one of the following values:
+  *     @arg IWDG_Prescaler_4: IWDG prescaler set to 4
+  *     @arg IWDG_Prescaler_8: IWDG prescaler set to 8
+  *     @arg IWDG_Prescaler_16: IWDG prescaler set to 16
+  *     @arg IWDG_Prescaler_32: IWDG prescaler set to 32
+  *     @arg IWDG_Prescaler_64: IWDG prescaler set to 64
+  *     @arg IWDG_Prescaler_128: IWDG prescaler set to 128
+  *     @arg IWDG_Prescaler_256: IWDG prescaler set to 256
+  * @retval None
+  */
+void IWDG_SetPrescaler(uint8_t IWDG_Prescaler)
+{
+  /* Check the parameters */
+  assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
+  IWDG->PR = IWDG_Prescaler;
+}
+
+/**
+  * @brief  Sets IWDG Reload value.
+  * @param  Reload: specifies the IWDG Reload value.
+  *   This parameter must be a number between 0 and 0x0FFF.
+  * @retval None
+  */
+void IWDG_SetReload(uint16_t Reload)
+{
+  /* Check the parameters */
+  assert_param(IS_IWDG_RELOAD(Reload));
+  IWDG->RLR = Reload;
+}
+
+/**
+  * @brief  Reloads IWDG counter with value defined in the reload register
+  *   (write access to IWDG_PR and IWDG_RLR registers disabled).
+  * @param  None
+  * @retval None
+  */
+void IWDG_ReloadCounter(void)
+{
+  IWDG->KR = KR_KEY_Reload;
+}
+
+/**
+  * @brief  Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled).
+  * @param  None
+  * @retval None
+  */
+void IWDG_Enable(void)
+{
+  IWDG->KR = KR_KEY_Enable;
+}
+
+/**
+  * @brief  Checks whether the specified IWDG flag is set or not.
+  * @param  IWDG_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg IWDG_FLAG_PVU: Prescaler Value Update on going
+  *     @arg IWDG_FLAG_RVU: Reload Value Update on going
+  * @retval The new state of IWDG_FLAG (SET or RESET).
+  */
+FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_IWDG_FLAG(IWDG_FLAG));
+  if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c
new file mode 100644
index 0000000000000000000000000000000000000000..2c8143b04084803f1d8797dfe0f0b447f62c7907
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c
@@ -0,0 +1,311 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_pwr.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the PWR firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_pwr.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup PWR 
+  * @brief PWR driver modules
+  * @{
+  */ 
+
+/** @defgroup PWR_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Private_Defines
+  * @{
+  */
+
+/* --------- PWR registers bit address in the alias region ---------- */
+#define PWR_OFFSET               (PWR_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+
+/* Alias word address of DBP bit */
+#define CR_OFFSET                (PWR_OFFSET + 0x00)
+#define DBP_BitNumber            0x08
+#define CR_DBP_BB                (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
+
+/* Alias word address of PVDE bit */
+#define PVDE_BitNumber           0x04
+#define CR_PVDE_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
+
+/* --- CSR Register ---*/
+
+/* Alias word address of EWUP bit */
+#define CSR_OFFSET               (PWR_OFFSET + 0x04)
+#define EWUP_BitNumber           0x08
+#define CSR_EWUP_BB              (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
+
+/* ------------------ PWR registers bit mask ------------------------ */
+
+/* CR register bit mask */
+#define CR_PDDS_Set              ((uint32_t)0x00000002)
+#define CR_DS_Mask               ((uint32_t)0xFFFFFFFC)
+#define CR_CWUF_Set              ((uint32_t)0x00000004)
+#define CR_PLS_Mask              ((uint32_t)0xFFFFFF1F)
+
+/* --------- Cortex System Control register bit mask ---------------- */
+
+/* Cortex System Control register address */
+#define SCB_SysCtrl              ((uint32_t)0xE000ED10)
+
+/* SLEEPDEEP bit mask */
+#define SysCtrl_SLEEPDEEP_Set    ((uint32_t)0x00000004)
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the PWR peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void PWR_DeInit(void)
+{
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
+}
+
+/**
+  * @brief  Enables or disables access to the RTC and backup registers.
+  * @param  NewState: new state of the access to the RTC and backup registers.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_BackupAccessCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the Power Voltage Detector(PVD).
+  * @param  NewState: new state of the PVD.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_PVDCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the voltage threshold detected by the Power Voltage Detector(PVD).
+  * @param  PWR_PVDLevel: specifies the PVD detection level
+  *   This parameter can be one of the following values:
+  *     @arg PWR_PVDLevel_2V2: PVD detection level set to 2.2V
+  *     @arg PWR_PVDLevel_2V3: PVD detection level set to 2.3V
+  *     @arg PWR_PVDLevel_2V4: PVD detection level set to 2.4V
+  *     @arg PWR_PVDLevel_2V5: PVD detection level set to 2.5V
+  *     @arg PWR_PVDLevel_2V6: PVD detection level set to 2.6V
+  *     @arg PWR_PVDLevel_2V7: PVD detection level set to 2.7V
+  *     @arg PWR_PVDLevel_2V8: PVD detection level set to 2.8V
+  *     @arg PWR_PVDLevel_2V9: PVD detection level set to 2.9V
+  * @retval None
+  */
+void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
+  tmpreg = PWR->CR;
+  /* Clear PLS[7:5] bits */
+  tmpreg &= CR_PLS_Mask;
+  /* Set PLS[7:5] bits according to PWR_PVDLevel value */
+  tmpreg |= PWR_PVDLevel;
+  /* Store the new value */
+  PWR->CR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the WakeUp Pin functionality.
+  * @param  NewState: new state of the WakeUp Pin functionality.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_WakeUpPinCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enters STOP mode.
+  * @param  PWR_Regulator: specifies the regulator state in STOP mode.
+  *   This parameter can be one of the following values:
+  *     @arg PWR_Regulator_ON: STOP mode with regulator ON
+  *     @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode
+  * @param  PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction.
+  *   This parameter can be one of the following values:
+  *     @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
+  *     @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
+  * @retval None
+  */
+void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_PWR_REGULATOR(PWR_Regulator));
+  assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
+  
+  /* Select the regulator state in STOP mode ---------------------------------*/
+  tmpreg = PWR->CR;
+  /* Clear PDDS and LPDS bits */
+  tmpreg &= CR_DS_Mask;
+  /* Set LPDS bit according to PWR_Regulator value */
+  tmpreg |= PWR_Regulator;
+  /* Store the new value */
+  PWR->CR = tmpreg;
+  /* Set SLEEPDEEP bit of Cortex System Control Register */
+  *(__IO uint32_t *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
+  
+  /* Select STOP mode entry --------------------------------------------------*/
+  if(PWR_STOPEntry == PWR_STOPEntry_WFI)
+  {   
+    /* Request Wait For Interrupt */
+    __WFI();
+  }
+  else
+  {
+    /* Request Wait For Event */
+    __WFE();
+  }
+}
+
+/**
+  * @brief  Enters STANDBY mode.
+  * @param  None
+  * @retval None
+  */
+void PWR_EnterSTANDBYMode(void)
+{
+  /* Clear Wake-up flag */
+  PWR->CR |= CR_CWUF_Set;
+  /* Select STANDBY mode */
+  PWR->CR |= CR_PDDS_Set;
+  /* Set SLEEPDEEP bit of Cortex System Control Register */
+  *(__IO uint32_t *) SCB_SysCtrl |= SysCtrl_SLEEPDEEP_Set;
+/* This option is used to ensure that store operations are completed */
+#if defined ( __CC_ARM   )
+  __force_stores();
+#endif
+  /* Request Wait For Interrupt */
+  __WFI();
+}
+
+/**
+  * @brief  Checks whether the specified PWR flag is set or not.
+  * @param  PWR_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg PWR_FLAG_WU: Wake Up flag
+  *     @arg PWR_FLAG_SB: StandBy flag
+  *     @arg PWR_FLAG_PVDO: PVD Output
+  * @retval The new state of PWR_FLAG (SET or RESET).
+  */
+FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
+  
+  if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the PWR's pending flags.
+  * @param  PWR_FLAG: specifies the flag to clear.
+  *   This parameter can be one of the following values:
+  *     @arg PWR_FLAG_WU: Wake Up flag
+  *     @arg PWR_FLAG_SB: StandBy flag
+  * @retval None
+  */
+void PWR_ClearFlag(uint32_t PWR_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
+         
+  PWR->CR |=  PWR_FLAG << 2;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c
new file mode 100644
index 0000000000000000000000000000000000000000..c19915c78999dc8ae2cce9fbbde5ced96e261c76
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c
@@ -0,0 +1,1447 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_rcc.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the RCC firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup RCC 
+  * @brief RCC driver modules
+  * @{
+  */ 
+
+/** @defgroup RCC_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Private_Defines
+  * @{
+  */
+
+/* ------------ RCC registers bit address in the alias region ----------- */
+#define RCC_OFFSET                (RCC_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+
+/* Alias word address of HSION bit */
+#define CR_OFFSET                 (RCC_OFFSET + 0x00)
+#define HSION_BitNumber           0x00
+#define CR_HSION_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4))
+
+/* Alias word address of PLLON bit */
+#define PLLON_BitNumber           0x18
+#define CR_PLLON_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
+
+#ifdef STM32F10X_CL
+ /* Alias word address of PLL2ON bit */
+ #define PLL2ON_BitNumber          0x1A
+ #define CR_PLL2ON_BB              (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL2ON_BitNumber * 4))
+
+ /* Alias word address of PLL3ON bit */
+ #define PLL3ON_BitNumber          0x1C
+ #define CR_PLL3ON_BB              (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL3ON_BitNumber * 4))
+#endif /* STM32F10X_CL */ 
+
+/* Alias word address of CSSON bit */
+#define CSSON_BitNumber           0x13
+#define CR_CSSON_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
+
+/* --- CFGR Register ---*/
+
+/* Alias word address of USBPRE bit */
+#define CFGR_OFFSET               (RCC_OFFSET + 0x04)
+
+#ifndef STM32F10X_CL
+ #define USBPRE_BitNumber          0x16
+ #define CFGR_USBPRE_BB            (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4))
+#else
+ #define OTGFSPRE_BitNumber        0x16
+ #define CFGR_OTGFSPRE_BB          (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (OTGFSPRE_BitNumber * 4))
+#endif /* STM32F10X_CL */ 
+
+/* --- BDCR Register ---*/
+
+/* Alias word address of RTCEN bit */
+#define BDCR_OFFSET               (RCC_OFFSET + 0x20)
+#define RTCEN_BitNumber           0x0F
+#define BDCR_RTCEN_BB             (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4))
+
+/* Alias word address of BDRST bit */
+#define BDRST_BitNumber           0x10
+#define BDCR_BDRST_BB             (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
+
+/* --- CSR Register ---*/
+
+/* Alias word address of LSION bit */
+#define CSR_OFFSET                (RCC_OFFSET + 0x24)
+#define LSION_BitNumber           0x00
+#define CSR_LSION_BB              (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4))
+
+#ifdef STM32F10X_CL
+/* --- CFGR2 Register ---*/
+
+ /* Alias word address of I2S2SRC bit */
+ #define CFGR2_OFFSET              (RCC_OFFSET + 0x2C)
+ #define I2S2SRC_BitNumber         0x11
+ #define CFGR2_I2S2SRC_BB          (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S2SRC_BitNumber * 4))
+
+ /* Alias word address of I2S3SRC bit */
+ #define I2S3SRC_BitNumber         0x12
+ #define CFGR2_I2S3SRC_BB          (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S3SRC_BitNumber * 4))
+#endif /* STM32F10X_CL */
+
+/* ---------------------- RCC registers bit mask ------------------------ */
+
+/* CR register bit mask */
+#define CR_HSEBYP_Reset           ((uint32_t)0xFFFBFFFF)
+#define CR_HSEBYP_Set             ((uint32_t)0x00040000)
+#define CR_HSEON_Reset            ((uint32_t)0xFFFEFFFF)
+#define CR_HSEON_Set              ((uint32_t)0x00010000)
+#define CR_HSITRIM_Mask           ((uint32_t)0xFFFFFF07)
+
+/* CFGR register bit mask */
+#ifndef STM32F10X_CL
+ #define CFGR_PLL_Mask            ((uint32_t)0xFFC0FFFF)
+#else
+ #define CFGR_PLL_Mask           ((uint32_t)0xFFC2FFFF)
+#endif /* STM32F10X_CL */ 
+
+#define CFGR_PLLMull_Mask         ((uint32_t)0x003C0000)
+#define CFGR_PLLSRC_Mask          ((uint32_t)0x00010000)
+#define CFGR_PLLXTPRE_Mask        ((uint32_t)0x00020000)
+#define CFGR_SWS_Mask             ((uint32_t)0x0000000C)
+#define CFGR_SW_Mask              ((uint32_t)0xFFFFFFFC)
+#define CFGR_HPRE_Reset_Mask      ((uint32_t)0xFFFFFF0F)
+#define CFGR_HPRE_Set_Mask        ((uint32_t)0x000000F0)
+#define CFGR_PPRE1_Reset_Mask     ((uint32_t)0xFFFFF8FF)
+#define CFGR_PPRE1_Set_Mask       ((uint32_t)0x00000700)
+#define CFGR_PPRE2_Reset_Mask     ((uint32_t)0xFFFFC7FF)
+#define CFGR_PPRE2_Set_Mask       ((uint32_t)0x00003800)
+#define CFGR_ADCPRE_Reset_Mask    ((uint32_t)0xFFFF3FFF)
+#define CFGR_ADCPRE_Set_Mask      ((uint32_t)0x0000C000)
+
+/* CSR register bit mask */
+#define CSR_RMVF_Set              ((uint32_t)0x01000000)
+
+#ifdef STM32F10X_CL
+/* CFGR2 register bit mask */
+ #define CFGR2_PREDIV1SRC         ((uint32_t)0x00010000)
+ #define CFGR2_PREDIV1            ((uint32_t)0x0000000F)
+ #define CFGR2_PREDIV2            ((uint32_t)0x000000F0)
+ #define CFGR2_PLL2MUL            ((uint32_t)0x00000F00)
+ #define CFGR2_PLL3MUL            ((uint32_t)0x0000F000)
+#endif /* STM32F10X_CL */ 
+
+/* RCC Flag Mask */
+#define FLAG_Mask                 ((uint8_t)0x1F)
+
+#ifndef HSI_Value
+/* Typical Value of the HSI in Hz */
+ #define HSI_Value                 ((uint32_t)8000000)
+#endif /* HSI_Value */
+
+/* CIR register byte 2 (Bits[15:8]) base address */
+#define CIR_BYTE2_ADDRESS         ((uint32_t)0x40021009)
+
+/* CIR register byte 3 (Bits[23:16]) base address */
+#define CIR_BYTE3_ADDRESS         ((uint32_t)0x4002100A)
+
+/* CFGR register byte 4 (Bits[31:24]) base address */
+#define CFGR_BYTE4_ADDRESS        ((uint32_t)0x40021007)
+
+/* BDCR register base address */
+#define BDCR_ADDRESS              (PERIPH_BASE + BDCR_OFFSET)
+
+#ifndef HSEStartUp_TimeOut
+/* Time out for HSE start up */
+ #define HSEStartUp_TimeOut        ((uint16_t)0x0500)
+#endif /* HSEStartUp_TimeOut */
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RCC_Private_Macros
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RCC_Private_Variables
+  * @{
+  */ 
+
+static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
+static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8};
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Resets the RCC clock configuration to the default reset state.
+  * @param  None
+  * @retval None
+  */
+void RCC_DeInit(void)
+{
+  /* Set HSION bit */
+  RCC->CR |= (uint32_t)0x00000001;
+
+  /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
+#ifndef STM32F10X_CL
+  RCC->CFGR &= (uint32_t)0xF8FF0000;
+#else
+  RCC->CFGR &= (uint32_t)0xF0FF0000;
+#endif /* STM32F10X_CL */   
+  
+  /* Reset HSEON, CSSON and PLLON bits */
+  RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+  /* Reset HSEBYP bit */
+  RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+  /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
+  RCC->CFGR &= (uint32_t)0xFF80FFFF;
+
+#ifndef STM32F10X_CL
+  /* Disable all interrupts and clear pending bits  */
+  RCC->CIR = 0x009F0000;
+#else
+  /* Reset PLL2ON and PLL3ON bits */
+  RCC->CR &= (uint32_t)0xEBFFFFFF;
+
+  /* Disable all interrupts and clear pending bits  */
+  RCC->CIR = 0x00FF0000;
+
+  /* Reset CFGR2 register */
+  RCC->CFGR2 = 0x00000000;
+#endif /* STM32F10X_CL */
+}
+
+/**
+  * @brief  Configures the External High Speed oscillator (HSE).
+  * @note   HSE can not be stopped if it is used directly or through the PLL as system clock.
+  * @param  RCC_HSE: specifies the new state of the HSE.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_HSE_OFF: HSE oscillator OFF
+  *     @arg RCC_HSE_ON: HSE oscillator ON
+  *     @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock
+  * @retval None
+  */
+void RCC_HSEConfig(uint32_t RCC_HSE)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_HSE(RCC_HSE));
+  /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/
+  /* Reset HSEON bit */
+  RCC->CR &= CR_HSEON_Reset;
+  /* Reset HSEBYP bit */
+  RCC->CR &= CR_HSEBYP_Reset;
+  /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */
+  switch(RCC_HSE)
+  {
+    case RCC_HSE_ON:
+      /* Set HSEON bit */
+      RCC->CR |= CR_HSEON_Set;
+      break;
+      
+    case RCC_HSE_Bypass:
+      /* Set HSEBYP and HSEON bits */
+      RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set;
+      break;
+      
+    default:
+      break;
+  }
+}
+
+/**
+  * @brief  Waits for HSE start-up.
+  * @param  None
+  * @retval An ErrorStatus enumuration value:
+  * - SUCCESS: HSE oscillator is stable and ready to use
+  * - ERROR: HSE oscillator not yet ready
+  */
+ErrorStatus RCC_WaitForHSEStartUp(void)
+{
+  __IO uint32_t StartUpCounter = 0;
+  ErrorStatus status = ERROR;
+  FlagStatus HSEStatus = RESET;
+  
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
+    StartUpCounter++;  
+  } while((StartUpCounter != HSEStartUp_TimeOut) && (HSEStatus == RESET));
+  
+  if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
+  {
+    status = SUCCESS;
+  }
+  else
+  {
+    status = ERROR;
+  }  
+  return (status);
+}
+
+/**
+  * @brief  Adjusts the Internal High Speed oscillator (HSI) calibration value.
+  * @param  HSICalibrationValue: specifies the calibration trimming value.
+  *   This parameter must be a number between 0 and 0x1F.
+  * @retval None
+  */
+void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue));
+  tmpreg = RCC->CR;
+  /* Clear HSITRIM[4:0] bits */
+  tmpreg &= CR_HSITRIM_Mask;
+  /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */
+  tmpreg |= (uint32_t)HSICalibrationValue << 3;
+  /* Store the new value */
+  RCC->CR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the Internal High Speed oscillator (HSI).
+  * @note   HSI can not be stopped if it is used directly or through the PLL as system clock.
+  * @param  NewState: new state of the HSI. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_HSICmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the PLL clock source and multiplication factor.
+  * @note   This function must be used only when the PLL is disabled.
+  * @param  RCC_PLLSource: specifies the PLL entry clock source.
+  *   For @b STM32_Connectivity_line_devices, this parameter can be one of the
+  *   following values:
+  *     @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry
+  *     @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock entry
+  *   For @b other_STM32_devices, this parameter can be one of the following values:
+  *     @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry
+  *     @arg RCC_PLLSource_HSE_Div1: HSE oscillator clock selected as PLL clock entry
+  *     @arg RCC_PLLSource_HSE_Div2: HSE oscillator clock divided by 2 selected as PLL clock entry 
+  * @param  RCC_PLLMul: specifies the PLL multiplication factor.
+  *   For @b STM32_Connectivity_line_devices, this parameter can be RCC_PLLMul_x where x:{[4,9], 6_5}
+  *   For @b other_STM32_devices, this parameter can be RCC_PLLMul_x where x:[2,16]  
+  * @retval None
+  */
+void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
+  assert_param(IS_RCC_PLL_MUL(RCC_PLLMul));
+
+  tmpreg = RCC->CFGR;
+  /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */
+  tmpreg &= CFGR_PLL_Mask;
+  /* Set the PLL configuration bits */
+  tmpreg |= RCC_PLLSource | RCC_PLLMul;
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the PLL.
+  * @note   The PLL can not be disabled if it is used as system clock.
+  * @param  NewState: new state of the PLL. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_PLLCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState;
+}
+
+#ifdef STM32F10X_CL
+/**
+  * @brief  Configures the PREDIV1 division factor.
+  * @note 
+  *   - This function must be used only when the PLL is disabled.
+  *   - This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_PREDIV1_Source: specifies the PREDIV1 clock source.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_PREDIV1_Source_HSE: HSE selected as PREDIV1 clock
+  *     @arg RCC_PREDIV1_Source_PLL2: PLL2 selected as PREDIV1 clock
+  * @param  RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor.
+  *   This parameter can be RCC_PREDIV1_Divx where x:[1,16]
+  * @retval None
+  */
+void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_PREDIV1_SOURCE(RCC_PREDIV1_Source));
+  assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div));
+
+  tmpreg = RCC->CFGR2;
+  /* Clear PREDIV1[3:0] and PREDIV1SRC bits */
+  tmpreg &= ~(CFGR2_PREDIV1 | CFGR2_PREDIV1SRC);
+  /* Set the PREDIV1 clock source and division factor */
+  tmpreg |= RCC_PREDIV1_Source | RCC_PREDIV1_Div ;
+  /* Store the new value */
+  RCC->CFGR2 = tmpreg;
+}
+
+
+/**
+  * @brief  Configures the PREDIV2 division factor.
+  * @note 
+  *   - This function must be used only when both PLL2 and PLL3 are disabled.
+  *   - This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_PREDIV2_Div: specifies the PREDIV2 clock division factor.
+  *   This parameter can be RCC_PREDIV2_Divx where x:[1,16]
+  * @retval None
+  */
+void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_PREDIV2(RCC_PREDIV2_Div));
+
+  tmpreg = RCC->CFGR2;
+  /* Clear PREDIV2[3:0] bits */
+  tmpreg &= ~CFGR2_PREDIV2;
+  /* Set the PREDIV2 division factor */
+  tmpreg |= RCC_PREDIV2_Div;
+  /* Store the new value */
+  RCC->CFGR2 = tmpreg;
+}
+
+/**
+  * @brief  Configures the PLL2 multiplication factor.
+  * @note
+  *   - This function must be used only when the PLL2 is disabled.
+  *   - This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_PLL2Mul: specifies the PLL2 multiplication factor.
+  *   This parameter can be RCC_PLL2Mul_x where x:{[8,14], 16, 20}
+  * @retval None
+  */
+void RCC_PLL2Config(uint32_t RCC_PLL2Mul)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_PLL2_MUL(RCC_PLL2Mul));
+
+  tmpreg = RCC->CFGR2;
+  /* Clear PLL2Mul[3:0] bits */
+  tmpreg &= ~CFGR2_PLL2MUL;
+  /* Set the PLL2 configuration bits */
+  tmpreg |= RCC_PLL2Mul;
+  /* Store the new value */
+  RCC->CFGR2 = tmpreg;
+}
+
+
+/**
+  * @brief  Enables or disables the PLL2.
+  * @note 
+  *   - The PLL2 can not be disabled if it is used indirectly as system clock
+  *     (i.e. it is used as PLL clock entry that is used as System clock).
+  *   - This function applies only to STM32 Connectivity line devices.
+  * @param  NewState: new state of the PLL2. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_PLL2Cmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CR_PLL2ON_BB = (uint32_t)NewState;
+}
+
+
+/**
+  * @brief  Configures the PLL3 multiplication factor.
+  * @note 
+  *   - This function must be used only when the PLL3 is disabled.
+  *   - This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_PLL3Mul: specifies the PLL3 multiplication factor.
+  *   This parameter can be RCC_PLL3Mul_x where x:{[8,14], 16, 20}
+  * @retval None
+  */
+void RCC_PLL3Config(uint32_t RCC_PLL3Mul)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_PLL3_MUL(RCC_PLL3Mul));
+
+  tmpreg = RCC->CFGR2;
+  /* Clear PLL3Mul[3:0] bits */
+  tmpreg &= ~CFGR2_PLL3MUL;
+  /* Set the PLL3 configuration bits */
+  tmpreg |= RCC_PLL3Mul;
+  /* Store the new value */
+  RCC->CFGR2 = tmpreg;
+}
+
+
+/**
+  * @brief  Enables or disables the PLL3.
+  * @note   This function applies only to STM32 Connectivity line devices.
+  * @param  NewState: new state of the PLL3. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_PLL3Cmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_PLL3ON_BB = (uint32_t)NewState;
+}
+#endif /* STM32F10X_CL */
+
+/**
+  * @brief  Configures the system clock (SYSCLK).
+  * @param  RCC_SYSCLKSource: specifies the clock source used as system clock.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_SYSCLKSource_HSI: HSI selected as system clock
+  *     @arg RCC_SYSCLKSource_HSE: HSE selected as system clock
+  *     @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock
+  * @retval None
+  */
+void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));
+  tmpreg = RCC->CFGR;
+  /* Clear SW[1:0] bits */
+  tmpreg &= CFGR_SW_Mask;
+  /* Set SW[1:0] bits according to RCC_SYSCLKSource value */
+  tmpreg |= RCC_SYSCLKSource;
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Returns the clock source used as system clock.
+  * @param  None
+  * @retval The clock source used as system clock. The returned value can
+  *   be one of the following:
+  *     - 0x00: HSI used as system clock
+  *     - 0x04: HSE used as system clock
+  *     - 0x08: PLL used as system clock
+  */
+uint8_t RCC_GetSYSCLKSource(void)
+{
+  return ((uint8_t)(RCC->CFGR & CFGR_SWS_Mask));
+}
+
+/**
+  * @brief  Configures the AHB clock (HCLK).
+  * @param  RCC_SYSCLK: defines the AHB clock divider. This clock is derived from 
+  *   the system clock (SYSCLK).
+  *   This parameter can be one of the following values:
+  *     @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK
+  *     @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2
+  *     @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4
+  *     @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8
+  *     @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16
+  *     @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64
+  *     @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128
+  *     @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256
+  *     @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512
+  * @retval None
+  */
+void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_RCC_HCLK(RCC_SYSCLK));
+  tmpreg = RCC->CFGR;
+  /* Clear HPRE[3:0] bits */
+  tmpreg &= CFGR_HPRE_Reset_Mask;
+  /* Set HPRE[3:0] bits according to RCC_SYSCLK value */
+  tmpreg |= RCC_SYSCLK;
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Configures the Low Speed APB clock (PCLK1).
+  * @param  RCC_HCLK: defines the APB1 clock divider. This clock is derived from 
+  *   the AHB clock (HCLK).
+  *   This parameter can be one of the following values:
+  *     @arg RCC_HCLK_Div1: APB1 clock = HCLK
+  *     @arg RCC_HCLK_Div2: APB1 clock = HCLK/2
+  *     @arg RCC_HCLK_Div4: APB1 clock = HCLK/4
+  *     @arg RCC_HCLK_Div8: APB1 clock = HCLK/8
+  *     @arg RCC_HCLK_Div16: APB1 clock = HCLK/16
+  * @retval None
+  */
+void RCC_PCLK1Config(uint32_t RCC_HCLK)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_RCC_PCLK(RCC_HCLK));
+  tmpreg = RCC->CFGR;
+  /* Clear PPRE1[2:0] bits */
+  tmpreg &= CFGR_PPRE1_Reset_Mask;
+  /* Set PPRE1[2:0] bits according to RCC_HCLK value */
+  tmpreg |= RCC_HCLK;
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Configures the High Speed APB clock (PCLK2).
+  * @param  RCC_HCLK: defines the APB2 clock divider. This clock is derived from 
+  *   the AHB clock (HCLK).
+  *   This parameter can be one of the following values:
+  *     @arg RCC_HCLK_Div1: APB2 clock = HCLK
+  *     @arg RCC_HCLK_Div2: APB2 clock = HCLK/2
+  *     @arg RCC_HCLK_Div4: APB2 clock = HCLK/4
+  *     @arg RCC_HCLK_Div8: APB2 clock = HCLK/8
+  *     @arg RCC_HCLK_Div16: APB2 clock = HCLK/16
+  * @retval None
+  */
+void RCC_PCLK2Config(uint32_t RCC_HCLK)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_RCC_PCLK(RCC_HCLK));
+  tmpreg = RCC->CFGR;
+  /* Clear PPRE2[2:0] bits */
+  tmpreg &= CFGR_PPRE2_Reset_Mask;
+  /* Set PPRE2[2:0] bits according to RCC_HCLK value */
+  tmpreg |= RCC_HCLK << 3;
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the specified RCC interrupts.
+  * @param  RCC_IT: specifies the RCC interrupt sources to be enabled or disabled.
+  * 
+  *   For @b STM32_Connectivity_line_devices, this parameter can be any combination
+  *   of the following values        
+  *     @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *     @arg RCC_IT_LSERDY: LSE ready interrupt
+  *     @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *     @arg RCC_IT_HSERDY: HSE ready interrupt
+  *     @arg RCC_IT_PLLRDY: PLL ready interrupt
+  *     @arg RCC_IT_PLL2RDY: PLL2 ready interrupt
+  *     @arg RCC_IT_PLL3RDY: PLL3 ready interrupt
+  * 
+  *   For @b other_STM32_devices, this parameter can be any combination of the 
+  *   following values        
+  *     @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *     @arg RCC_IT_LSERDY: LSE ready interrupt
+  *     @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *     @arg RCC_IT_HSERDY: HSE ready interrupt
+  *     @arg RCC_IT_PLLRDY: PLL ready interrupt
+  *       
+  * @param  NewState: new state of the specified RCC interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_IT(RCC_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Perform Byte access to RCC_CIR bits to enable the selected interrupts */
+    *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT;
+  }
+  else
+  {
+    /* Perform Byte access to RCC_CIR bits to disable the selected interrupts */
+    *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT;
+  }
+}
+
+#ifndef STM32F10X_CL
+/**
+  * @brief  Configures the USB clock (USBCLK).
+  * @param  RCC_USBCLKSource: specifies the USB clock source. This clock is 
+  *   derived from the PLL output.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB 
+  *                                     clock source
+  *     @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source
+  * @retval None
+  */
+void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource));
+
+  *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource;
+}
+#else
+/**
+  * @brief  Configures the USB OTG FS clock (OTGFSCLK).
+  *   This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_OTGFSCLKSource: specifies the USB OTG FS clock source.
+  *   This clock is derived from the PLL output.
+  *   This parameter can be one of the following values:
+  *     @arg  RCC_OTGFSCLKSource_PLLVCO_Div3: PLL VCO clock divided by 2 selected as USB OTG FS clock source
+  *     @arg  RCC_OTGFSCLKSource_PLLVCO_Div2: PLL VCO clock divided by 2 selected as USB OTG FS clock source
+  * @retval None
+  */
+void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_OTGFSCLK_SOURCE(RCC_OTGFSCLKSource));
+
+  *(__IO uint32_t *) CFGR_OTGFSPRE_BB = RCC_OTGFSCLKSource;
+}
+#endif /* STM32F10X_CL */ 
+
+/**
+  * @brief  Configures the ADC clock (ADCCLK).
+  * @param  RCC_PCLK2: defines the ADC clock divider. This clock is derived from 
+  *   the APB2 clock (PCLK2).
+  *   This parameter can be one of the following values:
+  *     @arg RCC_PCLK2_Div2: ADC clock = PCLK2/2
+  *     @arg RCC_PCLK2_Div4: ADC clock = PCLK2/4
+  *     @arg RCC_PCLK2_Div6: ADC clock = PCLK2/6
+  *     @arg RCC_PCLK2_Div8: ADC clock = PCLK2/8
+  * @retval None
+  */
+void RCC_ADCCLKConfig(uint32_t RCC_PCLK2)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_RCC_ADCCLK(RCC_PCLK2));
+  tmpreg = RCC->CFGR;
+  /* Clear ADCPRE[1:0] bits */
+  tmpreg &= CFGR_ADCPRE_Reset_Mask;
+  /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */
+  tmpreg |= RCC_PCLK2;
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+#ifdef STM32F10X_CL
+/**
+  * @brief  Configures the I2S2 clock source(I2S2CLK).
+  * @note
+  *   - This function must be called before enabling I2S2 APB clock.
+  *   - This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_I2S2CLKSource: specifies the I2S2 clock source.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_I2S2CLKSource_SYSCLK: system clock selected as I2S2 clock entry
+  *     @arg RCC_I2S2CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S2 clock entry
+  * @retval None
+  */
+void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_I2S2CLK_SOURCE(RCC_I2S2CLKSource));
+
+  *(__IO uint32_t *) CFGR2_I2S2SRC_BB = RCC_I2S2CLKSource;
+}
+
+/**
+  * @brief  Configures the I2S3 clock source(I2S2CLK).
+  * @note
+  *   - This function must be called before enabling I2S3 APB clock.
+  *   - This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_I2S3CLKSource: specifies the I2S3 clock source.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_I2S3CLKSource_SYSCLK: system clock selected as I2S3 clock entry
+  *     @arg RCC_I2S3CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S3 clock entry
+  * @retval None
+  */
+void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_I2S3CLK_SOURCE(RCC_I2S3CLKSource));
+
+  *(__IO uint32_t *) CFGR2_I2S3SRC_BB = RCC_I2S3CLKSource;
+}
+#endif /* STM32F10X_CL */
+
+/**
+  * @brief  Configures the External Low Speed oscillator (LSE).
+  * @param  RCC_LSE: specifies the new state of the LSE.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_LSE_OFF: LSE oscillator OFF
+  *     @arg RCC_LSE_ON: LSE oscillator ON
+  *     @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock
+  * @retval None
+  */
+void RCC_LSEConfig(uint8_t RCC_LSE)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_LSE(RCC_LSE));
+  /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/
+  /* Reset LSEON bit */
+  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;
+  /* Reset LSEBYP bit */
+  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;
+  /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */
+  switch(RCC_LSE)
+  {
+    case RCC_LSE_ON:
+      /* Set LSEON bit */
+      *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON;
+      break;
+      
+    case RCC_LSE_Bypass:
+      /* Set LSEBYP and LSEON bits */
+      *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON;
+      break;            
+      
+    default:
+      break;      
+  }
+}
+
+/**
+  * @brief  Enables or disables the Internal Low Speed oscillator (LSI).
+  * @note   LSI can not be disabled if the IWDG is running.
+  * @param  NewState: new state of the LSI. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_LSICmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the RTC clock (RTCCLK).
+  * @note   Once the RTC clock is selected it can’t be changed unless the Backup domain is reset.
+  * @param  RCC_RTCCLKSource: specifies the RTC clock source.
+  *   This parameter can be one of the following values:
+  *     @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock
+  *     @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock
+  *     @arg RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128 selected as RTC clock
+  * @retval None
+  */
+void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));
+  /* Select the RTC clock source */
+  RCC->BDCR |= RCC_RTCCLKSource;
+}
+
+/**
+  * @brief  Enables or disables the RTC clock.
+  * @note   This function must be used only after the RTC clock was selected using the RCC_RTCCLKConfig function.
+  * @param  NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_RTCCLKCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Returns the frequencies of different on chip clocks.
+  * @param  RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold
+  *   the clocks frequencies.
+  * @retval None
+  */
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
+{
+  uint32_t tmp = 0, pllmull = 0, pllsource = 0, presc = 0;
+
+#ifdef  STM32F10X_CL
+  uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0;
+#endif /* STM32F10X_CL */
+    
+  /* Get SYSCLK source -------------------------------------------------------*/
+  tmp = RCC->CFGR & CFGR_SWS_Mask;
+  
+  switch (tmp)
+  {
+    case 0x00:  /* HSI used as system clock */
+      RCC_Clocks->SYSCLK_Frequency = HSI_Value;
+      break;
+    case 0x04:  /* HSE used as system clock */
+      RCC_Clocks->SYSCLK_Frequency = HSE_Value;
+      break;
+    case 0x08:  /* PLL used as system clock */
+
+      /* Get PLL clock source and multiplication factor ----------------------*/
+      pllmull = RCC->CFGR & CFGR_PLLMull_Mask;
+      pllsource = RCC->CFGR & CFGR_PLLSRC_Mask;
+      
+#ifndef STM32F10X_CL      
+      pllmull = ( pllmull >> 18) + 2;
+      
+      if (pllsource == 0x00)
+      {/* HSI oscillator clock divided by 2 selected as PLL clock entry */
+        RCC_Clocks->SYSCLK_Frequency = (HSI_Value >> 1) * pllmull;
+      }
+      else
+      {/* HSE selected as PLL clock entry */
+        if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET)
+        {/* HSE oscillator clock divided by 2 */
+          RCC_Clocks->SYSCLK_Frequency = (HSE_Value >> 1) * pllmull;
+        }
+        else
+        {
+          RCC_Clocks->SYSCLK_Frequency = HSE_Value * pllmull;
+        }
+      }
+#else
+      pllmull = pllmull >> 18;
+      
+      if (pllmull != 0x0D)
+      {
+         pllmull += 2;
+      }
+      else
+      { /* PLL multiplication factor = PLL input clock * 6.5 */
+        pllmull = 13 / 2; 
+      }
+            
+      if (pllsource == 0x00)
+      {/* HSI oscillator clock divided by 2 selected as PLL clock entry */
+        RCC_Clocks->SYSCLK_Frequency = (HSI_Value >> 1) * pllmull;
+      }
+      else
+      {/* PREDIV1 selected as PLL clock entry */
+        
+        /* Get PREDIV1 clock source and division factor */
+        prediv1source = RCC->CFGR2 & CFGR2_PREDIV1SRC;
+        prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1;
+        
+        if (prediv1source == 0)
+        { /* HSE oscillator clock selected as PREDIV1 clock entry */
+          RCC_Clocks->SYSCLK_Frequency = (HSE_Value / prediv1factor) * pllmull;          
+        }
+        else
+        {/* PLL2 clock selected as PREDIV1 clock entry */
+          
+          /* Get PREDIV2 division factor and PLL2 multiplication factor */
+          prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1;
+          pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2; 
+          RCC_Clocks->SYSCLK_Frequency = (((HSE_Value / prediv2factor) * pll2mull) / prediv1factor) * pllmull;                         
+        }
+      }
+#endif /* STM32F10X_CL */ 
+      break;
+
+    default:
+      RCC_Clocks->SYSCLK_Frequency = HSI_Value;
+      break;
+  }
+
+  /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/
+  /* Get HCLK prescaler */
+  tmp = RCC->CFGR & CFGR_HPRE_Set_Mask;
+  tmp = tmp >> 4;
+  presc = APBAHBPrescTable[tmp];
+  /* HCLK clock frequency */
+  RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc;
+  /* Get PCLK1 prescaler */
+  tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask;
+  tmp = tmp >> 8;
+  presc = APBAHBPrescTable[tmp];
+  /* PCLK1 clock frequency */
+  RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+  /* Get PCLK2 prescaler */
+  tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask;
+  tmp = tmp >> 11;
+  presc = APBAHBPrescTable[tmp];
+  /* PCLK2 clock frequency */
+  RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+  /* Get ADCCLK prescaler */
+  tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask;
+  tmp = tmp >> 14;
+  presc = ADCPrescTable[tmp];
+  /* ADCCLK clock frequency */
+  RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc;
+}
+
+/**
+  * @brief  Enables or disables the AHB peripheral clock.
+  * @param  RCC_AHBPeriph: specifies the AHB peripheral to gates its clock.
+  *   
+  *   For @b STM32_Connectivity_line_devices, this parameter can be any combination
+  *   of the following values:        
+  *     @arg RCC_AHBPeriph_DMA1
+  *     @arg RCC_AHBPeriph_DMA2
+  *     @arg RCC_AHBPeriph_SRAM
+  *     @arg RCC_AHBPeriph_FLITF
+  *     @arg RCC_AHBPeriph_CRC
+  *     @arg RCC_AHBPeriph_OTG_FS    
+  *     @arg RCC_AHBPeriph_ETH_MAC   
+  *     @arg RCC_AHBPeriph_ETH_MAC_Tx
+  *     @arg RCC_AHBPeriph_ETH_MAC_Rx
+  * 
+  *   For @b other_STM32_devices, this parameter can be any combination of the 
+  *   following values:        
+  *     @arg RCC_AHBPeriph_DMA1
+  *     @arg RCC_AHBPeriph_DMA2
+  *     @arg RCC_AHBPeriph_SRAM
+  *     @arg RCC_AHBPeriph_FLITF
+  *     @arg RCC_AHBPeriph_CRC
+  *     @arg RCC_AHBPeriph_FSMC
+  *     @arg RCC_AHBPeriph_SDIO
+  *   
+  * @note SRAM and FLITF clock can be disabled only during sleep mode.
+  * @param  NewState: new state of the specified peripheral clock.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->AHBENR |= RCC_AHBPeriph;
+  }
+  else
+  {
+    RCC->AHBENR &= ~RCC_AHBPeriph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the High Speed APB (APB2) peripheral clock.
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to gates its clock.
+  *   This parameter can be any combination of the following values:
+  *     @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB,
+  *          RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE,
+  *          RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1,
+  *          RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1,
+  *          RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3
+  * @param  NewState: new state of the specified peripheral clock.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB2ENR |= RCC_APB2Periph;
+  }
+  else
+  {
+    RCC->APB2ENR &= ~RCC_APB2Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the Low Speed APB (APB1) peripheral clock.
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to gates its clock.
+  *   This parameter can be any combination of the following values:
+  *     @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
+  *          RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
+  *          RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
+  *          RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, 
+  *          RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
+  *          RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP,
+  *          RCC_APB1Periph_PWR, RCC_APB1Periph_DAC
+  * @param  NewState: new state of the specified peripheral clock.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB1ENR |= RCC_APB1Periph;
+  }
+  else
+  {
+    RCC->APB1ENR &= ~RCC_APB1Periph;
+  }
+}
+
+#ifdef STM32F10X_CL
+/**
+  * @brief  Forces or releases AHB peripheral reset.
+  * @note   This function applies only to STM32 Connectivity line devices.
+  * @param  RCC_AHBPeriph: specifies the AHB peripheral to reset.
+  *   This parameter can be any combination of the following values:
+  *     @arg RCC_AHBPeriph_OTG_FS 
+  *     @arg RCC_AHBPeriph_ETH_MAC
+  * @param  NewState: new state of the specified peripheral reset.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB_PERIPH_RESET(RCC_AHBPeriph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->AHBRSTR |= RCC_AHBPeriph;
+  }
+  else
+  {
+    RCC->AHBRSTR &= ~RCC_AHBPeriph;
+  }
+}
+#endif /* STM32F10X_CL */ 
+
+/**
+  * @brief  Forces or releases High Speed APB (APB2) peripheral reset.
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to reset.
+  *   This parameter can be any combination of the following values:
+  *     @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB,
+  *          RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE,
+  *          RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1,
+  *          RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1,
+  *          RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3
+  * @param  NewState: new state of the specified peripheral reset.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB2RSTR |= RCC_APB2Periph;
+  }
+  else
+  {
+    RCC->APB2RSTR &= ~RCC_APB2Periph;
+  }
+}
+
+/**
+  * @brief  Forces or releases Low Speed APB (APB1) peripheral reset.
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to reset.
+  *   This parameter can be any combination of the following values:
+  *     @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4,
+  *          RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7,
+  *          RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3,
+  *          RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, 
+  *          RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2,
+  *          RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP,
+  *          RCC_APB1Periph_PWR, RCC_APB1Periph_DAC
+  * @param  NewState: new state of the specified peripheral clock.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB1RSTR |= RCC_APB1Periph;
+  }
+  else
+  {
+    RCC->APB1RSTR &= ~RCC_APB1Periph;
+  }
+}
+
+/**
+  * @brief  Forces or releases the Backup domain reset.
+  * @param  NewState: new state of the Backup domain reset.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_BackupResetCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the Clock Security System.
+  * @param  NewState: new state of the Clock Security System..
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Selects the clock source to output on MCO pin.
+  * @param  RCC_MCO: specifies the clock source to output.
+  *   
+  *   For @b STM32_Connectivity_line_devices, this parameter can be one of the
+  *   following values:       
+  *     @arg RCC_MCO_NoClock: No clock selected
+  *     @arg RCC_MCO_SYSCLK: System clock selected
+  *     @arg RCC_MCO_HSI: HSI oscillator clock selected
+  *     @arg RCC_MCO_HSE: HSE oscillator clock selected
+  *     @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected
+  *     @arg RCC_MCO_PLL2CLK: PLL2 clock selected                     
+  *     @arg RCC_MCO_PLL3CLK_Div2: PLL3 clock divided by 2 selected   
+  *     @arg RCC_MCO_XT1: External 3-25 MHz oscillator clock selected  
+  *     @arg RCC_MCO_PLL3CLK: PLL3 clock selected 
+  * 
+  *   For  @b other_STM32_devices, this parameter can be one of the following values:        
+  *     @arg RCC_MCO_NoClock: No clock selected
+  *     @arg RCC_MCO_SYSCLK: System clock selected
+  *     @arg RCC_MCO_HSI: HSI oscillator clock selected
+  *     @arg RCC_MCO_HSE: HSE oscillator clock selected
+  *     @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected
+  *   
+  * @retval None
+  */
+void RCC_MCOConfig(uint8_t RCC_MCO)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_MCO(RCC_MCO));
+
+  /* Perform Byte access to MCO bits to select the MCO source */
+  *(__IO uint8_t *) CFGR_BYTE4_ADDRESS = RCC_MCO;
+}
+
+/**
+  * @brief  Checks whether the specified RCC flag is set or not.
+  * @param  RCC_FLAG: specifies the flag to check.
+  *   
+  *   For @b STM32_Connectivity_line_devices, this parameter can be one of the
+  *   following values:
+  *     @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready
+  *     @arg RCC_FLAG_HSERDY: HSE oscillator clock ready
+  *     @arg RCC_FLAG_PLLRDY: PLL clock ready
+  *     @arg RCC_FLAG_PLL2RDY: PLL2 clock ready      
+  *     @arg RCC_FLAG_PLL3RDY: PLL3 clock ready                           
+  *     @arg RCC_FLAG_LSERDY: LSE oscillator clock ready
+  *     @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready
+  *     @arg RCC_FLAG_PINRST: Pin reset
+  *     @arg RCC_FLAG_PORRST: POR/PDR reset
+  *     @arg RCC_FLAG_SFTRST: Software reset
+  *     @arg RCC_FLAG_IWDGRST: Independent Watchdog reset
+  *     @arg RCC_FLAG_WWDGRST: Window Watchdog reset
+  *     @arg RCC_FLAG_LPWRRST: Low Power reset
+  * 
+  *   For @b other_STM32_devices, this parameter can be one of the following values:        
+  *     @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready
+  *     @arg RCC_FLAG_HSERDY: HSE oscillator clock ready
+  *     @arg RCC_FLAG_PLLRDY: PLL clock ready
+  *     @arg RCC_FLAG_LSERDY: LSE oscillator clock ready
+  *     @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready
+  *     @arg RCC_FLAG_PINRST: Pin reset
+  *     @arg RCC_FLAG_PORRST: POR/PDR reset
+  *     @arg RCC_FLAG_SFTRST: Software reset
+  *     @arg RCC_FLAG_IWDGRST: Independent Watchdog reset
+  *     @arg RCC_FLAG_WWDGRST: Window Watchdog reset
+  *     @arg RCC_FLAG_LPWRRST: Low Power reset
+  *   
+  * @retval The new state of RCC_FLAG (SET or RESET).
+  */
+FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG)
+{
+  uint32_t tmp = 0;
+  uint32_t statusreg = 0;
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_RCC_FLAG(RCC_FLAG));
+
+  /* Get the RCC register index */
+  tmp = RCC_FLAG >> 5;
+  if (tmp == 1)               /* The flag to check is in CR register */
+  {
+    statusreg = RCC->CR;
+  }
+  else if (tmp == 2)          /* The flag to check is in BDCR register */
+  {
+    statusreg = RCC->BDCR;
+  }
+  else                       /* The flag to check is in CSR register */
+  {
+    statusreg = RCC->CSR;
+  }
+
+  /* Get the flag position */
+  tmp = RCC_FLAG & FLAG_Mask;
+  if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the RCC reset flags.
+  * @note   The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST,
+  *   RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST
+  * @param  None
+  * @retval None
+  */
+void RCC_ClearFlag(void)
+{
+  /* Set RMVF bit to clear the reset flags */
+  RCC->CSR |= CSR_RMVF_Set;
+}
+
+/**
+  * @brief  Checks whether the specified RCC interrupt has occurred or not.
+  * @param  RCC_IT: specifies the RCC interrupt source to check.
+  *   
+  *   For @b STM32_Connectivity_line_devices, this parameter can be one of the
+  *   following values:
+  *     @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *     @arg RCC_IT_LSERDY: LSE ready interrupt
+  *     @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *     @arg RCC_IT_HSERDY: HSE ready interrupt
+  *     @arg RCC_IT_PLLRDY: PLL ready interrupt
+  *     @arg RCC_IT_PLL2RDY: PLL2 ready interrupt 
+  *     @arg RCC_IT_PLL3RDY: PLL3 ready interrupt                      
+  *     @arg RCC_IT_CSS: Clock Security System interrupt
+  * 
+  *   For @b other_STM32_devices, this parameter can be one of the following values:        
+  *     @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *     @arg RCC_IT_LSERDY: LSE ready interrupt
+  *     @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *     @arg RCC_IT_HSERDY: HSE ready interrupt
+  *     @arg RCC_IT_PLLRDY: PLL ready interrupt
+  *     @arg RCC_IT_CSS: Clock Security System interrupt
+  *   
+  * @retval The new state of RCC_IT (SET or RESET).
+  */
+ITStatus RCC_GetITStatus(uint8_t RCC_IT)
+{
+  ITStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_RCC_GET_IT(RCC_IT));
+
+  /* Check the status of the specified RCC interrupt */
+  if ((RCC->CIR & RCC_IT) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+
+  /* Return the RCC_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the RCC’s interrupt pending bits.
+  * @param  RCC_IT: specifies the interrupt pending bit to clear.
+  *   
+  *   For @b STM32_Connectivity_line_devices, this parameter can be any combination
+  *   of the following values:
+  *     @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *     @arg RCC_IT_LSERDY: LSE ready interrupt
+  *     @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *     @arg RCC_IT_HSERDY: HSE ready interrupt
+  *     @arg RCC_IT_PLLRDY: PLL ready interrupt
+  *     @arg RCC_IT_PLL2RDY: PLL2 ready interrupt 
+  *     @arg RCC_IT_PLL3RDY: PLL3 ready interrupt                      
+  *     @arg RCC_IT_CSS: Clock Security System interrupt
+  * 
+  *   For @b other_STM32_devices, this parameter can be any combination of the
+  *   following values:        
+  *     @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *     @arg RCC_IT_LSERDY: LSE ready interrupt
+  *     @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *     @arg RCC_IT_HSERDY: HSE ready interrupt
+  *     @arg RCC_IT_PLLRDY: PLL ready interrupt
+  *   
+  *     @arg RCC_IT_CSS: Clock Security System interrupt
+  * @retval None
+  */
+void RCC_ClearITPendingBit(uint8_t RCC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_CLEAR_IT(RCC_IT));
+
+  /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
+     pending bits */
+  *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c
new file mode 100644
index 0000000000000000000000000000000000000000..3bafe7ed1274e73fa3b72f4f30bef55658fea06e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c
@@ -0,0 +1,341 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_rtc.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the RTC firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_rtc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup RTC 
+  * @brief RTC driver modules
+  * @{
+  */
+
+/** @defgroup RTC_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Private_Defines
+  * @{
+  */
+
+#define CRL_CNF_Set      ((uint16_t)0x0010)      /*!< Configuration Flag Enable Mask */
+#define CRL_CNF_Reset    ((uint16_t)0xFFEF)      /*!< Configuration Flag Disable Mask */
+#define RTC_LSB_Mask     ((uint32_t)0x0000FFFF)  /*!< RTC LSB Mask */
+#define PRLH_MSB_Mask    ((uint32_t)0x000F0000)  /*!< RTC Prescaler MSB Mask */
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified RTC interrupts.
+  * @param  RTC_IT: specifies the RTC interrupts sources to be enabled or disabled.
+  *   This parameter can be any combination of the following values:
+  *     @arg RTC_IT_OW: Overflow interrupt
+  *     @arg RTC_IT_ALR: Alarm interrupt
+  *     @arg RTC_IT_SEC: Second interrupt
+  * @param  NewState: new state of the specified RTC interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_IT(RTC_IT));  
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    RTC->CRH |= RTC_IT;
+  }
+  else
+  {
+    RTC->CRH &= (uint16_t)~RTC_IT;
+  }
+}
+
+/**
+  * @brief  Enters the RTC configuration mode.
+  * @param  None
+  * @retval None
+  */
+void RTC_EnterConfigMode(void)
+{
+  /* Set the CNF flag to enter in the Configuration Mode */
+  RTC->CRL |= CRL_CNF_Set;
+}
+
+/**
+  * @brief  Exits from the RTC configuration mode.
+  * @param  None
+  * @retval None
+  */
+void RTC_ExitConfigMode(void)
+{
+  /* Reset the CNF flag to exit from the Configuration Mode */
+  RTC->CRL &= CRL_CNF_Reset;
+}
+
+/**
+  * @brief  Gets the RTC counter value.
+  * @param  None
+  * @retval RTC counter value.
+  */
+uint32_t RTC_GetCounter(void)
+{
+  uint16_t tmp = 0;
+  tmp = RTC->CNTL;
+  return (((uint32_t)RTC->CNTH << 16 ) | tmp) ;
+}
+
+/**
+  * @brief  Sets the RTC counter value.
+  * @param  CounterValue: RTC counter new value.
+  * @retval None
+  */
+void RTC_SetCounter(uint32_t CounterValue)
+{ 
+  RTC_EnterConfigMode();
+  /* Set RTC COUNTER MSB word */
+  RTC->CNTH = CounterValue >> 16;
+  /* Set RTC COUNTER LSB word */
+  RTC->CNTL = (CounterValue & RTC_LSB_Mask);
+  RTC_ExitConfigMode();
+}
+
+/**
+  * @brief  Sets the RTC prescaler value.
+  * @param  PrescalerValue: RTC prescaler new value.
+  * @retval None
+  */
+void RTC_SetPrescaler(uint32_t PrescalerValue)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_PRESCALER(PrescalerValue));
+  
+  RTC_EnterConfigMode();
+  /* Set RTC PRESCALER MSB word */
+  RTC->PRLH = (PrescalerValue & PRLH_MSB_Mask) >> 16;
+  /* Set RTC PRESCALER LSB word */
+  RTC->PRLL = (PrescalerValue & RTC_LSB_Mask);
+  RTC_ExitConfigMode();
+}
+
+/**
+  * @brief  Sets the RTC alarm value.
+  * @param  AlarmValue: RTC alarm new value.
+  * @retval None
+  */
+void RTC_SetAlarm(uint32_t AlarmValue)
+{  
+  RTC_EnterConfigMode();
+  /* Set the ALARM MSB word */
+  RTC->ALRH = AlarmValue >> 16;
+  /* Set the ALARM LSB word */
+  RTC->ALRL = (AlarmValue & RTC_LSB_Mask);
+  RTC_ExitConfigMode();
+}
+
+/**
+  * @brief  Gets the RTC divider value.
+  * @param  None
+  * @retval RTC Divider value.
+  */
+uint32_t RTC_GetDivider(void)
+{
+  uint32_t tmp = 0x00;
+  tmp = ((uint32_t)RTC->DIVH & (uint32_t)0x000F) << 16;
+  tmp |= RTC->DIVL;
+  return tmp;
+}
+
+/**
+  * @brief  Waits until last write operation on RTC registers has finished.
+  * @note   This function must be called before any write to RTC registers.
+  * @param  None
+  * @retval None
+  */
+void RTC_WaitForLastTask(void)
+{
+  /* Loop until RTOFF flag is set */
+  while ((RTC->CRL & RTC_FLAG_RTOFF) == (uint16_t)RESET)
+  {
+  }
+}
+
+/**
+  * @brief  Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL)
+  *   are synchronized with RTC APB clock.
+  * @note   This function must be called before any read operation after an APB reset
+  *   or an APB clock stop.
+  * @param  None
+  * @retval None
+  */
+void RTC_WaitForSynchro(void)
+{
+  /* Clear RSF flag */
+  RTC->CRL &= (uint16_t)~RTC_FLAG_RSF;
+  /* Loop until RSF flag is set */
+  while ((RTC->CRL & RTC_FLAG_RSF) == (uint16_t)RESET)
+  {
+  }
+}
+
+/**
+  * @brief  Checks whether the specified RTC flag is set or not.
+  * @param  RTC_FLAG: specifies the flag to check.
+  *   This parameter can be one the following values:
+  *     @arg RTC_FLAG_RTOFF: RTC Operation OFF flag
+  *     @arg RTC_FLAG_RSF: Registers Synchronized flag
+  *     @arg RTC_FLAG_OW: Overflow flag
+  *     @arg RTC_FLAG_ALR: Alarm flag
+  *     @arg RTC_FLAG_SEC: Second flag
+  * @retval The new state of RTC_FLAG (SET or RESET).
+  */
+FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_RTC_GET_FLAG(RTC_FLAG)); 
+  
+  if ((RTC->CRL & RTC_FLAG) != (uint16_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the RTC’s pending flags.
+  * @param  RTC_FLAG: specifies the flag to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg RTC_FLAG_RSF: Registers Synchronized flag. This flag is cleared only after
+  *                        an APB reset or an APB Clock stop.
+  *     @arg RTC_FLAG_OW: Overflow flag
+  *     @arg RTC_FLAG_ALR: Alarm flag
+  *     @arg RTC_FLAG_SEC: Second flag
+  * @retval None
+  */
+void RTC_ClearFlag(uint16_t RTC_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG)); 
+    
+  /* Clear the coressponding RTC flag */
+  RTC->CRL &= (uint16_t)~RTC_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified RTC interrupt has occured or not.
+  * @param  RTC_IT: specifies the RTC interrupts sources to check.
+  *   This parameter can be one of the following values:
+  *     @arg RTC_IT_OW: Overflow interrupt
+  *     @arg RTC_IT_ALR: Alarm interrupt
+  *     @arg RTC_IT_SEC: Second interrupt
+  * @retval The new state of the RTC_IT (SET or RESET).
+  */
+ITStatus RTC_GetITStatus(uint16_t RTC_IT)
+{
+  ITStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_RTC_GET_IT(RTC_IT)); 
+  
+  bitstatus = (ITStatus)(RTC->CRL & RTC_IT);
+  if (((RTC->CRH & RTC_IT) != (uint16_t)RESET) && (bitstatus != (uint16_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the RTC’s interrupt pending bits.
+  * @param  RTC_IT: specifies the interrupt pending bit to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg RTC_IT_OW: Overflow interrupt
+  *     @arg RTC_IT_ALR: Alarm interrupt
+  *     @arg RTC_IT_SEC: Second interrupt
+  * @retval None
+  */
+void RTC_ClearITPendingBit(uint16_t RTC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_IT(RTC_IT));  
+  
+  /* Clear the coressponding RTC pending bit */
+  RTC->CRL &= (uint16_t)~RTC_IT;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c
new file mode 100644
index 0000000000000000000000000000000000000000..e23372fcdd7684c56541b3c2ce1e8c2bcfca2a53
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c
@@ -0,0 +1,798 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_sdio.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the SDIO firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_sdio.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup SDIO 
+  * @brief SDIO driver modules
+  * @{
+  */ 
+
+/** @defgroup SDIO_Private_TypesDefinitions
+  * @{
+  */ 
+
+/* ------------ SDIO registers bit address in the alias region ----------- */
+#define SDIO_OFFSET                (SDIO_BASE - PERIPH_BASE)
+
+/* --- CLKCR Register ---*/
+
+/* Alias word address of CLKEN bit */
+#define CLKCR_OFFSET              (SDIO_OFFSET + 0x04)
+#define CLKEN_BitNumber           0x08
+#define CLKCR_CLKEN_BB            (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4))
+
+/* --- CMD Register ---*/
+
+/* Alias word address of SDIOSUSPEND bit */
+#define CMD_OFFSET                (SDIO_OFFSET + 0x0C)
+#define SDIOSUSPEND_BitNumber     0x0B
+#define CMD_SDIOSUSPEND_BB        (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4))
+
+/* Alias word address of ENCMDCOMPL bit */
+#define ENCMDCOMPL_BitNumber      0x0C
+#define CMD_ENCMDCOMPL_BB         (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4))
+
+/* Alias word address of NIEN bit */
+#define NIEN_BitNumber            0x0D
+#define CMD_NIEN_BB               (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4))
+
+/* Alias word address of ATACMD bit */
+#define ATACMD_BitNumber          0x0E
+#define CMD_ATACMD_BB             (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4))
+
+/* --- DCTRL Register ---*/
+
+/* Alias word address of DMAEN bit */
+#define DCTRL_OFFSET              (SDIO_OFFSET + 0x2C)
+#define DMAEN_BitNumber           0x03
+#define DCTRL_DMAEN_BB            (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4))
+
+/* Alias word address of RWSTART bit */
+#define RWSTART_BitNumber         0x08
+#define DCTRL_RWSTART_BB          (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4))
+
+/* Alias word address of RWSTOP bit */
+#define RWSTOP_BitNumber          0x09
+#define DCTRL_RWSTOP_BB           (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4))
+
+/* Alias word address of RWMOD bit */
+#define RWMOD_BitNumber           0x0A
+#define DCTRL_RWMOD_BB            (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4))
+
+/* Alias word address of SDIOEN bit */
+#define SDIOEN_BitNumber          0x0B
+#define DCTRL_SDIOEN_BB           (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4))
+
+/* ---------------------- SDIO registers bit mask ------------------------ */
+
+/* --- CLKCR Register ---*/
+
+/* CLKCR register clear mask */
+#define CLKCR_CLEAR_MASK         ((uint32_t)0xFFFF8100) 
+
+/* --- PWRCTRL Register ---*/
+
+/* SDIO PWRCTRL Mask */
+#define PWR_PWRCTRL_MASK         ((uint32_t)0xFFFFFFFC)
+
+/* --- DCTRL Register ---*/
+
+/* SDIO DCTRL Clear Mask */
+#define DCTRL_CLEAR_MASK         ((uint32_t)0xFFFFFF08)
+
+/* --- CMD Register ---*/
+
+/* CMD Register clear mask */
+#define CMD_CLEAR_MASK           ((uint32_t)0xFFFFF800)
+
+/* SDIO RESP Registers Address */
+#define SDIO_RESP_ADDR           ((uint32_t)(SDIO_BASE + 0x14))
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Private_Defines
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the SDIO peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void SDIO_DeInit(void)
+{
+  SDIO->POWER = 0x00000000;
+  SDIO->CLKCR = 0x00000000;
+  SDIO->ARG = 0x00000000;
+  SDIO->CMD = 0x00000000;
+  SDIO->DTIMER = 0x00000000;
+  SDIO->DLEN = 0x00000000;
+  SDIO->DCTRL = 0x00000000;
+  SDIO->ICR = 0x00C007FF;
+  SDIO->MASK = 0x00000000;
+}
+
+/**
+  * @brief  Initializes the SDIO peripheral according to the specified 
+  *   parameters in the SDIO_InitStruct.
+  * @param  SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure 
+  *   that contains the configuration information for the SDIO peripheral.
+  * @retval None
+  */
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+  uint32_t tmpreg = 0;
+    
+  /* Check the parameters */
+  assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge));
+  assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass));
+  assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave));
+  assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide));
+  assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl)); 
+   
+/*---------------------------- SDIO CLKCR Configuration ------------------------*/  
+  /* Get the SDIO CLKCR value */
+  tmpreg = SDIO->CLKCR;
+  
+  /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */
+  tmpreg &= CLKCR_CLEAR_MASK;
+  
+  /* Set CLKDIV bits according to SDIO_ClockDiv value */
+  /* Set PWRSAV bit according to SDIO_ClockPowerSave value */
+  /* Set BYPASS bit according to SDIO_ClockBypass value */
+  /* Set WIDBUS bits according to SDIO_BusWide value */
+  /* Set NEGEDGE bits according to SDIO_ClockEdge value */
+  /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */
+  tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv  | SDIO_InitStruct->SDIO_ClockPowerSave |
+             SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide |
+             SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl); 
+  
+  /* Write to SDIO CLKCR */
+  SDIO->CLKCR = tmpreg;
+}
+
+/**
+  * @brief  Fills each SDIO_InitStruct member with its default value.
+  * @param  SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which 
+  *   will be initialized.
+  * @retval None
+  */
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+  /* SDIO_InitStruct members default value */
+  SDIO_InitStruct->SDIO_ClockDiv = 0x00;
+  SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+  SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+  SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+  SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b;
+  SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+}
+
+/**
+  * @brief  Enables or disables the SDIO Clock.
+  * @param  NewState: new state of the SDIO Clock. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_ClockCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CLKCR_CLKEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Sets the power status of the controller.
+  * @param  SDIO_PowerState: new state of the Power state. 
+  *   This parameter can be one of the following values:
+  *     @arg SDIO_PowerState_OFF
+  *     @arg SDIO_PowerState_ON
+  * @retval None
+  */
+void SDIO_SetPowerState(uint32_t SDIO_PowerState)
+{
+  /* Check the parameters */
+  assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState));
+  
+  SDIO->POWER &= PWR_PWRCTRL_MASK;
+  SDIO->POWER |= SDIO_PowerState;
+}
+
+/**
+  * @brief  Gets the power status of the controller.
+  * @param  None
+  * @retval Power status of the controller. The returned value can
+  *   be one of the following:
+  * - 0x00: Power OFF
+  * - 0x02: Power UP
+  * - 0x03: Power ON 
+  */
+uint32_t SDIO_GetPowerState(void)
+{
+  return (SDIO->POWER & (~PWR_PWRCTRL_MASK));
+}
+
+/**
+  * @brief  Enables or disables the SDIO interrupts.
+  * @param  SDIO_IT: specifies the SDIO interrupt sources to be enabled or disabled.
+  *   This parameter can be one or a combination of the following values:
+  *     @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt
+  *     @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt
+  *     @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt
+  *     @arg SDIO_IT_DTIMEOUT: Data timeout interrupt
+  *     @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+  *     @arg SDIO_IT_RXOVERR:  Received FIFO overrun error interrupt
+  *     @arg SDIO_IT_CMDREND:  Command response received (CRC check passed) interrupt
+  *     @arg SDIO_IT_CMDSENT:  Command sent (no response required) interrupt
+  *     @arg SDIO_IT_DATAEND:  Data end (data counter, SDIDCOUNT, is zero) interrupt
+  *     @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide 
+  *                            bus mode interrupt
+  *     @arg SDIO_IT_DBCKEND:  Data block sent/received (CRC check passed) interrupt
+  *     @arg SDIO_IT_CMDACT:   Command transfer in progress interrupt
+  *     @arg SDIO_IT_TXACT:    Data transmit in progress interrupt
+  *     @arg SDIO_IT_RXACT:    Data receive in progress interrupt
+  *     @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+  *     @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+  *     @arg SDIO_IT_TXFIFOF:  Transmit FIFO full interrupt
+  *     @arg SDIO_IT_RXFIFOF:  Receive FIFO full interrupt
+  *     @arg SDIO_IT_TXFIFOE:  Transmit FIFO empty interrupt
+  *     @arg SDIO_IT_RXFIFOE:  Receive FIFO empty interrupt
+  *     @arg SDIO_IT_TXDAVL:   Data available in transmit FIFO interrupt
+  *     @arg SDIO_IT_RXDAVL:   Data available in receive FIFO interrupt
+  *     @arg SDIO_IT_SDIOIT:   SD I/O interrupt received interrupt
+  *     @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt
+  * @param  NewState: new state of the specified SDIO interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None 
+  */
+void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SDIO_IT(SDIO_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the SDIO interrupts */
+    SDIO->MASK |= SDIO_IT;
+  }
+  else
+  {
+    /* Disable the SDIO interrupts */
+    SDIO->MASK &= ~SDIO_IT;
+  } 
+}
+
+/**
+  * @brief  Enables or disables the SDIO DMA request.
+  * @param  NewState: new state of the selected SDIO DMA request.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_DMACmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_DMAEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Initializes the SDIO Command according to the specified 
+  *   parameters in the SDIO_CmdInitStruct and send the command.
+  * @param  SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef 
+  *   structure that contains the configuration information for the SDIO command.
+  * @retval None
+  */
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex));
+  assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response));
+  assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait));
+  assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM));
+  
+/*---------------------------- SDIO ARG Configuration ------------------------*/
+  /* Set the SDIO Argument value */
+  SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument;
+  
+/*---------------------------- SDIO CMD Configuration ------------------------*/  
+  /* Get the SDIO CMD value */
+  tmpreg = SDIO->CMD;
+  /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */
+  tmpreg &= CMD_CLEAR_MASK;
+  /* Set CMDINDEX bits according to SDIO_CmdIndex value */
+  /* Set WAITRESP bits according to SDIO_Response value */
+  /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */
+  /* Set CPSMEN bits according to SDIO_CPSM value */
+  tmpreg |= (uint32_t)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response
+           | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM;
+  
+  /* Write to SDIO CMD */
+  SDIO->CMD = tmpreg;
+}
+
+/**
+  * @brief  Fills each SDIO_CmdInitStruct member with its default value.
+  * @param  SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef 
+  *   structure which will be initialized.
+  * @retval None
+  */
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct)
+{
+  /* SDIO_CmdInitStruct members default value */
+  SDIO_CmdInitStruct->SDIO_Argument = 0x00;
+  SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00;
+  SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No;
+  SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No;
+  SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable;
+}
+
+/**
+  * @brief  Returns command index of last command for which response received.
+  * @param  None
+  * @retval Returns the command index of the last command response received.
+  */
+uint8_t SDIO_GetCommandResponse(void)
+{
+  return (uint8_t)(SDIO->RESPCMD);
+}
+
+/**
+  * @brief  Returns response received from the card for the last command.
+  * @param  SDIO_RESP: Specifies the SDIO response register. 
+  *   This parameter can be one of the following values:
+  *     @arg SDIO_RESP1: Response Register 1
+  *     @arg SDIO_RESP2: Response Register 2
+  *     @arg SDIO_RESP3: Response Register 3
+  *     @arg SDIO_RESP4: Response Register 4
+  * @retval The Corresponding response register value.
+  */
+uint32_t SDIO_GetResponse(uint32_t SDIO_RESP)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_SDIO_RESP(SDIO_RESP));
+
+  tmp = SDIO_RESP_ADDR + SDIO_RESP;
+  
+  return (*(__IO uint32_t *) tmp); 
+}
+
+/**
+  * @brief  Initializes the SDIO data path according to the specified 
+  *   parameters in the SDIO_DataInitStruct.
+  * @param  SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef structure that
+  *   contains the configuration information for the SDIO command.
+  * @retval None
+  */
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength));
+  assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize));
+  assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir));
+  assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode));
+  assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM));
+
+/*---------------------------- SDIO DTIMER Configuration ---------------------*/
+  /* Set the SDIO Data TimeOut value */
+  SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut;
+
+/*---------------------------- SDIO DLEN Configuration -----------------------*/
+  /* Set the SDIO DataLength value */
+  SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength;
+
+/*---------------------------- SDIO DCTRL Configuration ----------------------*/  
+  /* Get the SDIO DCTRL value */
+  tmpreg = SDIO->DCTRL;
+  /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */
+  tmpreg &= DCTRL_CLEAR_MASK;
+  /* Set DEN bit according to SDIO_DPSM value */
+  /* Set DTMODE bit according to SDIO_TransferMode value */
+  /* Set DTDIR bit according to SDIO_TransferDir value */
+  /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */
+  tmpreg |= (uint32_t)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir
+           | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM;
+
+  /* Write to SDIO DCTRL */
+  SDIO->DCTRL = tmpreg;
+}
+
+/**
+  * @brief  Fills each SDIO_DataInitStruct member with its default value.
+  * @param  SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef structure which
+  *   will be initialized.
+  * @retval None
+  */
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+  /* SDIO_DataInitStruct members default value */
+  SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF;
+  SDIO_DataInitStruct->SDIO_DataLength = 0x00;
+  SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+  SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard;
+  SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block;  
+  SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable;
+}
+
+/**
+  * @brief  Returns number of remaining data bytes to be transferred.
+  * @param  None
+  * @retval Number of remaining data bytes to be transferred
+  */
+uint32_t SDIO_GetDataCounter(void)
+{ 
+  return SDIO->DCOUNT;
+}
+
+/**
+  * @brief  Read one data word from Rx FIFO.
+  * @param  None
+  * @retval Data received
+  */
+uint32_t SDIO_ReadData(void)
+{ 
+  return SDIO->FIFO;
+}
+
+/**
+  * @brief  Write one data word to Tx FIFO.
+  * @param  Data: 32-bit data word to write.
+  * @retval None
+  */
+void SDIO_WriteData(uint32_t Data)
+{ 
+  SDIO->FIFO = Data;
+}
+
+/**
+  * @brief  Returns the number of words left to be written to or read from FIFO.	
+  * @param  None
+  * @retval Remaining number of words.
+  */
+uint32_t SDIO_GetFIFOCount(void)
+{ 
+  return SDIO->FIFOCNT;
+}
+
+/**
+  * @brief  Starts the SD I/O Read Wait operation.	
+  * @param  NewState: new state of the Start SDIO Read Wait operation. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_StartSDIOReadWait(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_RWSTART_BB = (uint32_t) NewState;
+}
+
+/**
+  * @brief  Stops the SD I/O Read Wait operation.	
+  * @param  NewState: new state of the Stop SDIO Read Wait operation. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_StopSDIOReadWait(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_RWSTOP_BB = (uint32_t) NewState;
+}
+
+/**
+  * @brief  Sets one of the two options of inserting read wait interval.
+  * @param  SDIO_ReadWaitMode: SD I/O Read Wait operation mode.
+  *   This parametre can be:
+  *     @arg SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK
+  *     @arg SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2
+  * @retval None
+  */
+void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode)
+{
+  /* Check the parameters */
+  assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode));
+  
+  *(__IO uint32_t *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode;
+}
+
+/**
+  * @brief  Enables or disables the SD I/O Mode Operation.
+  * @param  NewState: new state of SDIO specific operation. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_SetSDIOOperation(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_SDIOEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the SD I/O Mode suspend command sending.
+  * @param  NewState: new state of the SD I/O Mode suspend command.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_SDIOSUSPEND_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the command completion signal.
+  * @param  NewState: new state of command completion signal. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_CommandCompletionCmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_ENCMDCOMPL_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the CE-ATA interrupt.
+  * @param  NewState: new state of CE-ATA interrupt. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_CEATAITCmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)((~((uint32_t)NewState)) & ((uint32_t)0x1));
+}
+
+/**
+  * @brief  Sends CE-ATA command (CMD61).
+  * @param  NewState: new state of CE-ATA command. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_SendCEATACmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_ATACMD_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Checks whether the specified SDIO flag is set or not.
+  * @param  SDIO_FLAG: specifies the flag to check. 
+  *   This parameter can be one of the following values:
+  *     @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed)
+  *     @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed)
+  *     @arg SDIO_FLAG_CTIMEOUT: Command response timeout
+  *     @arg SDIO_FLAG_DTIMEOUT: Data timeout
+  *     @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+  *     @arg SDIO_FLAG_RXOVERR:  Received FIFO overrun error
+  *     @arg SDIO_FLAG_CMDREND:  Command response received (CRC check passed)
+  *     @arg SDIO_FLAG_CMDSENT:  Command sent (no response required)
+  *     @arg SDIO_FLAG_DATAEND:  Data end (data counter, SDIDCOUNT, is zero)
+  *     @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide 
+  *                              bus mode.
+  *     @arg SDIO_FLAG_DBCKEND:  Data block sent/received (CRC check passed)
+  *     @arg SDIO_FLAG_CMDACT:   Command transfer in progress
+  *     @arg SDIO_FLAG_TXACT:    Data transmit in progress
+  *     @arg SDIO_FLAG_RXACT:    Data receive in progress
+  *     @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty
+  *     @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full
+  *     @arg SDIO_FLAG_TXFIFOF:  Transmit FIFO full
+  *     @arg SDIO_FLAG_RXFIFOF:  Receive FIFO full
+  *     @arg SDIO_FLAG_TXFIFOE:  Transmit FIFO empty
+  *     @arg SDIO_FLAG_RXFIFOE:  Receive FIFO empty
+  *     @arg SDIO_FLAG_TXDAVL:   Data available in transmit FIFO
+  *     @arg SDIO_FLAG_RXDAVL:   Data available in receive FIFO
+  *     @arg SDIO_FLAG_SDIOIT:   SD I/O interrupt received
+  *     @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61
+  * @retval The new state of SDIO_FLAG (SET or RESET).
+  */
+FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG)
+{ 
+  FlagStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_FLAG(SDIO_FLAG));
+  
+  if ((SDIO->STA & SDIO_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the SDIO's pending flags.
+  * @param  SDIO_FLAG: specifies the flag to clear.  
+  *   This parameter can be one or a combination of the following values:
+  *     @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed)
+  *     @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed)
+  *     @arg SDIO_FLAG_CTIMEOUT: Command response timeout
+  *     @arg SDIO_FLAG_DTIMEOUT: Data timeout
+  *     @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+  *     @arg SDIO_FLAG_RXOVERR:  Received FIFO overrun error
+  *     @arg SDIO_FLAG_CMDREND:  Command response received (CRC check passed)
+  *     @arg SDIO_FLAG_CMDSENT:  Command sent (no response required)
+  *     @arg SDIO_FLAG_DATAEND:  Data end (data counter, SDIDCOUNT, is zero)
+  *     @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide 
+  *                              bus mode
+  *     @arg SDIO_FLAG_DBCKEND:  Data block sent/received (CRC check passed)
+  *     @arg SDIO_FLAG_SDIOIT:   SD I/O interrupt received
+  *     @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61
+  * @retval None
+  */
+void SDIO_ClearFlag(uint32_t SDIO_FLAG)
+{ 
+  /* Check the parameters */
+  assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG));
+   
+  SDIO->ICR = SDIO_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified SDIO interrupt has occurred or not.
+  * @param  SDIO_IT: specifies the SDIO interrupt source to check. 
+  *   This parameter can be one of the following values:
+  *     @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt
+  *     @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt
+  *     @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt
+  *     @arg SDIO_IT_DTIMEOUT: Data timeout interrupt
+  *     @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+  *     @arg SDIO_IT_RXOVERR:  Received FIFO overrun error interrupt
+  *     @arg SDIO_IT_CMDREND:  Command response received (CRC check passed) interrupt
+  *     @arg SDIO_IT_CMDSENT:  Command sent (no response required) interrupt
+  *     @arg SDIO_IT_DATAEND:  Data end (data counter, SDIDCOUNT, is zero) interrupt
+  *     @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide 
+  *                            bus mode interrupt
+  *     @arg SDIO_IT_DBCKEND:  Data block sent/received (CRC check passed) interrupt
+  *     @arg SDIO_IT_CMDACT:   Command transfer in progress interrupt
+  *     @arg SDIO_IT_TXACT:    Data transmit in progress interrupt
+  *     @arg SDIO_IT_RXACT:    Data receive in progress interrupt
+  *     @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+  *     @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+  *     @arg SDIO_IT_TXFIFOF:  Transmit FIFO full interrupt
+  *     @arg SDIO_IT_RXFIFOF:  Receive FIFO full interrupt
+  *     @arg SDIO_IT_TXFIFOE:  Transmit FIFO empty interrupt
+  *     @arg SDIO_IT_RXFIFOE:  Receive FIFO empty interrupt
+  *     @arg SDIO_IT_TXDAVL:   Data available in transmit FIFO interrupt
+  *     @arg SDIO_IT_RXDAVL:   Data available in receive FIFO interrupt
+  *     @arg SDIO_IT_SDIOIT:   SD I/O interrupt received interrupt
+  *     @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt
+  * @retval The new state of SDIO_IT (SET or RESET).
+  */
+ITStatus SDIO_GetITStatus(uint32_t SDIO_IT)
+{ 
+  ITStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_GET_IT(SDIO_IT));
+  if ((SDIO->STA & SDIO_IT) != (uint32_t)RESET)  
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the SDIO’s interrupt pending bits.
+  * @param  SDIO_IT: specifies the interrupt pending bit to clear. 
+  *   This parameter can be one or a combination of the following values:
+  *     @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt
+  *     @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt
+  *     @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt
+  *     @arg SDIO_IT_DTIMEOUT: Data timeout interrupt
+  *     @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+  *     @arg SDIO_IT_RXOVERR:  Received FIFO overrun error interrupt
+  *     @arg SDIO_IT_CMDREND:  Command response received (CRC check passed) interrupt
+  *     @arg SDIO_IT_CMDSENT:  Command sent (no response required) interrupt
+  *     @arg SDIO_IT_DATAEND:  Data end (data counter, SDIDCOUNT, is zero) interrupt
+  *     @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide 
+  *                            bus mode interrupt
+  *     @arg SDIO_IT_SDIOIT:   SD I/O interrupt received interrupt
+  *     @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61
+  * @retval None
+  */
+void SDIO_ClearITPendingBit(uint32_t SDIO_IT)
+{ 
+  /* Check the parameters */
+  assert_param(IS_SDIO_CLEAR_IT(SDIO_IT));
+   
+  SDIO->ICR = SDIO_IT;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c
new file mode 100644
index 0000000000000000000000000000000000000000..427de6baba2faf087df64ae348b48c29f542af59
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c
@@ -0,0 +1,907 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_spi.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the SPI firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_spi.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup SPI 
+  * @brief SPI driver modules
+  * @{
+  */ 
+
+/** @defgroup SPI_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup SPI_Private_Defines
+  * @{
+  */
+
+/* SPI SPE mask */
+#define CR1_SPE_Set          ((uint16_t)0x0040)
+#define CR1_SPE_Reset        ((uint16_t)0xFFBF)
+
+/* I2S I2SE mask */
+#define I2SCFGR_I2SE_Set     ((uint16_t)0x0400)
+#define I2SCFGR_I2SE_Reset   ((uint16_t)0xFBFF)
+
+/* SPI CRCNext mask */
+#define CR1_CRCNext_Set      ((uint16_t)0x1000)
+
+/* SPI CRCEN mask */
+#define CR1_CRCEN_Set        ((uint16_t)0x2000)
+#define CR1_CRCEN_Reset      ((uint16_t)0xDFFF)
+
+/* SPI SSOE mask */
+#define CR2_SSOE_Set         ((uint16_t)0x0004)
+#define CR2_SSOE_Reset       ((uint16_t)0xFFFB)
+
+/* SPI registers Masks */
+#define CR1_CLEAR_Mask       ((uint16_t)0x3040)
+#define I2SCFGR_CLEAR_Mask   ((uint16_t)0xF040)
+
+/* SPI or I2S mode selection masks */
+#define SPI_Mode_Select      ((uint16_t)0xF7FF)
+#define I2S_Mode_Select      ((uint16_t)0x0800) 
+
+/* I2S clock source selection masks */
+#define I2S2_CLOCK_SRC       ((uint32_t)(0x00020000))
+#define I2S3_CLOCK_SRC       ((uint32_t)(0x00040000))
+#define I2S_MUL_MASK         ((uint32_t)(0x0000F000))
+#define I2S_DIV_MASK         ((uint32_t)(0x000000F0))
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the SPIx peripheral registers to their default
+  *   reset values (Affects also the I2Ss).
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @retval None
+  */
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+  if (SPIx == SPI1)
+  {
+    /* Enable SPI1 reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
+    /* Release SPI1 from reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE);
+  }
+  else if (SPIx == SPI2)
+  {
+    /* Enable SPI2 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
+    /* Release SPI2 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE);
+  }
+  else
+  {
+    if (SPIx == SPI3)
+    {
+      /* Enable SPI3 reset state */
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
+      /* Release SPI3 from reset state */
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE);
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the SPIx peripheral according to the specified 
+  *   parameters in the SPI_InitStruct.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  SPI_InitStruct: pointer to a SPI_InitTypeDef structure that
+  *   contains the configuration information for the specified SPI peripheral.
+  * @retval None
+  */
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct)
+{
+  uint16_t tmpreg = 0;
+  
+  /* check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));   
+  
+  /* Check the SPI parameters */
+  assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction));
+  assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode));
+  assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize));
+  assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL));
+  assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA));
+  assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS));
+  assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler));
+  assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit));
+  assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial));
+
+/*---------------------------- SPIx CR1 Configuration ------------------------*/
+  /* Get the SPIx CR1 value */
+  tmpreg = SPIx->CR1;
+  /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
+  tmpreg &= CR1_CLEAR_Mask;
+  /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
+     master/salve mode, CPOL and CPHA */
+  /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
+  /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
+  /* Set LSBFirst bit according to SPI_FirstBit value */
+  /* Set BR bits according to SPI_BaudRatePrescaler value */
+  /* Set CPOL bit according to SPI_CPOL value */
+  /* Set CPHA bit according to SPI_CPHA value */
+  tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode |
+                  SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL |  
+                  SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS |  
+                  SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit);
+  /* Write to SPIx CR1 */
+  SPIx->CR1 = tmpreg;
+  
+  /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
+  SPIx->I2SCFGR &= SPI_Mode_Select;		
+
+/*---------------------------- SPIx CRCPOLY Configuration --------------------*/
+  /* Write to SPIx CRCPOLY */
+  SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial;
+}
+
+/**
+  * @brief  Initializes the SPIx peripheral according to the specified 
+  *   parameters in the I2S_InitStruct.
+  * @param  SPIx: where x can be  2 or 3 to select the SPI peripheral
+  *   (configured in I2S mode).
+  * @param  I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
+  *   contains the configuration information for the specified SPI peripheral
+  *   configured in I2S mode.
+  * @note
+  *  The function calculates the optimal prescaler needed to obtain the most 
+  *  accurate audio frequency (depending on the I2S clock source, the PLL values 
+  *  and the product configuration). But in case the prescaler value is greater 
+  *  than 511, the default value (0x02) will be configured instead.  *   
+  * @retval None
+  */
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
+{
+  uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
+  uint32_t tmp = 0;
+  RCC_ClocksTypeDef RCC_Clocks;
+  uint32_t sourceclock = 0;
+  
+  /* Check the I2S parameters */
+  assert_param(IS_SPI_23_PERIPH(SPIx));
+  assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
+  assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
+  assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
+  assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput));
+  assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq));
+  assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));  
+
+/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
+  /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
+  SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask; 
+  SPIx->I2SPR = 0x0002;
+  
+  /* Get the I2SCFGR register value */
+  tmpreg = SPIx->I2SCFGR;
+  
+  /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
+  if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default)
+  {
+    i2sodd = (uint16_t)0;
+    i2sdiv = (uint16_t)2;   
+  }
+  /* If the requested audio frequency is not the default, compute the prescaler */
+  else
+  {
+    /* Check the frame length (For the Prescaler computing) */
+    if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b)
+    {
+      /* Packet length is 16 bits */
+      packetlength = 1;
+    }
+    else
+    {
+      /* Packet length is 32 bits */
+      packetlength = 2;
+    }
+
+    /* Get the I2S clock source mask depending on the peripheral number */
+    if(((uint32_t)SPIx) == SPI2_BASE)
+    {
+      /* The mask is relative to I2S2 */
+      tmp = I2S2_CLOCK_SRC;
+    }
+    else 
+    {
+      /* The mask is relative to I2S3 */      
+      tmp = I2S3_CLOCK_SRC;
+    }
+
+    /* Check the I2S clock source configuration depending on the Device:
+       Only Connectivity line devices have the PLL3 VCO clock */
+#ifdef STM32F10X_CL
+    if((RCC->CFGR2 & tmp) != 0)
+    {
+      /* Get the configuration bits of RCC PLL3 multiplier */
+      tmp = (uint32_t)((RCC->CFGR2 & I2S_MUL_MASK) >> 12);
+
+      /* Get the value of the PLL3 multiplier */      
+      if((tmp > 5) && (tmp < 15))
+      {
+        /* Multplier is between 8 and 14 (value 15 is forbidden) */
+        tmp += 2;
+      }
+      else
+      {
+        if (tmp == 15)
+        {
+          /* Multiplier is 20 */
+          tmp = 20;
+        }
+      }      
+      /* Get the PREDIV2 value */
+      sourceclock = (uint32_t)(((RCC->CFGR2 & I2S_DIV_MASK) >> 4) + 1);
+      
+      /* Calculate the Source Clock frequency based on PLL3 and PREDIV2 values */
+      sourceclock = (uint32_t) ((HSE_Value / sourceclock) * tmp * 2); 
+    }
+    else
+    {
+      /* I2S Clock source is System clock: Get System Clock frequency */
+      RCC_GetClocksFreq(&RCC_Clocks);      
+      
+      /* Get the source clock value: based on System Clock value */
+      sourceclock = RCC_Clocks.SYSCLK_Frequency;
+    }        
+#else /* STM32F10X_HD */
+    /* I2S Clock source is System clock: Get System Clock frequency */
+    RCC_GetClocksFreq(&RCC_Clocks);      
+      
+    /* Get the source clock value: based on System Clock value */
+    sourceclock = RCC_Clocks.SYSCLK_Frequency;    
+#endif /* STM32F10X_CL */    
+
+    /* Compute the Real divider depending on the MCLK output state with a flaoting point */
+    if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
+    {
+      /* MCLK output is enabled */
+      tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5);
+    }
+    else
+    {
+      /* MCLK output is disabled */
+      tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5);
+    }
+    
+    /* Remove the flaoting point */
+    tmp = tmp / 10;  
+      
+    /* Check the parity of the divider */
+    i2sodd = (uint16_t)(tmp & (uint16_t)0x0001);
+   
+    /* Compute the i2sdiv prescaler */
+    i2sdiv = (uint16_t)((tmp - i2sodd) / 2);
+   
+    /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
+    i2sodd = (uint16_t) (i2sodd << 8);
+  }
+  
+  /* Test if the divider is 1 or 0 or greater than 0xFF */
+  if ((i2sdiv < 2) || (i2sdiv > 0xFF))
+  {
+    /* Set the default values */
+    i2sdiv = 2;
+    i2sodd = 0;
+  }
+
+  /* Write to SPIx I2SPR register the computed value */
+  SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput));  
+ 
+  /* Configure the I2S with the SPI_InitStruct values */
+  tmpreg |= (uint16_t)(I2S_Mode_Select | (uint16_t)(I2S_InitStruct->I2S_Mode | \
+                  (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \
+                  (uint16_t)I2S_InitStruct->I2S_CPOL))));
+ 
+  /* Write to SPIx I2SCFGR */  
+  SPIx->I2SCFGR = tmpreg;   
+}
+
+/**
+  * @brief  Fills each SPI_InitStruct member with its default value.
+  * @param  SPI_InitStruct : pointer to a SPI_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct)
+{
+/*--------------- Reset SPI init structure parameters values -----------------*/
+  /* Initialize the SPI_Direction member */
+  SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+  /* initialize the SPI_Mode member */
+  SPI_InitStruct->SPI_Mode = SPI_Mode_Slave;
+  /* initialize the SPI_DataSize member */
+  SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b;
+  /* Initialize the SPI_CPOL member */
+  SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low;
+  /* Initialize the SPI_CPHA member */
+  SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge;
+  /* Initialize the SPI_NSS member */
+  SPI_InitStruct->SPI_NSS = SPI_NSS_Hard;
+  /* Initialize the SPI_BaudRatePrescaler member */
+  SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2;
+  /* Initialize the SPI_FirstBit member */
+  SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB;
+  /* Initialize the SPI_CRCPolynomial member */
+  SPI_InitStruct->SPI_CRCPolynomial = 7;
+}
+
+/**
+  * @brief  Fills each I2S_InitStruct member with its default value.
+  * @param  I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct)
+{
+/*--------------- Reset I2S init structure parameters values -----------------*/
+  /* Initialize the I2S_Mode member */
+  I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx;
+  
+  /* Initialize the I2S_Standard member */
+  I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips;
+  
+  /* Initialize the I2S_DataFormat member */
+  I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b;
+  
+  /* Initialize the I2S_MCLKOutput member */
+  I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable;
+  
+  /* Initialize the I2S_AudioFreq member */
+  I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default;
+  
+  /* Initialize the I2S_CPOL member */
+  I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low;
+}
+
+/**
+  * @brief  Enables or disables the specified SPI peripheral.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  NewState: new state of the SPIx peripheral. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI peripheral */
+    SPIx->CR1 |= CR1_SPE_Set;
+  }
+  else
+  {
+    /* Disable the selected SPI peripheral */
+    SPIx->CR1 &= CR1_SPE_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified SPI peripheral (in I2S mode).
+  * @param  SPIx: where x can be 2 or 3 to select the SPI peripheral.
+  * @param  NewState: new state of the SPIx peripheral. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_23_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI peripheral (in I2S mode) */
+    SPIx->I2SCFGR |= I2SCFGR_I2SE_Set;
+  }
+  else
+  {
+    /* Disable the selected SPI peripheral (in I2S mode) */
+    SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified SPI/I2S interrupts.
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  *   - 2 or 3 in I2S mode
+  * @param  SPI_I2S_IT: specifies the SPI/I2S interrupt source to be enabled or disabled. 
+  *   This parameter can be one of the following values:
+  *     @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask
+  *     @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask
+  *     @arg SPI_I2S_IT_ERR: Error interrupt mask
+  * @param  NewState: new state of the specified SPI/I2S interrupt.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState)
+{
+  uint16_t itpos = 0, itmask = 0 ;
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT));
+
+  /* Get the SPI/I2S IT index */
+  itpos = SPI_I2S_IT >> 4;
+
+  /* Set the IT mask */
+  itmask = (uint16_t)1 << (uint16_t)itpos;
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI/I2S interrupt */
+    SPIx->CR2 |= itmask;
+  }
+  else
+  {
+    /* Disable the selected SPI/I2S interrupt */
+    SPIx->CR2 &= (uint16_t)~itmask;
+  }
+}
+
+/**
+  * @brief  Enables or disables the SPIx/I2Sx DMA interface.
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  *   - 2 or 3 in I2S mode
+  * @param  SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request to be enabled or disabled. 
+  *   This parameter can be any combination of the following values:
+  *     @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request
+  *     @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request
+  * @param  NewState: new state of the selected SPI/I2S DMA transfer request.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI/I2S DMA requests */
+    SPIx->CR2 |= SPI_I2S_DMAReq;
+  }
+  else
+  {
+    /* Disable the selected SPI/I2S DMA requests */
+    SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq;
+  }
+}
+
+/**
+  * @brief  Transmits a Data through the SPIx/I2Sx peripheral.
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  *   - 2 or 3 in I2S mode
+  * @param  Data : Data to be transmitted.
+  * @retval None
+  */
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  
+  /* Write in the DR register the data to be sent */
+  SPIx->DR = Data;
+}
+
+/**
+  * @brief  Returns the most recent received data by the SPIx/I2Sx peripheral. 
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  *   - 2 or 3 in I2S mode
+  * @retval The value of the received data.
+  */
+uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  
+  /* Return the data in the DR register */
+  return SPIx->DR;
+}
+
+/**
+  * @brief  Configures internally by software the NSS pin for the selected SPI.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  SPI_NSSInternalSoft: specifies the SPI NSS internal state.
+  *   This parameter can be one of the following values:
+  *     @arg SPI_NSSInternalSoft_Set: Set NSS pin internally
+  *     @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally
+  * @retval None
+  */
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft));
+  if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset)
+  {
+    /* Set NSS pin internally by software */
+    SPIx->CR1 |= SPI_NSSInternalSoft_Set;
+  }
+  else
+  {
+    /* Reset NSS pin internally by software */
+    SPIx->CR1 &= SPI_NSSInternalSoft_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the SS output for the selected SPI.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  NewState: new state of the SPIx SS output. 
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI SS output */
+    SPIx->CR2 |= CR2_SSOE_Set;
+  }
+  else
+  {
+    /* Disable the selected SPI SS output */
+    SPIx->CR2 &= CR2_SSOE_Reset;
+  }
+}
+
+/**
+  * @brief  Configures the data size for the selected SPI.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  SPI_DataSize: specifies the SPI data size.
+  *   This parameter can be one of the following values:
+  *     @arg SPI_DataSize_16b: Set data frame format to 16bit
+  *     @arg SPI_DataSize_8b: Set data frame format to 8bit
+  * @retval None
+  */
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_DATASIZE(SPI_DataSize));
+  /* Clear DFF bit */
+  SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b;
+  /* Set new DFF bit value */
+  SPIx->CR1 |= SPI_DataSize;
+}
+
+/**
+  * @brief  Transmit the SPIx CRC value.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @retval None
+  */
+void SPI_TransmitCRC(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  
+  /* Enable the selected SPI CRC transmission */
+  SPIx->CR1 |= CR1_CRCNext_Set;
+}
+
+/**
+  * @brief  Enables or disables the CRC value calculation of the transfered bytes.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  NewState: new state of the SPIx CRC value calculation.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI CRC calculation */
+    SPIx->CR1 |= CR1_CRCEN_Set;
+  }
+  else
+  {
+    /* Disable the selected SPI CRC calculation */
+    SPIx->CR1 &= CR1_CRCEN_Reset;
+  }
+}
+
+/**
+  * @brief  Returns the transmit or the receive CRC register value for the specified SPI.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  SPI_CRC: specifies the CRC register to be read.
+  *   This parameter can be one of the following values:
+  *     @arg SPI_CRC_Tx: Selects Tx CRC register
+  *     @arg SPI_CRC_Rx: Selects Rx CRC register
+  * @retval The selected CRC register value..
+  */
+uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC)
+{
+  uint16_t crcreg = 0;
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_CRC(SPI_CRC));
+  if (SPI_CRC != SPI_CRC_Rx)
+  {
+    /* Get the Tx CRC register */
+    crcreg = SPIx->TXCRCR;
+  }
+  else
+  {
+    /* Get the Rx CRC register */
+    crcreg = SPIx->RXCRCR;
+  }
+  /* Return the selected CRC register */
+  return crcreg;
+}
+
+/**
+  * @brief  Returns the CRC Polynomial register value for the specified SPI.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @retval The CRC Polynomial register value.
+  */
+uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  
+  /* Return the CRC polynomial register */
+  return SPIx->CRCPR;
+}
+
+/**
+  * @brief  Selects the data transfer direction in bi-directional mode for the specified SPI.
+  * @param  SPIx: where x can be 1, 2 or 3 to select the SPI peripheral.
+  * @param  SPI_Direction: specifies the data transfer direction in bi-directional mode. 
+  *   This parameter can be one of the following values:
+  *     @arg SPI_Direction_Tx: Selects Tx transmission direction
+  *     @arg SPI_Direction_Rx: Selects Rx receive direction
+  * @retval None
+  */
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_DIRECTION(SPI_Direction));
+  if (SPI_Direction == SPI_Direction_Tx)
+  {
+    /* Set the Tx only mode */
+    SPIx->CR1 |= SPI_Direction_Tx;
+  }
+  else
+  {
+    /* Set the Rx only mode */
+    SPIx->CR1 &= SPI_Direction_Rx;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified SPI/I2S flag is set or not.
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  *   - 2 or 3 in I2S mode
+  * @param  SPI_I2S_FLAG: specifies the SPI/I2S flag to check. 
+  *   This parameter can be one of the following values:
+  *     @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag.
+  *     @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag.
+  *     @arg SPI_I2S_FLAG_BSY: Busy flag.
+  *     @arg SPI_I2S_FLAG_OVR: Overrun flag.
+  *     @arg SPI_FLAG_MODF: Mode Fault flag.
+  *     @arg SPI_FLAG_CRCERR: CRC Error flag.
+  *     @arg I2S_FLAG_UDR: Underrun Error flag.
+  *     @arg I2S_FLAG_CHSIDE: Channel Side flag.
+  * @retval The new state of SPI_I2S_FLAG (SET or RESET).
+  */
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG));
+  /* Check the status of the specified SPI/I2S flag */
+  if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET)
+  {
+    /* SPI_I2S_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SPI_I2S_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the SPI_I2S_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the SPIx CRC Error (CRCERR) flag.
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  * @param  SPI_I2S_FLAG: specifies the SPI flag to clear. 
+  *   This function clears only CRCERR flag.
+  * @note
+  *   - OVR (OverRun error) flag is cleared by software sequence: a read 
+  *     operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read 
+  *     operation to SPI_SR register (SPI_I2S_GetFlagStatus()).
+  *   - UDR (UnderRun error) flag is cleared by a read operation to 
+  *     SPI_SR register (SPI_I2S_GetFlagStatus()).
+  *   - MODF (Mode Fault) flag is cleared by software sequence: a read/write 
+  *     operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a 
+  *     write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI).
+  * @retval None
+  */
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG));
+    
+    /* Clear the selected SPI CRC Error (CRCERR) flag */
+    SPIx->SR = (uint16_t)~SPI_I2S_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified SPI/I2S interrupt has occurred or not.
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  *   - 2 or 3 in I2S mode
+  * @param  SPI_I2S_IT: specifies the SPI/I2S interrupt source to check. 
+  *   This parameter can be one of the following values:
+  *     @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt.
+  *     @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt.
+  *     @arg SPI_I2S_IT_OVR: Overrun interrupt.
+  *     @arg SPI_IT_MODF: Mode Fault interrupt.
+  *     @arg SPI_IT_CRCERR: CRC Error interrupt.
+  *     @arg I2S_IT_UDR: Underrun Error interrupt.
+  * @retval The new state of SPI_I2S_IT (SET or RESET).
+  */
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint16_t itpos = 0, itmask = 0, enablestatus = 0;
+
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT));
+
+  /* Get the SPI/I2S IT index */
+  itpos = 0x01 << (SPI_I2S_IT & 0x0F);
+
+  /* Get the SPI/I2S IT mask */
+  itmask = SPI_I2S_IT >> 4;
+
+  /* Set the IT mask */
+  itmask = 0x01 << itmask;
+
+  /* Get the SPI_I2S_IT enable bit status */
+  enablestatus = (SPIx->CR2 & itmask) ;
+
+  /* Check the status of the specified SPI/I2S interrupt */
+  if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus)
+  {
+    /* SPI_I2S_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SPI_I2S_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the SPI_I2S_IT status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the SPIx CRC Error (CRCERR) interrupt pending bit.
+  * @param  SPIx: where x can be
+  *   - 1, 2 or 3 in SPI mode 
+  * @param  SPI_I2S_IT: specifies the SPI interrupt pending bit to clear.
+  *   This function clears only CRCERR intetrrupt pending bit.   
+  * @note
+  *   - OVR (OverRun Error) interrupt pending bit is cleared by software 
+  *     sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData()) 
+  *     followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()).
+  *   - UDR (UnderRun Error) interrupt pending bit is cleared by a read 
+  *     operation to SPI_SR register (SPI_I2S_GetITStatus()).
+  *   - MODF (Mode Fault) interrupt pending bit is cleared by software sequence:
+  *     a read/write operation to SPI_SR register (SPI_I2S_GetITStatus()) 
+  *     followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable 
+  *     the SPI).
+  * @retval None
+  */
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
+{
+  uint16_t itpos = 0;
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT));
+
+  /* Get the SPI IT index */
+  itpos = 0x01 << (SPI_I2S_IT & 0x0F);
+
+  /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */
+  SPIx->SR = (uint16_t)~itpos;
+}
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c
new file mode 100644
index 0000000000000000000000000000000000000000..b7daab9e78009d76950ebcd0a0f15596473dffc7
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c
@@ -0,0 +1,2799 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_tim.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the TIM firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_tim.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup TIM 
+  * @brief TIM driver modules
+  * @{
+  */
+
+/** @defgroup TIM_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_Defines
+  * @{
+  */
+
+/* ---------------------- TIM registers bit mask ------------------------ */
+#define CR1_CEN_Set                 ((uint16_t)0x0001)
+#define CR1_CEN_Reset               ((uint16_t)0x03FE)
+#define CR1_UDIS_Set                ((uint16_t)0x0002)
+#define CR1_UDIS_Reset              ((uint16_t)0x03FD)
+#define CR1_URS_Set                 ((uint16_t)0x0004)
+#define CR1_URS_Reset               ((uint16_t)0x03FB)
+#define CR1_OPM_Reset               ((uint16_t)0x03F7)
+#define CR1_CounterMode_Mask        ((uint16_t)0x038F)
+#define CR1_ARPE_Set                ((uint16_t)0x0080)
+#define CR1_ARPE_Reset              ((uint16_t)0x037F)
+#define CR1_CKD_Mask                ((uint16_t)0x00FF)
+#define CR2_CCPC_Set                ((uint16_t)0x0001)
+#define CR2_CCPC_Reset              ((uint16_t)0xFFFE)
+#define CR2_CCUS_Set                ((uint16_t)0x0004)
+#define CR2_CCUS_Reset              ((uint16_t)0xFFFB)
+#define CR2_CCDS_Set                ((uint16_t)0x0008)
+#define CR2_CCDS_Reset              ((uint16_t)0xFFF7)
+#define CR2_MMS_Mask                ((uint16_t)0xFF8F)
+#define CR2_TI1S_Set                ((uint16_t)0x0080)
+#define CR2_TI1S_Reset              ((uint16_t)0xFF7F)
+#define CR2_OIS1_Reset              ((uint16_t)0x7EFF)
+#define CR2_OIS1N_Reset             ((uint16_t)0x7DFF)
+#define CR2_OIS2_Reset              ((uint16_t)0x7BFF)
+#define CR2_OIS2N_Reset             ((uint16_t)0x77FF)
+#define CR2_OIS3_Reset              ((uint16_t)0x6FFF)
+#define CR2_OIS3N_Reset             ((uint16_t)0x5FFF)
+#define CR2_OIS4_Reset              ((uint16_t)0x3FFF)
+#define SMCR_SMS_Mask               ((uint16_t)0xFFF8)
+#define SMCR_ETR_Mask               ((uint16_t)0x00FF)
+#define SMCR_TS_Mask                ((uint16_t)0xFF8F)
+#define SMCR_MSM_Reset              ((uint16_t)0xFF7F)
+#define SMCR_ECE_Set                ((uint16_t)0x4000)
+#define CCMR_CC13S_Mask             ((uint16_t)0xFFFC)
+#define CCMR_CC24S_Mask             ((uint16_t)0xFCFF)
+#define CCMR_TI13Direct_Set         ((uint16_t)0x0001)
+#define CCMR_TI24Direct_Set         ((uint16_t)0x0100)
+#define CCMR_OC13FE_Reset           ((uint16_t)0xFFFB)
+#define CCMR_OC24FE_Reset           ((uint16_t)0xFBFF)
+#define CCMR_OC13PE_Reset           ((uint16_t)0xFFF7)
+#define CCMR_OC24PE_Reset           ((uint16_t)0xF7FF)
+#define CCMR_OC13M_Mask             ((uint16_t)0xFF8F)
+#define CCMR_OC24M_Mask             ((uint16_t)0x8FFF) 
+#define CCMR_OC13CE_Reset           ((uint16_t)0xFF7F)
+#define CCMR_OC24CE_Reset           ((uint16_t)0x7FFF)
+#define CCMR_IC13PSC_Mask           ((uint16_t)0xFFF3)
+#define CCMR_IC24PSC_Mask           ((uint16_t)0xF3FF)
+#define CCMR_IC13F_Mask             ((uint16_t)0xFF0F)
+#define CCMR_IC24F_Mask             ((uint16_t)0x0FFF)
+#define CCMR_Offset                 ((uint16_t)0x0018)
+#define CCER_CCE_Set                ((uint16_t)0x0001)
+#define	CCER_CCNE_Set               ((uint16_t)0x0004)
+#define CCER_CC1P_Reset             ((uint16_t)0xFFFD)
+#define CCER_CC2P_Reset             ((uint16_t)0xFFDF)
+#define CCER_CC3P_Reset             ((uint16_t)0xFDFF)
+#define CCER_CC4P_Reset             ((uint16_t)0xDFFF)
+#define CCER_CC1NP_Reset            ((uint16_t)0xFFF7)
+#define CCER_CC2NP_Reset            ((uint16_t)0xFF7F)
+#define CCER_CC3NP_Reset            ((uint16_t)0xF7FF)
+#define CCER_CC1E_Set               ((uint16_t)0x0001)
+#define CCER_CC1E_Reset             ((uint16_t)0xFFFE)
+#define CCER_CC1NE_Reset            ((uint16_t)0xFFFB)
+#define CCER_CC2E_Set               ((uint16_t)0x0010)
+#define CCER_CC2E_Reset             ((uint16_t)0xFFEF)
+#define CCER_CC2NE_Reset            ((uint16_t)0xFFBF)
+#define CCER_CC3E_Set               ((uint16_t)0x0100)
+#define CCER_CC3E_Reset             ((uint16_t)0xFEFF)
+#define CCER_CC3NE_Reset            ((uint16_t)0xFBFF)
+#define CCER_CC4E_Set               ((uint16_t)0x1000)
+#define CCER_CC4E_Reset             ((uint16_t)0xEFFF)
+#define BDTR_MOE_Set                ((uint16_t)0x8000)
+#define BDTR_MOE_Reset              ((uint16_t)0x7FFF)
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_FunctionPrototypes
+  * @{
+  */
+
+static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the TIMx peripheral registers to their default reset values.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @retval None
+  */
+void TIM_DeInit(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx)); 
+ 
+  if (TIMx == TIM1)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE);  
+  }     
+  else if (TIMx == TIM2)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE);
+  }
+  else if (TIMx == TIM3)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE);
+  }
+  else if (TIMx == TIM4)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE);
+  } 
+  else if (TIMx == TIM5)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE);
+  } 
+  else if (TIMx == TIM6)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE);
+  } 
+  else if (TIMx == TIM7)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE);
+  } 
+  else
+  {
+    if (TIMx == TIM8)
+    {
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE);
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE);
+    }  
+  }
+}
+
+/**
+  * @brief  Initializes the TIMx Time Base Unit peripheral according to 
+  *   the specified parameters in the TIM_TimeBaseInitStruct.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef
+  *   structure that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx)); 
+  assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode));
+  assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision));
+  /* Select the Counter Mode and set the clock division */
+  TIMx->CR1 &= CR1_CKD_Mask & CR1_CounterMode_Mask;
+  TIMx->CR1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision |
+                TIM_TimeBaseInitStruct->TIM_CounterMode;
+  
+  /* Set the Autoreload value */
+  TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ;
+ 
+  /* Set the Prescaler value */
+  TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler;
+    
+  if ((((uint32_t) TIMx) == TIM1_BASE) || (((uint32_t) TIMx) == TIM8_BASE))  
+  {
+    /* Set the Repetition Counter value */
+    TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter;
+  }
+
+  /* Generate an update event to reload the Prescaler value immediatly */
+  TIMx->EGR = TIM_PSCReloadMode_Immediate;          
+}
+
+/**
+  * @brief  Initializes the TIMx Channel1 according to the specified
+  *   parameters in the TIM_OCInitStruct.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+  *   that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+  /* Disable the Channel 1: Reset the CC1E Bit */
+  TIMx->CCER &= CCER_CC1E_Reset;
+  
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR1 register value */
+  tmpccmrx = TIMx->CCMR1;
+    
+  /* Reset the Output Compare mode and Capture/Compare selection Bits */
+  tmpccmrx &= CCMR_OC13M_Mask & CCMR_CC13S_Mask;
+  
+  /* Select the Output Compare Mode */
+  tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= CCER_CC1P_Reset;
+  /* Set the Output Compare Polarity */
+  tmpccer |= TIM_OCInitStruct->TIM_OCPolarity;
+  
+  /* Set the Output State */
+  tmpccer |= TIM_OCInitStruct->TIM_OutputState;
+ 
+  if(((uint32_t) TIMx == TIM1_BASE) || ((uint32_t) TIMx == TIM8_BASE))
+  {
+    assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+    assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+    assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    
+    /* Reset the Output N Polarity level */
+    tmpccer &= CCER_CC1NP_Reset;
+    /* Set the Output N Polarity */
+    tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity;
+    /* Reset the Output N State */
+    tmpccer &= CCER_CC1NE_Reset;
+    
+    /* Set the Output N State */
+    tmpccer |= TIM_OCInitStruct->TIM_OutputNState;
+    /* Reset the Ouput Compare and Output Compare N IDLE State */
+    tmpcr2 &= CR2_OIS1_Reset;
+    tmpcr2 &= CR2_OIS1N_Reset;
+    /* Set the Output Idle state */
+    tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState;
+    /* Set the Output N Idle state */
+    tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState;
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmrx;
+
+  /* Set the Capture Compare Register value */
+  TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Initializes the TIMx Channel2 according to the specified
+  *   parameters in the TIM_OCInitStruct.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+  *   that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+  /* Disable the Channel 2: Reset the CC2E Bit */
+  TIMx->CCER &= CCER_CC2E_Reset;
+  
+  /* Get the TIMx CCER register value */  
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR1 register value */
+  tmpccmrx = TIMx->CCMR1;
+
+  /* Reset the Output Compare mode and Capture/Compare selection Bits */
+  tmpccmrx &= CCMR_OC24M_Mask & CCMR_CC24S_Mask;  
+  
+  /* Select the Output Compare Mode */
+  tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8);
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= CCER_CC2P_Reset;
+  /* Set the Output Compare Polarity */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 4);
+  
+  /* Set the Output State */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 4);
+    
+  if(((uint32_t) TIMx == TIM1_BASE) || ((uint32_t) TIMx == TIM8_BASE))
+  {
+    assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+    assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+    assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    
+    /* Reset the Output N Polarity level */
+    tmpccer &= CCER_CC2NP_Reset;
+    /* Set the Output N Polarity */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 4);
+    /* Reset the Output N State */
+    tmpccer &= CCER_CC2NE_Reset;
+    
+    /* Set the Output N State */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 4);
+    /* Reset the Ouput Compare and Output Compare N IDLE State */
+    tmpcr2 &= CR2_OIS2_Reset;
+    tmpcr2 &= CR2_OIS2N_Reset;
+    /* Set the Output Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 2);
+    /* Set the Output N Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 2);
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmrx;
+
+  /* Set the Capture Compare Register value */
+  TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Initializes the TIMx Channel3 according to the specified
+  *   parameters in the TIM_OCInitStruct.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+  *   that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+  /* Disable the Channel 2: Reset the CC2E Bit */
+  TIMx->CCER &= CCER_CC3E_Reset;
+  
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR2 register value */
+  tmpccmrx = TIMx->CCMR2;
+    
+  /* Reset the Output Compare mode and Capture/Compare selection Bits */
+  tmpccmrx &= CCMR_OC13M_Mask & CCMR_CC13S_Mask;  
+  
+  /* Select the Output Compare Mode */
+  tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= CCER_CC3P_Reset;
+  /* Set the Output Compare Polarity */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 8);
+  
+  /* Set the Output State */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 8);
+   
+  if(((uint32_t) TIMx == TIM1_BASE) || ((uint32_t) TIMx == TIM8_BASE))
+  {
+    assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+    assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+    assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    
+    /* Reset the Output N Polarity level */
+    tmpccer &= CCER_CC3NP_Reset;
+    /* Set the Output N Polarity */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 8);
+    /* Reset the Output N State */
+    tmpccer &= CCER_CC3NE_Reset;
+    
+    /* Set the Output N State */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 8);
+    /* Reset the Ouput Compare and Output Compare N IDLE State */
+    tmpcr2 &= CR2_OIS3_Reset;
+    tmpcr2 &= CR2_OIS3N_Reset;
+    /* Set the Output Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 4);
+    /* Set the Output N Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 4);
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR2 */
+  TIMx->CCMR2 = tmpccmrx;
+
+  /* Set the Capture Compare Register value */
+  TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Initializes the TIMx Channel4 according to the specified
+  *   parameters in the TIM_OCInitStruct.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure
+  *   that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+  /* Disable the Channel 2: Reset the CC4E Bit */
+  TIMx->CCER &= CCER_CC4E_Reset;
+  
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR2 register value */
+  tmpccmrx = TIMx->CCMR2;
+    
+  /* Reset the Output Compare mode and Capture/Compare selection Bits */
+  tmpccmrx &= CCMR_OC24M_Mask & CCMR_CC24S_Mask; 
+   
+  /* Select the Output Compare Mode */
+  tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8);
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= CCER_CC4P_Reset;
+  /* Set the Output Compare Polarity */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 12);
+  
+  /* Set the Output State */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 12);
+    
+  if(((uint32_t) TIMx == TIM1_BASE) || ((uint32_t) TIMx == TIM8_BASE))
+  {
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    /* Reset the Ouput Compare IDLE State */
+    tmpcr2 &= CR2_OIS4_Reset;
+    /* Set the Output Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 6);
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR2 */  
+  TIMx->CCMR2 = tmpccmrx;
+
+  /* Set the Capture Compare Register value */
+  TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Initializes the TIM peripheral according to the specified
+  *   parameters in the TIM_ICInitStruct.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure
+  *   that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel));
+  assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity));
+  assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler));
+  assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter));
+  
+  if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+  {
+    /* TI1 Configuration */
+    TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2)
+  {
+    /* TI2 Configuration */
+    TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3)
+  {
+    /* TI3 Configuration */
+    TI3_Config(TIMx,  TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else
+  {
+    /* TI4 Configuration */
+    TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+}
+
+/**
+  * @brief  Configures the TIM peripheral according to the specified
+  *   parameters in the TIM_ICInitStruct to measure an external PWM signal.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure
+  *   that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+  uint16_t icoppositepolarity = TIM_ICPolarity_Rising;
+  uint16_t icoppositeselection = TIM_ICSelection_DirectTI;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Select the Opposite Input Polarity */
+  if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising)
+  {
+    icoppositepolarity = TIM_ICPolarity_Falling;
+  }
+  else
+  {
+    icoppositepolarity = TIM_ICPolarity_Rising;
+  }
+  /* Select the Opposite Input */
+  if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI)
+  {
+    icoppositeselection = TIM_ICSelection_IndirectTI;
+  }
+  else
+  {
+    icoppositeselection = TIM_ICSelection_DirectTI;
+  }
+  if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+  {
+    /* TI1 Configuration */
+    TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+    /* TI2 Configuration */
+    TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else
+  { 
+    /* TI2 Configuration */
+    TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+    /* TI1 Configuration */
+    TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+}
+
+/**
+  * @brief  Configures the: Break feature, dead time, Lock level, the OSSI,
+  *   the OSSR State and the AOE(automatic output enable).
+  * @param  TIMx: where x can be  1 or 8 to select the TIM 
+  * @param  TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that
+  *   contains the BDTR Register configuration  information for the TIM peripheral.
+  * @retval None
+  */
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState));
+  assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState));
+  assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel));
+  assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break));
+  assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity));
+  assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput));
+  /* Set the Lock level, the Break enable Bit and the Ploarity, the OSSR State,
+     the OSSI State, the dead time value and the Automatic Output Enable Bit */
+  TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState |
+             TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime |
+             TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity |
+             TIM_BDTRInitStruct->TIM_AutomaticOutput;
+}
+
+/**
+  * @brief  Fills each TIM_TimeBaseInitStruct member with its default value.
+  * @param  TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef
+  *   structure which will be initialized.
+  * @retval None
+  */
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+  /* Set the default configuration */
+  TIM_TimeBaseInitStruct->TIM_Period = 0xFFFF;
+  TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000;
+  TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1;
+  TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000;
+}
+
+/**
+  * @brief  Fills each TIM_OCInitStruct member with its default value.
+  * @param  TIM_OCInitStruct : pointer to a TIM_OCInitTypeDef structure which will
+  *   be initialized.
+  * @retval None
+  */
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  /* Set the default configuration */
+  TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing;
+  TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable;
+  TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable;
+  TIM_OCInitStruct->TIM_Pulse = 0x0000;
+  TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High;
+  TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High;
+  TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset;
+  TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset;
+}
+
+/**
+  * @brief  Fills each TIM_ICInitStruct member with its default value.
+  * @param  TIM_ICInitStruct : pointer to a TIM_ICInitTypeDef structure which will
+  *   be initialized.
+  * @retval None
+  */
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+  /* Set the default configuration */
+  TIM_ICInitStruct->TIM_Channel = TIM_Channel_1;
+  TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising;
+  TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI;
+  TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1;
+  TIM_ICInitStruct->TIM_ICFilter = 0x00;
+}
+
+/**
+  * @brief  Fills each TIM_BDTRInitStruct member with its default value.
+  * @param  TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which
+  *   will be initialized.
+  * @retval None
+  */
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct)
+{
+  /* Set the default configuration */
+  TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable;
+  TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable;
+  TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF;
+  TIM_BDTRInitStruct->TIM_DeadTime = 0x00;
+  TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable;
+  TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low;
+  TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable;
+}
+
+/**
+  * @brief  Enables or disables the specified TIM peripheral.
+  * @param  TIMx: where x can be 1 to 8 to select the TIMx peripheral.
+  * @param  NewState: new state of the TIMx peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the TIM Counter */
+    TIMx->CR1 |= CR1_CEN_Set;
+  }
+  else
+  {
+    /* Disable the TIM Counter */
+    TIMx->CR1 &= CR1_CEN_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the TIM peripheral Main Outputs.
+  * @param  TIMx: where x can be 1 or 8 to select the TIMx peripheral.
+  * @param  NewState: new state of the TIM peripheral Main Outputs.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the TIM Main Output */
+    TIMx->BDTR |= BDTR_MOE_Set;
+  }
+  else
+  {
+    /* Disable the TIM Main Output */
+    TIMx->BDTR &= BDTR_MOE_Reset;
+  }  
+}
+
+/**
+  * @brief  Enables or disables the specified TIM interrupts.
+  * @param  TIMx: where x can be 1 to 8 to select the TIMx peripheral.
+  * @param  TIM_IT: specifies the TIM interrupts sources to be enabled or disabled.
+  *   This parameter can be any combination of the following values:
+  *     @arg TIM_IT_Update: TIM update Interrupt source
+  *     @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+  *     @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+  *     @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+  *     @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+  *     @arg TIM_IT_COM: TIM Commutation Interrupt source
+  *     @arg TIM_IT_Trigger: TIM Trigger Interrupt source
+  *     @arg TIM_IT_Break: TIM Break Interrupt source
+  * @note 
+  *   - TIM6 and TIM7 can only generate an update interrupt. 
+  *   - TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8.  
+  * @param  NewState: new state of the TIM interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState)
+{  
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_IT(TIM_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the Interrupt sources */
+    TIMx->DIER |= TIM_IT;
+  }
+  else
+  {
+    /* Disable the Interrupt sources */
+    TIMx->DIER &= (uint16_t)~TIM_IT;
+  }
+}
+
+/**
+  * @brief  Configures the TIMx event to be generate by software.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_EventSource: specifies the event source.
+  *   This parameter can be one or more of the following values:	   
+  *     @arg TIM_EventSource_Update: Timer update Event source
+  *     @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source
+  *     @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source
+  *     @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source
+  *     @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source
+  *     @arg TIM_EventSource_COM: Timer COM event source  
+  *     @arg TIM_EventSource_Trigger: Timer Trigger Event source
+  *     @arg TIM_EventSource_Break: Timer Break event source
+  * @note 
+  *   - TIM6 and TIM7 can only generate an update event. 
+  *   - TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8.      
+  * @retval None
+  */
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource)
+{ 
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource));
+  
+  /* Set the event sources */
+  TIMx->EGR = TIM_EventSource;
+}
+
+/**
+  * @brief  Configures the TIMx’s DMA interface.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_DMABase: DMA Base address.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_DMABase_CR, TIM_DMABase_CR2, TIM_DMABase_SMCR,
+  *   TIM_DMABase_DIER, TIM1_DMABase_SR, TIM_DMABase_EGR,
+  *   TIM_DMABase_CCMR1, TIM_DMABase_CCMR2, TIM_DMABase_CCER,
+  *   TIM_DMABase_CNT, TIM_DMABase_PSC, TIM_DMABase_ARR,
+  *   TIM_DMABase_RCR, TIM_DMABase_CCR1, TIM_DMABase_CCR2,
+  *   TIM_DMABase_CCR3, TIM_DMABase_CCR4, TIM_DMABase_BDTR,
+  *   TIM_DMABase_DCR.
+  * @param  TIM_DMABurstLength: DMA Burst length.
+  *   This parameter can be one value between:
+  *   TIM_DMABurstLength_1Byte and TIM_DMABurstLength_18Bytes.
+  * @retval None
+  */
+void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_DMA_BASE(TIM_DMABase));
+  assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength));
+  /* Set the DMA Base and the DMA Burst Length */
+  TIMx->DCR = TIM_DMABase | TIM_DMABurstLength;
+}
+
+/**
+  * @brief  Enables or disables the TIMx’s DMA Requests.
+  * @param  TIMx: where x can be  1 to 8 to select the TIM peripheral. 
+  * @param  TIM_DMASource: specifies the DMA Request sources.
+  *   This parameter can be any combination of the following values:
+  *     @arg TIM_DMA_Update: TIM update Interrupt source
+  *     @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+  *     @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+  *     @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+  *     @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+  *     @arg TIM_DMA_COM: TIM Commutation DMA source
+  *     @arg TIM_DMA_Trigger: TIM Trigger DMA source
+  * @param  NewState: new state of the DMA Request sources.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the DMA sources */
+    TIMx->DIER |= TIM_DMASource; 
+  }
+  else
+  {
+    /* Disable the DMA sources */
+    TIMx->DIER &= (uint16_t)~TIM_DMASource;
+  }
+}
+
+/**
+  * @brief  Configures the TIMx interrnal Clock
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @retval None
+  */
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Disable slave mode to clock the prescaler directly with the internal clock */
+  TIMx->SMCR &=  SMCR_SMS_Mask;
+}
+
+/**
+  * @brief  Configures the TIMx Internal Trigger as External Clock
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ITRSource: Trigger source.
+  *   This parameter can be one of the following values:
+  * @param  TIM_TS_ITR0: Internal Trigger 0
+  * @param  TIM_TS_ITR1: Internal Trigger 1
+  * @param  TIM_TS_ITR2: Internal Trigger 2
+  * @param  TIM_TS_ITR3: Internal Trigger 3
+  * @retval None
+  */
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource));
+  /* Select the Internal Trigger */
+  TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource);
+  /* Select the External clock mode1 */
+  TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+
+/**
+  * @brief  Configures the TIMx Trigger as External Clock
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_TIxExternalCLKSource: Trigger source.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector
+  *     @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1
+  *     @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2
+  * @param  TIM_ICPolarity: specifies the TIx Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPolarity_Rising
+  *     @arg TIM_ICPolarity_Falling
+  * @param  ICFilter : specifies the filter value.
+  *   This parameter must be a value between 0x0 and 0xF.
+  * @retval None
+  */
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource,
+                                uint16_t TIM_ICPolarity, uint16_t ICFilter)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_TIXCLK_SOURCE(TIM_TIxExternalCLKSource));
+  assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity));
+  assert_param(IS_TIM_IC_FILTER(ICFilter));
+  /* Configure the Timer Input Clock Source */
+  if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2)
+  {
+    TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+  }
+  else
+  {
+    TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+  }
+  /* Select the Trigger source */
+  TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource);
+  /* Select the External clock mode1 */
+  TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+
+/**
+  * @brief  Configures the External clock Mode1
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF.
+  *     @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2.
+  *     @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4.
+  *     @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8.
+  * @param  TIM_ExtTRGPolarity: The external Trigger Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active.
+  *     @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active.
+  * @param  ExtTRGFilter: External Trigger Filter.
+  *   This parameter must be a value between 0x00 and 0x0F
+  * @retval None
+  */
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity,
+                             uint16_t ExtTRGFilter)
+{
+  uint16_t tmpsmcr = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+  assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+  assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+  /* Configure the ETR Clock source */
+  TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+  
+  /* Get the TIMx SMCR register value */
+  tmpsmcr = TIMx->SMCR;
+  /* Reset the SMS Bits */
+  tmpsmcr &= SMCR_SMS_Mask;
+  /* Select the External clock mode1 */
+  tmpsmcr |= TIM_SlaveMode_External1;
+  /* Select the Trigger selection : ETRF */
+  tmpsmcr &= SMCR_TS_Mask;
+  tmpsmcr |= TIM_TS_ETRF;
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+}
+
+/**
+  * @brief  Configures the External clock Mode2
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF.
+  *     @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2.
+  *     @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4.
+  *     @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8.
+  * @param  TIM_ExtTRGPolarity: The external Trigger Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active.
+  *     @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active.
+  * @param  ExtTRGFilter: External Trigger Filter.
+  *   This parameter must be a value between 0x00 and 0x0F
+  * @retval None
+  */
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, 
+                             uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+  assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+  assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+  /* Configure the ETR Clock source */
+  TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+  /* Enable the External clock mode2 */
+  TIMx->SMCR |= SMCR_ECE_Set;
+}
+
+/**
+  * @brief  Configures the TIMx External Trigger (ETR).
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF.
+  *     @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2.
+  *     @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4.
+  *     @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8.
+  * @param  TIM_ExtTRGPolarity: The external Trigger Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active.
+  *     @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active.
+  * @param  ExtTRGFilter: External Trigger Filter.
+  *   This parameter must be a value between 0x00 and 0x0F
+  * @retval None
+  */
+void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity,
+                   uint16_t ExtTRGFilter)
+{
+  uint16_t tmpsmcr = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+  assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+  assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+  tmpsmcr = TIMx->SMCR;
+  /* Reset the ETR Bits */
+  tmpsmcr &= SMCR_ETR_Mask;
+  /* Set the Prescaler, the Filter value and the Polarity */
+  tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8)));
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+}
+
+/**
+  * @brief  Configures the TIMx Prescaler.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  Prescaler: specifies the Prescaler Register value
+  * @param  TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode
+  *   This parameter can be one of the following values:
+  *     @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event.
+  *     @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediatly.
+  * @retval None
+  */
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode));
+  /* Set the Prescaler value */
+  TIMx->PSC = Prescaler;
+  /* Set or reset the UG Bit */
+  TIMx->EGR = TIM_PSCReloadMode;
+}
+
+/**
+  * @brief  Specifies the TIMx Counter Mode to be used.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_CounterMode: specifies the Counter Mode to be used
+  *   This parameter can be one of the following values:
+  *     @arg TIM_CounterMode_Up: TIM Up Counting Mode
+  *     @arg TIM_CounterMode_Down: TIM Down Counting Mode
+  *     @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1
+  *     @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2
+  *     @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3
+  * @retval None
+  */
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode)
+{
+  uint16_t tmpcr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode));
+  tmpcr1 = TIMx->CR1;
+  /* Reset the CMS and DIR Bits */
+  tmpcr1 &= CR1_CounterMode_Mask;
+  /* Set the Counter Mode */
+  tmpcr1 |= TIM_CounterMode;
+  /* Write to TIMx CR1 register */
+  TIMx->CR1 = tmpcr1;
+}
+
+/**
+  * @brief  Selects the Input Trigger source
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_InputTriggerSource: The Input Trigger source.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_TS_ITR0: Internal Trigger 0
+  *     @arg TIM_TS_ITR1: Internal Trigger 1
+  *     @arg TIM_TS_ITR2: Internal Trigger 2
+  *     @arg TIM_TS_ITR3: Internal Trigger 3
+  *     @arg TIM_TS_TI1F_ED: TI1 Edge Detector
+  *     @arg TIM_TS_TI1FP1: Filtered Timer Input 1
+  *     @arg TIM_TS_TI2FP2: Filtered Timer Input 2
+  *     @arg TIM_TS_ETRF: External Trigger input
+  * @retval None
+  */
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource)
+{
+  uint16_t tmpsmcr = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource));
+  /* Get the TIMx SMCR register value */
+  tmpsmcr = TIMx->SMCR;
+  /* Reset the TS Bits */
+  tmpsmcr &= SMCR_TS_Mask;
+  /* Set the Input Trigger source */
+  tmpsmcr |= TIM_InputTriggerSource;
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+}
+
+/**
+  * @brief  Configures the TIMx Encoder Interface.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_EncoderMode: specifies the TIMx Encoder Mode.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level.
+  *     @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level.
+  *     @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending
+  *                                on the level of the other input.
+  * @param  TIM_IC1Polarity: specifies the IC1 Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_ICPolarity_Falling: IC Falling edge.
+  *     @arg TIM_ICPolarity_Rising: IC Rising edge.
+  * @param  TIM_IC2Polarity: specifies the IC2 Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_ICPolarity_Falling: IC Falling edge.
+  *     @arg TIM_ICPolarity_Rising: IC Rising edge.
+  * @retval None
+  */
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode,
+                                uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity)
+{
+  uint16_t tmpsmcr = 0;
+  uint16_t tmpccmr1 = 0;
+  uint16_t tmpccer = 0;
+    
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode));
+  assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity));
+  assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity));
+
+  /* Get the TIMx SMCR register value */
+  tmpsmcr = TIMx->SMCR;
+
+  /* Get the TIMx CCMR1 register value */
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+
+  /* Set the encoder Mode */
+  tmpsmcr &= SMCR_SMS_Mask;
+  tmpsmcr |= TIM_EncoderMode;
+
+  /* Select the Capture Compare 1 and the Capture Compare 2 as input */
+  tmpccmr1 &= CCMR_CC13S_Mask & CCMR_CC24S_Mask;
+  tmpccmr1 |= CCMR_TI13Direct_Set | CCMR_TI24Direct_Set;
+
+  /* Set the TI1 and the TI2 Polarities */
+  tmpccer &= CCER_CC1P_Reset & CCER_CC2P_Reset;
+  tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4));
+
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmr1;
+
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Forces the TIMx output 1 waveform to active or inactive level.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ForcedAction_Active: Force active level on OC1REF
+  *     @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF.
+  * @retval None
+  */
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC1M Bits */
+  tmpccmr1 &= CCMR_OC13M_Mask;
+  /* Configure The Forced output Mode */
+  tmpccmr1 |= TIM_ForcedAction;
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Forces the TIMx output 2 waveform to active or inactive level.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ForcedAction_Active: Force active level on OC2REF
+  *     @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF.
+  * @retval None
+  */
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC2M Bits */
+  tmpccmr1 &= CCMR_OC24M_Mask;
+  /* Configure The Forced output Mode */
+  tmpccmr1 |= (uint16_t)(TIM_ForcedAction << 8);
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Forces the TIMx output 3 waveform to active or inactive level.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ForcedAction_Active: Force active level on OC3REF
+  *     @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF.
+  * @retval None
+  */
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC1M Bits */
+  tmpccmr2 &= CCMR_OC13M_Mask;
+  /* Configure The Forced output Mode */
+  tmpccmr2 |= TIM_ForcedAction;
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Forces the TIMx output 4 waveform to active or inactive level.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ForcedAction_Active: Force active level on OC4REF
+  *     @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF.
+  * @retval None
+  */
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC2M Bits */
+  tmpccmr2 &= CCMR_OC24M_Mask;
+  /* Configure The Forced output Mode */
+  tmpccmr2 |= (uint16_t)(TIM_ForcedAction << 8);
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Enables or disables TIMx peripheral Preload register on ARR.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  NewState: new state of the TIMx peripheral Preload register
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the ARR Preload Bit */
+    TIMx->CR1 |= CR1_ARPE_Set;
+  }
+  else
+  {
+    /* Reset the ARR Preload Bit */
+    TIMx->CR1 &= CR1_ARPE_Reset;
+  }
+}
+
+/**
+  * @brief  Selects the TIM peripheral Commutation event.
+  * @param  TIMx: where x can be  1 or 8 to select the TIMx peripheral
+  * @param  NewState: new state of the Commutation event.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the COM Bit */
+    TIMx->CR2 |= CR2_CCUS_Set;
+  }
+  else
+  {
+    /* Reset the COM Bit */
+    TIMx->CR2 &= CR2_CCUS_Reset;
+  }
+}
+
+/**
+  * @brief  Selects the TIMx peripheral Capture Compare DMA source.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  NewState: new state of the Capture Compare DMA source
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the CCDS Bit */
+    TIMx->CR2 |= CR2_CCDS_Set;
+  }
+  else
+  {
+    /* Reset the CCDS Bit */
+    TIMx->CR2 &= CR2_CCDS_Reset;
+  }
+}
+
+/**
+  * @brief  Sets or Resets the TIM peripheral Capture Compare Preload Control bit.
+  * @param  TIMx: where x can be  1 or 8 to select the TIMx peripheral
+  * @param  NewState: new state of the Capture Compare Preload Control bit
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the CCPC Bit */
+    TIMx->CR2 |= CR2_CCPC_Set;
+  }
+  else
+  {
+    /* Reset the CCPC Bit */
+    TIMx->CR2 &= CR2_CCPC_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR1.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCPreload_Enable
+  *     @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC1PE Bit */
+  tmpccmr1 &= CCMR_OC13PE_Reset;
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr1 |= TIM_OCPreload;
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR2.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCPreload_Enable
+  *     @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC2PE Bit */
+  tmpccmr1 &= CCMR_OC24PE_Reset;
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr1 |= (uint16_t)(TIM_OCPreload << 8);
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR3.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCPreload_Enable
+  *     @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC3PE Bit */
+  tmpccmr2 &= CCMR_OC13PE_Reset;
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr2 |= TIM_OCPreload;
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR4.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCPreload_Enable
+  *     @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC4PE Bit */
+  tmpccmr2 &= CCMR_OC24PE_Reset;
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr2 |= (uint16_t)(TIM_OCPreload << 8);
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 1 Fast feature.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *     @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+  /* Get the TIMx CCMR1 register value */
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC1FE Bit */
+  tmpccmr1 &= CCMR_OC13FE_Reset;
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr1 |= TIM_OCFast;
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 2 Fast feature.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *     @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+  /* Get the TIMx CCMR1 register value */
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC2FE Bit */
+  tmpccmr1 &= CCMR_OC24FE_Reset;
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr1 |= (uint16_t)(TIM_OCFast << 8);
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 3 Fast feature.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *     @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+  /* Get the TIMx CCMR2 register value */
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC3FE Bit */
+  tmpccmr2 &= CCMR_OC13FE_Reset;
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr2 |= TIM_OCFast;
+  /* Write to TIMx CCMR2 */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 4 Fast feature.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *     @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+  /* Get the TIMx CCMR2 register value */
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC4FE Bit */
+  tmpccmr2 &= CCMR_OC24FE_Reset;
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr2 |= (uint16_t)(TIM_OCFast << 8);
+  /* Write to TIMx CCMR2 */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF1 signal on an external event
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCClear_Enable: TIM Output clear enable
+  *     @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC1CE Bit */
+  tmpccmr1 &= CCMR_OC13CE_Reset;
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr1 |= TIM_OCClear;
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF2 signal on an external event
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCClear_Enable: TIM Output clear enable
+  *     @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr1 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+  tmpccmr1 = TIMx->CCMR1;
+  /* Reset the OC2CE Bit */
+  tmpccmr1 &= CCMR_OC24CE_Reset;
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr1 |= (uint16_t)(TIM_OCClear << 8);
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF3 signal on an external event
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCClear_Enable: TIM Output clear enable
+  *     @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC3CE Bit */
+  tmpccmr2 &= CCMR_OC13CE_Reset;
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr2 |= TIM_OCClear;
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF4 signal on an external event
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OCClear_Enable: TIM Output clear enable
+  *     @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr2 = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+  tmpccmr2 = TIMx->CCMR2;
+  /* Reset the OC4CE Bit */
+  tmpccmr2 &= CCMR_OC24CE_Reset;
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr2 |= (uint16_t)(TIM_OCClear << 8);
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Configures the TIMx channel 1 polarity.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPolarity: specifies the OC1 Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_OCPolarity_High: Output Compare active high
+  *     @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+  tmpccer = TIMx->CCER;
+  /* Set or Reset the CC1P Bit */
+  tmpccer &= CCER_CC1P_Reset;
+  tmpccer |= TIM_OCPolarity;
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx Channel 1N polarity.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_OCNPolarity: specifies the OC1N Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_OCNPolarity_High: Output Compare active high
+  *     @arg TIM_OCNPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity)
+{
+  uint16_t tmpccer = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+   
+  tmpccer = TIMx->CCER;
+  /* Set or Reset the CC1NP Bit */
+  tmpccer &= CCER_CC1NP_Reset;
+  tmpccer |= TIM_OCNPolarity;
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx channel 2 polarity.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPolarity: specifies the OC2 Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_OCPolarity_High: Output Compare active high
+  *     @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+  tmpccer = TIMx->CCER;
+  /* Set or Reset the CC2P Bit */
+  tmpccer &= CCER_CC2P_Reset;
+  tmpccer |= (uint16_t)(TIM_OCPolarity << 4);
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx Channel 2N polarity.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_OCNPolarity: specifies the OC2N Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_OCNPolarity_High: Output Compare active high
+  *     @arg TIM_OCNPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity)
+{
+  uint16_t tmpccer = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+  
+  tmpccer = TIMx->CCER;
+  /* Set or Reset the CC2NP Bit */
+  tmpccer &= CCER_CC2NP_Reset;
+  tmpccer |= (uint16_t)(TIM_OCNPolarity << 4);
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx channel 3 polarity.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPolarity: specifies the OC3 Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_OCPolarity_High: Output Compare active high
+  *     @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+  tmpccer = TIMx->CCER;
+  /* Set or Reset the CC3P Bit */
+  tmpccer &= CCER_CC3P_Reset;
+  tmpccer |= (uint16_t)(TIM_OCPolarity << 8);
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx Channel 3N polarity.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_OCNPolarity: specifies the OC3N Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_OCNPolarity_High: Output Compare active high
+  *     @arg TIM_OCNPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity)
+{
+  uint16_t tmpccer = 0;
+ 
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+    
+  tmpccer = TIMx->CCER;
+  /* Set or Reset the CC3NP Bit */
+  tmpccer &= CCER_CC3NP_Reset;
+  tmpccer |= (uint16_t)(TIM_OCNPolarity << 8);
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx channel 4 polarity.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPolarity: specifies the OC4 Polarity
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_OCPolarity_High: Output Compare active high
+  *     @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+  tmpccer = TIMx->CCER;
+  /* Set or Reset the CC4P Bit */
+  tmpccer &= CCER_CC4P_Reset;
+  tmpccer |= (uint16_t)(TIM_OCPolarity << 12);
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Enables or disables the TIM Capture Compare Channel x.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_Channel: specifies the TIM Channel
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_Channel_1: TIM Channel 1
+  *     @arg TIM_Channel_2: TIM Channel 2
+  *     @arg TIM_Channel_3: TIM Channel 3
+  *     @arg TIM_Channel_4: TIM Channel 4
+  * @param  TIM_CCx: specifies the TIM Channel CCxE bit new state.
+  *   This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. 
+  * @retval None
+  */
+void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx)
+{
+  uint16_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_CHANNEL(TIM_Channel));
+  assert_param(IS_TIM_CCX(TIM_CCx));
+
+  tmp = CCER_CCE_Set << TIM_Channel;
+
+  /* Reset the CCxE Bit */
+  TIMx->CCER &= (uint16_t)~ tmp;
+
+  /* Set or reset the CCxE Bit */ 
+  TIMx->CCER |=  (uint16_t)(TIM_CCx << TIM_Channel);
+}
+
+/**
+  * @brief  Enables or disables the TIM Capture Compare Channel xN.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_Channel: specifies the TIM Channel
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_Channel_1: TIM Channel 1
+  *     @arg TIM_Channel_2: TIM Channel 2
+  *     @arg TIM_Channel_3: TIM Channel 3
+  * @param  TIM_CCxN: specifies the TIM Channel CCxNE bit new state.
+  *   This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. 
+  * @retval None
+  */
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN)
+{
+  uint16_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_18_PERIPH(TIMx));
+  assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel));
+  assert_param(IS_TIM_CCXN(TIM_CCxN));
+
+  tmp = CCER_CCNE_Set << TIM_Channel;
+
+  /* Reset the CCxNE Bit */
+  TIMx->CCER &= (uint16_t) ~tmp;
+
+  /* Set or reset the CCxNE Bit */ 
+  TIMx->CCER |=  (uint16_t)(TIM_CCxN << TIM_Channel);
+}
+
+/**
+  * @brief  Selects the TIM Ouput Compare Mode.
+  * @note   This function disables the selected channel before changing the Ouput
+  *         Compare Mode.
+  *         User has to enable this channel using TIM_CCxCmd and TIM_CCxNCmd functions.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_Channel: specifies the TIM Channel
+  *   This parmeter can be one of the following values:
+  *     @arg TIM_Channel_1: TIM Channel 1
+  *     @arg TIM_Channel_2: TIM Channel 2
+  *     @arg TIM_Channel_3: TIM Channel 3
+  *     @arg TIM_Channel_4: TIM Channel 4
+  * @param  TIM_OCMode: specifies the TIM Output Compare Mode.
+  *   This paramter can be one of the following values:
+  *     @arg TIM_OCMode_Timing
+  *     @arg TIM_OCMode_Active
+  *     @arg TIM_OCMode_Toggle
+  *     @arg TIM_OCMode_PWM1
+  *     @arg TIM_OCMode_PWM2
+  *     @arg TIM_ForcedAction_Active
+  *     @arg TIM_ForcedAction_InActive
+  * @retval None
+  */
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
+{
+  uint32_t tmp = 0;
+  uint16_t tmp1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_CHANNEL(TIM_Channel));
+  assert_param(IS_TIM_OCM(TIM_OCMode));
+
+  tmp = (uint32_t) TIMx;
+  tmp += CCMR_Offset;
+
+  tmp1 = CCER_CCE_Set << (uint16_t)TIM_Channel;
+
+  /* Disable the Channel: Reset the CCxE Bit */
+  TIMx->CCER &= (uint16_t) ~tmp1;
+
+  if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
+  {
+    tmp += (TIM_Channel>>1);
+
+    /* Reset the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp &= CCMR_OC13M_Mask;
+   
+    /* Configure the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp |= TIM_OCMode;
+  }
+  else
+  {
+    tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1;
+
+    /* Reset the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp &= CCMR_OC24M_Mask;
+    
+    /* Configure the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8);
+  }
+}
+
+/**
+  * @brief  Enables or Disables the TIMx Update event.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  NewState: new state of the TIMx UDIS bit
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the Update Disable Bit */
+    TIMx->CR1 |= CR1_UDIS_Set;
+  }
+  else
+  {
+    /* Reset the Update Disable Bit */
+    TIMx->CR1 &= CR1_UDIS_Reset;
+  }
+}
+
+/**
+  * @brief  Configures the TIMx Update Request Interrupt source.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_UpdateSource: specifies the Update source.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_UpdateSource_Regular: Source of update is the counter overflow/underflow
+                                       or the setting of UG bit, or an update generation
+                                       through the slave mode controller.
+  *     @arg TIM_UpdateSource_Global: Source of update is counter overflow/underflow.
+  * @retval None
+  */
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource));
+  if (TIM_UpdateSource != TIM_UpdateSource_Global)
+  {
+    /* Set the URS Bit */
+    TIMx->CR1 |= CR1_URS_Set;
+  }
+  else
+  {
+    /* Reset the URS Bit */
+    TIMx->CR1 &= CR1_URS_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the TIMx’s Hall sensor interface.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  NewState: new state of the TIMx Hall sensor interface.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the TI1S Bit */
+    TIMx->CR2 |= CR2_TI1S_Set;
+  }
+  else
+  {
+    /* Reset the TI1S Bit */
+    TIMx->CR2 &= CR2_TI1S_Reset;
+  }
+}
+
+/**
+  * @brief  Selects the TIMx’s One Pulse Mode.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_OPMode: specifies the OPM Mode to be used.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_OPMode_Single
+  *     @arg TIM_OPMode_Repetitive
+  * @retval None
+  */
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_OPM_MODE(TIM_OPMode));
+  /* Reset the OPM Bit */
+  TIMx->CR1 &= CR1_OPM_Reset;
+  /* Configure the OPM Mode */
+  TIMx->CR1 |= TIM_OPMode;
+}
+
+/**
+  * @brief  Selects the TIMx Trigger Output Mode.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_TRGOSource: specifies the Trigger Output source.
+  *   This paramter can be one of the following values:
+  *
+  *  - For all TIMx
+  *     @arg TIM_TRGOSource_Reset:  The UG bit in the TIM_EGR register is used as the trigger output (TRGO).
+  *     @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output (TRGO).
+  *     @arg TIM_TRGOSource_Update: The update event is selected as the trigger output (TRGO).
+  *
+  *  - For all TIMx except TIM6 and TIM7
+  *     @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag
+  *                              is to be set, as soon as a capture or compare match occurs (TRGO).
+  *     @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output (TRGO).
+  *     @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output (TRGO).
+  *     @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output (TRGO).
+  *     @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output (TRGO).
+  *
+  * @retval None
+  */
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource));
+  /* Reset the MMS Bits */
+  TIMx->CR2 &= CR2_MMS_Mask;
+  /* Select the TRGO source */
+  TIMx->CR2 |=  TIM_TRGOSource;
+}
+
+/**
+  * @brief  Selects the TIMx Slave Mode.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_SlaveMode: specifies the Timer Slave Mode.
+  *   This paramter can be one of the following values:
+  *     @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal (TRGI) re-initializes
+  *                               the counter and triggers an update of the registers.
+  *     @arg TIM_SlaveMode_Gated:     The counter clock is enabled when the trigger signal (TRGI) is high.
+  *     @arg TIM_SlaveMode_Trigger:   The counter starts at a rising edge of the trigger TRGI.
+  *     @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter.
+  * @retval None
+  */
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode));
+  /* Reset the SMS Bits */
+  TIMx->SMCR &= SMCR_SMS_Mask;
+  /* Select the Slave Mode */
+  TIMx->SMCR |= TIM_SlaveMode;
+}
+
+/**
+  * @brief  Sets or Resets the TIMx Master/Slave Mode.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_MasterSlaveMode: specifies the Timer Master Slave Mode.
+  *   This paramter can be one of the following values:
+  *     @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer
+  *                                      and its slaves (through TRGO).
+  *     @arg TIM_MasterSlaveMode_Disable: No action
+  * @retval None
+  */
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode));
+  /* Reset the MSM Bit */
+  TIMx->SMCR &= SMCR_MSM_Reset;
+  
+  /* Set or Reset the MSM Bit */
+  TIMx->SMCR |= TIM_MasterSlaveMode;
+}
+
+/**
+  * @brief  Sets the TIMx Counter Register value
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  Counter: specifies the Counter register new value.
+  * @retval None
+  */
+void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  /* Set the Counter Register value */
+  TIMx->CNT = Counter;
+}
+
+/**
+  * @brief  Sets the TIMx Autoreload Register value
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  Autoreload: specifies the Autoreload register new value.
+  * @retval None
+  */
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  /* Set the Autoreload Register value */
+  TIMx->ARR = Autoreload;
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare1 Register value
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  Compare1: specifies the Capture Compare1 register new value.
+  * @retval None
+  */
+void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Set the Capture Compare1 Register value */
+  TIMx->CCR1 = Compare1;
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare2 Register value
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  Compare2: specifies the Capture Compare2 register new value.
+  * @retval None
+  */
+void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Set the Capture Compare2 Register value */
+  TIMx->CCR2 = Compare2;
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare3 Register value
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  Compare3: specifies the Capture Compare3 register new value.
+  * @retval None
+  */
+void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Set the Capture Compare3 Register value */
+  TIMx->CCR3 = Compare3;
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare4 Register value
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  Compare4: specifies the Capture Compare4 register new value.
+  * @retval None
+  */
+void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Set the Capture Compare4 Register value */
+  TIMx->CCR4 = Compare4;
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 1 prescaler.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture1 prescaler new value.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPSC_DIV1: no prescaler
+  *     @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *     @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *     @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+  /* Reset the IC1PSC Bits */
+  TIMx->CCMR1 &= CCMR_IC13PSC_Mask;
+  /* Set the IC1PSC value */
+  TIMx->CCMR1 |= TIM_ICPSC;
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 2 prescaler.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture2 prescaler new value.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPSC_DIV1: no prescaler
+  *     @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *     @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *     @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+  /* Reset the IC2PSC Bits */
+  TIMx->CCMR1 &= CCMR_IC24PSC_Mask;
+  /* Set the IC2PSC value */
+  TIMx->CCMR1 |= (uint16_t)(TIM_ICPSC << 8);
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 3 prescaler.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture3 prescaler new value.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPSC_DIV1: no prescaler
+  *     @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *     @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *     @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+  /* Reset the IC3PSC Bits */
+  TIMx->CCMR2 &= CCMR_IC13PSC_Mask;
+  /* Set the IC3PSC value */
+  TIMx->CCMR2 |= TIM_ICPSC;
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 4 prescaler.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture4 prescaler new value.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPSC_DIV1: no prescaler
+  *     @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *     @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *     @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{  
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+  /* Reset the IC4PSC Bits */
+  TIMx->CCMR2 &= CCMR_IC24PSC_Mask;
+  /* Set the IC4PSC value */
+  TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8);
+}
+
+/**
+  * @brief  Sets the TIMx Clock Division value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_CKD: specifies the clock division value.
+  *   This parameter can be one of the following value:
+  *     @arg TIM_CKD_DIV1: TDTS = Tck_tim
+  *     @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim
+  *     @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim
+  * @retval None
+  */
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  assert_param(IS_TIM_CKD_DIV(TIM_CKD));
+  /* Reset the CKD Bits */
+  TIMx->CR1 &= CR1_CKD_Mask;
+  /* Set the CKD value */
+  TIMx->CR1 |= TIM_CKD;
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 1 value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @retval Capture Compare 1 Register value.
+  */
+uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Get the Capture 1 Register value */
+  return TIMx->CCR1;
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 2 value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @retval Capture Compare 2 Register value.
+  */
+uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Get the Capture 2 Register value */
+  return TIMx->CCR2;
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 3 value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @retval Capture Compare 3 Register value.
+  */
+uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx)); 
+  /* Get the Capture 3 Register value */
+  return TIMx->CCR3;
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 4 value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @retval Capture Compare 4 Register value.
+  */
+uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_123458_PERIPH(TIMx));
+  /* Get the Capture 4 Register value */
+  return TIMx->CCR4;
+}
+
+/**
+  * @brief  Gets the TIMx Counter value.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @retval Counter Register value.
+  */
+uint16_t TIM_GetCounter(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  /* Get the Counter Register value */
+  return TIMx->CNT;
+}
+
+/**
+  * @brief  Gets the TIMx Prescaler value.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @retval Prescaler Register value.
+  */
+uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  /* Get the Prescaler Register value */
+  return TIMx->PSC;
+}
+
+/**
+  * @brief  Checks whether the specified TIM flag is set or not.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_FLAG_Update: TIM update Flag
+  *     @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+  *     @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+  *     @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+  *     @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+  *     @arg TIM_FLAG_COM: TIM Commutation Flag
+  *     @arg TIM_FLAG_Trigger: TIM Trigger Flag
+  *     @arg TIM_FLAG_Break: TIM Break Flag
+  *     @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag
+  *     @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag
+  *     @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag
+  *     @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag
+  * @note
+  *   - TIM6 and TIM7 can have only one update flag. 
+  *   - TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8.    
+  * @retval The new state of TIM_FLAG (SET or RESET).
+  */
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG)
+{ 
+  ITStatus bitstatus = RESET;  
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_GET_FLAG(TIM_FLAG));
+  
+  if ((TIMx->SR & TIM_FLAG) != (uint16_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the TIMx's pending flags.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_FLAG: specifies the flag bit to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg TIM_FLAG_Update: TIM update Flag
+  *     @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+  *     @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+  *     @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+  *     @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+  *     @arg TIM_FLAG_COM: TIM Commutation Flag
+  *     @arg TIM_FLAG_Trigger: TIM Trigger Flag
+  *     @arg TIM_FLAG_Break: TIM Break Flag
+  *     @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag
+  *     @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag
+  *     @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag
+  *     @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag
+  * @note
+  *   - TIM6 and TIM7 can have only one update flag. 
+  *   - TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8.  
+  * @retval None
+  */
+void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG)
+{  
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_CLEAR_FLAG(TIM_FLAG));
+   
+  /* Clear the flags */
+  TIMx->SR = (uint16_t)~TIM_FLAG;
+}
+
+/**
+  * @brief  Checks whether the TIM interrupt has occurred or not.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_IT: specifies the TIM interrupt source to check.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_IT_Update: TIM update Interrupt source
+  *     @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+  *     @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+  *     @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+  *     @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+  *     @arg TIM_IT_COM: TIM Commutation Interrupt source
+  *     @arg TIM_IT_Trigger: TIM Trigger Interrupt source
+  *     @arg TIM_IT_Break: TIM Break Interrupt source
+  * @note
+  *   - TIM6 and TIM7 can generate only an update interrupt.
+  *   - TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8.  
+  * @retval The new state of the TIM_IT(SET or RESET).
+  */
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT)
+{
+  ITStatus bitstatus = RESET;  
+  uint16_t itstatus = 0x0, itenable = 0x0;
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_GET_IT(TIM_IT));
+   
+  itstatus = TIMx->SR & TIM_IT;
+  
+  itenable = TIMx->DIER & TIM_IT;
+  if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the TIMx's interrupt pending bits.
+  * @param  TIMx: where x can be 1 to 8 to select the TIM peripheral.
+  * @param  TIM_IT: specifies the pending bit to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg TIM_IT_Update: TIM1 update Interrupt source
+  *     @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+  *     @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+  *     @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+  *     @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+  *     @arg TIM_IT_COM: TIM Commutation Interrupt source
+  *     @arg TIM_IT_Trigger: TIM Trigger Interrupt source
+  *     @arg TIM_IT_Break: TIM Break Interrupt source
+  * @note
+  *   - TIM6 and TIM7 can generate only an update interrupt.
+  *   - TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8.    
+  * @retval None
+  */
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_IT(TIM_IT));
+  /* Clear the IT pending Bit */
+  TIMx->SR = (uint16_t)~TIM_IT;
+}
+
+/**
+  * @brief  Configure the TI1 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPolarity_Rising
+  *     @arg TIM_ICPolarity_Falling
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1.
+  *     @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2.
+  *     @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *   This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr1 = 0, tmpccer = 0;
+  /* Disable the Channel 1: Reset the CC1E Bit */
+  TIMx->CCER &= CCER_CC1E_Reset;
+  tmpccmr1 = TIMx->CCMR1;
+  tmpccer = TIMx->CCER;
+  /* Select the Input and set the filter */
+  tmpccmr1 &= CCMR_CC13S_Mask & CCMR_IC13F_Mask;
+  tmpccmr1 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4));
+  /* Select the Polarity and set the CC1E Bit */
+  tmpccer &= CCER_CC1P_Reset;
+  tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)CCER_CC1E_Set);
+  /* Write to TIMx CCMR1 and CCER registers */
+  TIMx->CCMR1 = tmpccmr1;
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configure the TI2 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPolarity_Rising
+  *     @arg TIM_ICPolarity_Falling
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2.
+  *     @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1.
+  *     @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *   This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr1 = 0, tmpccer = 0, tmp = 0;
+  /* Disable the Channel 2: Reset the CC2E Bit */
+  TIMx->CCER &= CCER_CC2E_Reset;
+  tmpccmr1 = TIMx->CCMR1;
+  tmpccer = TIMx->CCER;
+  tmp = (uint16_t)(TIM_ICPolarity << 4);
+  /* Select the Input and set the filter */
+  tmpccmr1 &= CCMR_CC24S_Mask & CCMR_IC24F_Mask;
+  tmpccmr1 |= (uint16_t)(TIM_ICFilter << 12);
+  tmpccmr1 |= (uint16_t)(TIM_ICSelection << 8);
+  /* Select the Polarity and set the CC2E Bit */
+  tmpccer &= CCER_CC2P_Reset;
+  tmpccer |=  (uint16_t)(tmp | (uint16_t)CCER_CC2E_Set);
+  /* Write to TIMx CCMR1 and CCER registers */
+  TIMx->CCMR1 = tmpccmr1 ;
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configure the TI3 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPolarity_Rising
+  *     @arg TIM_ICPolarity_Falling
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3.
+  *     @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4.
+  *     @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *   This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+  /* Disable the Channel 3: Reset the CC3E Bit */
+  TIMx->CCER &= CCER_CC3E_Reset;
+  tmpccmr2 = TIMx->CCMR2;
+  tmpccer = TIMx->CCER;
+  tmp = (uint16_t)(TIM_ICPolarity << 8);
+  /* Select the Input and set the filter */
+  tmpccmr2 &= CCMR_CC13S_Mask & CCMR_IC13F_Mask;
+  tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4));
+  /* Select the Polarity and set the CC3E Bit */
+  tmpccer &= CCER_CC3P_Reset;
+  tmpccer |= (uint16_t)(tmp | (uint16_t)CCER_CC3E_Set);
+  /* Write to TIMx CCMR2 and CCER registers */
+  TIMx->CCMR2 = tmpccmr2;
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configure the TI1 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICPolarity_Rising
+  *     @arg TIM_ICPolarity_Falling
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *   This parameter can be one of the following values:
+  *     @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4.
+  *     @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3.
+  *     @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *   This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+
+  /* Disable the Channel 4: Reset the CC4E Bit */
+  TIMx->CCER &= CCER_CC4E_Reset;
+  tmpccmr2 = TIMx->CCMR2;
+  tmpccer = TIMx->CCER;
+  tmp = (uint16_t)(TIM_ICPolarity << 12);
+
+  /* Select the Input and set the filter */
+  tmpccmr2 &= CCMR_CC24S_Mask & CCMR_IC24F_Mask;
+  tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8);
+  tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12);
+
+  /* Select the Polarity and set the CC4E Bit */
+  tmpccer &= CCER_CC4P_Reset;
+  tmpccer |= (uint16_t)(tmp | (uint16_t)CCER_CC4E_Set);
+  /* Write to TIMx CCMR2 and CCER registers */
+  TIMx->CCMR2 = tmpccmr2;
+  TIMx->CCER = tmpccer ;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c
new file mode 100644
index 0000000000000000000000000000000000000000..0e642d4b3f44e7b1597ef763238b34539051efe5
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c
@@ -0,0 +1,967 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_usart.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the USART firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_usart.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup USART 
+  * @brief USART driver modules
+  * @{
+  */
+
+/** @defgroup USART_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Private_Defines
+  * @{
+  */
+
+#define CR1_UE_Set                ((uint16_t)0x2000)  /*!< USART Enable Mask */
+#define CR1_UE_Reset              ((uint16_t)0xDFFF)  /*!< USART Disable Mask */
+
+#define CR1_WAKE_Mask             ((uint16_t)0xF7FF)  /*!< USART WakeUp Method Mask */
+
+#define CR1_RWU_Set               ((uint16_t)0x0002)  /*!< USART mute mode Enable Mask */
+#define CR1_RWU_Reset             ((uint16_t)0xFFFD)  /*!< USART mute mode Enable Mask */
+#define CR1_SBK_Set               ((uint16_t)0x0001)  /*!< USART Break Character send Mask */
+#define CR1_CLEAR_Mask            ((uint16_t)0xE9F3)  /*!< USART CR1 Mask */
+#define CR2_Address_Mask          ((uint16_t)0xFFF0)  /*!< USART address Mask */
+
+#define CR2_LINEN_Set              ((uint16_t)0x4000)  /*!< USART LIN Enable Mask */
+#define CR2_LINEN_Reset            ((uint16_t)0xBFFF)  /*!< USART LIN Disable Mask */
+
+#define CR2_LBDL_Mask             ((uint16_t)0xFFDF)  /*!< USART LIN Break detection Mask */
+#define CR2_STOP_CLEAR_Mask       ((uint16_t)0xCFFF)  /*!< USART CR2 STOP Bits Mask */
+#define CR2_CLOCK_CLEAR_Mask      ((uint16_t)0xF0FF)  /*!< USART CR2 Clock Mask */
+
+#define CR3_SCEN_Set              ((uint16_t)0x0020)  /*!< USART SC Enable Mask */
+#define CR3_SCEN_Reset            ((uint16_t)0xFFDF)  /*!< USART SC Disable Mask */
+
+#define CR3_NACK_Set              ((uint16_t)0x0010)  /*!< USART SC NACK Enable Mask */
+#define CR3_NACK_Reset            ((uint16_t)0xFFEF)  /*!< USART SC NACK Disable Mask */
+
+#define CR3_HDSEL_Set             ((uint16_t)0x0008)  /*!< USART Half-Duplex Enable Mask */
+#define CR3_HDSEL_Reset           ((uint16_t)0xFFF7)  /*!< USART Half-Duplex Disable Mask */
+
+#define CR3_IRLP_Mask             ((uint16_t)0xFFFB)  /*!< USART IrDA LowPower mode Mask */
+#define CR3_CLEAR_Mask            ((uint16_t)0xFCFF)  /*!< USART CR3 Mask */
+
+#define CR3_IREN_Set              ((uint16_t)0x0002)  /*!< USART IrDA Enable Mask */
+#define CR3_IREN_Reset            ((uint16_t)0xFFFD)  /*!< USART IrDA Disable Mask */
+#define GTPR_LSB_Mask             ((uint16_t)0x00FF)  /*!< Guard Time Register LSB Mask */
+#define GTPR_MSB_Mask             ((uint16_t)0xFF00)  /*!< Guard Time Register MSB Mask */
+#define IT_Mask                   ((uint16_t)0x001F)  /*!< USART Interrupt Mask */
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the USARTx peripheral registers to their default reset values.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values: USART1, USART2, USART3, UART4 or UART5.
+  * @retval None
+  */
+void USART_DeInit(USART_TypeDef* USARTx)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+  if (USARTx == USART1)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE);
+  }
+  else if (USARTx == USART2)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE);
+  }
+  else if (USARTx == USART3)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE);
+  }    
+  else if (USARTx == UART4)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE);
+  }    
+  else
+  {
+    if (USARTx == UART5)
+    { 
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE);
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE);
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the USARTx peripheral according to the specified
+  *   parameters in the USART_InitStruct .
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_InitStruct: pointer to a USART_InitTypeDef structure
+  *   that contains the configuration information for the specified USART peripheral.
+  * @retval None
+  */
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct)
+{
+  uint32_t tmpreg = 0x00, apbclock = 0x00;
+  uint32_t integerdivider = 0x00;
+  uint32_t fractionaldivider = 0x00;
+  uint32_t usartxbase = 0;
+  RCC_ClocksTypeDef RCC_ClocksStatus;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate));  
+  assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength));
+  assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits));
+  assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity));
+  assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode));
+  assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl));
+  /* The hardware flow control is available only for USART1, USART2 and USART3 */
+  if (USART_InitStruct->USART_HardwareFlowControl != USART_HardwareFlowControl_None)
+  {
+    assert_param(IS_USART_123_PERIPH(USARTx));
+  }
+
+  usartxbase = (uint32_t)USARTx;
+
+/*---------------------------- USART CR2 Configuration -----------------------*/
+  tmpreg = USARTx->CR2;
+  /* Clear STOP[13:12] bits */
+  tmpreg &= CR2_STOP_CLEAR_Mask;
+  /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/
+  /* Set STOP[13:12] bits according to USART_StopBits value */
+  tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits;
+  
+  /* Write to USART CR2 */
+  USARTx->CR2 = (uint16_t)tmpreg;
+
+/*---------------------------- USART CR1 Configuration -----------------------*/
+  tmpreg = USARTx->CR1;
+  /* Clear M, PCE, PS, TE and RE bits */
+  tmpreg &= CR1_CLEAR_Mask;
+  /* Configure the USART Word Length, Parity and mode ----------------------- */
+  /* Set the M bits according to USART_WordLength value */
+  /* Set PCE and PS bits according to USART_Parity value */
+  /* Set TE and RE bits according to USART_Mode value */
+  tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity |
+            USART_InitStruct->USART_Mode;
+  /* Write to USART CR1 */
+  USARTx->CR1 = (uint16_t)tmpreg;
+
+/*---------------------------- USART CR3 Configuration -----------------------*/  
+  tmpreg = USARTx->CR3;
+  /* Clear CTSE and RTSE bits */
+  tmpreg &= CR3_CLEAR_Mask;
+  /* Configure the USART HFC -------------------------------------------------*/
+  /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */
+  tmpreg |= USART_InitStruct->USART_HardwareFlowControl;
+  /* Write to USART CR3 */
+  USARTx->CR3 = (uint16_t)tmpreg;
+
+/*---------------------------- USART BRR Configuration -----------------------*/
+  /* Configure the USART Baud Rate -------------------------------------------*/
+  RCC_GetClocksFreq(&RCC_ClocksStatus);
+  if (usartxbase == USART1_BASE)
+  {
+    apbclock = RCC_ClocksStatus.PCLK2_Frequency;
+  }
+  else
+  {
+    apbclock = RCC_ClocksStatus.PCLK1_Frequency;
+  }
+  /* Determine the integer part */
+  integerdivider = ((0x19 * apbclock) / (0x04 * (USART_InitStruct->USART_BaudRate)));
+  tmpreg = (integerdivider / 0x64) << 0x04;
+  /* Determine the fractional part */
+  fractionaldivider = integerdivider - (0x64 * (tmpreg >> 0x04));
+  tmpreg |= ((((fractionaldivider * 0x10) + 0x32) / 0x64)) & ((uint8_t)0x0F);
+  /* Write to USART BRR */
+  USARTx->BRR = (uint16_t)tmpreg;
+}
+
+/**
+  * @brief  Fills each USART_InitStruct member with its default value.
+  * @param  USART_InitStruct: pointer to a USART_InitTypeDef structure
+  *   which will be initialized.
+  * @retval None
+  */
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct)
+{
+  /* USART_InitStruct members default value */
+  USART_InitStruct->USART_BaudRate = 9600;
+  USART_InitStruct->USART_WordLength = USART_WordLength_8b;
+  USART_InitStruct->USART_StopBits = USART_StopBits_1;
+  USART_InitStruct->USART_Parity = USART_Parity_No ;
+  USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+  USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None;  
+}
+
+/**
+  * @brief  Initializes the USARTx peripheral Clock according to the 
+  *   specified parameters in the USART_ClockInitStruct .
+  * @param  USARTx: where x can be 1, 2, 3 to select the USART peripheral.
+  * @param  USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef
+  *   structure that contains the configuration information for the specified 
+  *   USART peripheral.  
+  * @note The Smart Card mode is not available for UART4 and UART5.
+  * @retval None
+  */
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+  uint32_t tmpreg = 0x00;
+  /* Check the parameters */
+  assert_param(IS_USART_123_PERIPH(USARTx));
+  assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock));
+  assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL));
+  assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA));
+  assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit));
+  
+/*---------------------------- USART CR2 Configuration -----------------------*/
+  tmpreg = USARTx->CR2;
+  /* Clear CLKEN, CPOL, CPHA and LBCL bits */
+  tmpreg &= CR2_CLOCK_CLEAR_Mask;
+  /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/
+  /* Set CLKEN bit according to USART_Clock value */
+  /* Set CPOL bit according to USART_CPOL value */
+  /* Set CPHA bit according to USART_CPHA value */
+  /* Set LBCL bit according to USART_LastBit value */
+  tmpreg |= (uint32_t)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | 
+                 USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit;
+  /* Write to USART CR2 */
+  USARTx->CR2 = (uint16_t)tmpreg;
+}
+
+/**
+  * @brief  Fills each USART_ClockInitStruct member with its default value.
+  * @param  USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef
+  *   structure which will be initialized.
+  * @retval None
+  */
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+  /* USART_ClockInitStruct members default value */
+  USART_ClockInitStruct->USART_Clock = USART_Clock_Disable;
+  USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low;
+  USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge;
+  USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable;
+}
+
+/**
+  * @brief  Enables or disables the specified USART peripheral.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  NewState: new state of the USARTx peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected USART by setting the UE bit in the CR1 register */
+    USARTx->CR1 |= CR1_UE_Set;
+  }
+  else
+  {
+    /* Disable the selected USART by clearing the UE bit in the CR1 register */
+    USARTx->CR1 &= CR1_UE_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified USART interrupts.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_IT: specifies the USART interrupt sources to be enabled or disabled.
+  *   This parameter can be one of the following values:
+  *     @arg USART_IT_CTS:  CTS change interrupt (not available for UART4 and UART5)
+  *     @arg USART_IT_LBD:  LIN Break detection interrupt
+  *     @arg USART_IT_TXE:  Tansmit Data Register empty interrupt
+  *     @arg USART_IT_TC:   Transmission complete interrupt
+  *     @arg USART_IT_RXNE: Receive Data register not empty interrupt
+  *     @arg USART_IT_IDLE: Idle line detection interrupt
+  *     @arg USART_IT_PE:   Parity Error interrupt
+  *     @arg USART_IT_ERR:  Error interrupt(Frame error, noise error, overrun error)
+  * @param  NewState: new state of the specified USARTx interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState)
+{
+  uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00;
+  uint32_t usartxbase = 0x00;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_CONFIG_IT(USART_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  /* The CTS interrupt is not available for UART4 and UART5 */
+  if (USART_IT == USART_IT_CTS)
+  {
+    assert_param(IS_USART_123_PERIPH(USARTx));
+  }   
+  
+  usartxbase = (uint32_t)USARTx;
+
+  /* Get the USART register index */
+  usartreg = (((uint8_t)USART_IT) >> 0x05);
+
+  /* Get the interrupt position */
+  itpos = USART_IT & IT_Mask;
+  itmask = (((uint32_t)0x01) << itpos);
+    
+  if (usartreg == 0x01) /* The IT is in CR1 register */
+  {
+    usartxbase += 0x0C;
+  }
+  else if (usartreg == 0x02) /* The IT is in CR2 register */
+  {
+    usartxbase += 0x10;
+  }
+  else /* The IT is in CR3 register */
+  {
+    usartxbase += 0x14; 
+  }
+  if (NewState != DISABLE)
+  {
+    *(__IO uint32_t*)usartxbase  |= itmask;
+  }
+  else
+  {
+    *(__IO uint32_t*)usartxbase &= ~itmask;
+  }
+}
+
+/**
+  * @brief  Enables or disables the USART’s DMA interface.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3 or UART4.  
+  * @param  USART_DMAReq: specifies the DMA request.
+  *   This parameter can be any combination of the following values:
+  *     @arg USART_DMAReq_Tx: USART DMA transmit request
+  *     @arg USART_DMAReq_Rx: USART DMA receive request
+  * @param  NewState: new state of the DMA Request sources.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @note The DMA mode is not available for UART5.  
+  * @retval None
+  */
+void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_1234_PERIPH(USARTx));
+  assert_param(IS_USART_DMAREQ(USART_DMAReq));  
+  assert_param(IS_FUNCTIONAL_STATE(NewState)); 
+  if (NewState != DISABLE)
+  {
+    /* Enable the DMA transfer for selected requests by setting the DMAT and/or
+       DMAR bits in the USART CR3 register */
+    USARTx->CR3 |= USART_DMAReq;
+  }
+  else
+  {
+    /* Disable the DMA transfer for selected requests by clearing the DMAT and/or
+       DMAR bits in the USART CR3 register */
+    USARTx->CR3 &= (uint16_t)~USART_DMAReq;
+  }
+}
+
+/**
+  * @brief  Sets the address of the USART node.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_Address: Indicates the address of the USART node.
+  * @retval None
+  */
+void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_ADDRESS(USART_Address)); 
+    
+  /* Clear the USART address */
+  USARTx->CR2 &= CR2_Address_Mask;
+  /* Set the USART address node */
+  USARTx->CR2 |= USART_Address;
+}
+
+/**
+  * @brief  Selects the USART WakeUp method.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_WakeUp: specifies the USART wakeup method.
+  *   This parameter can be one of the following values:
+  *     @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection
+  *     @arg USART_WakeUp_AddressMark: WakeUp by an address mark
+  * @retval None
+  */
+void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_WAKEUP(USART_WakeUp));
+  
+  USARTx->CR1 &= CR1_WAKE_Mask;
+  USARTx->CR1 |= USART_WakeUp;
+}
+
+/**
+  * @brief  Determines if the USART is in mute mode or not.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  NewState: new state of the USART mute mode.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState)); 
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the USART mute mode  by setting the RWU bit in the CR1 register */
+    USARTx->CR1 |= CR1_RWU_Set;
+  }
+  else
+  {
+    /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */
+    USARTx->CR1 &= CR1_RWU_Reset;
+  }
+}
+
+/**
+  * @brief  Sets the USART LIN Break detection length.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_LINBreakDetectLength: specifies the LIN break detection length.
+  *   This parameter can be one of the following values:
+  *     @arg USART_LINBreakDetectLength_10b: 10-bit break detection
+  *     @arg USART_LINBreakDetectLength_11b: 11-bit break detection
+  * @retval None
+  */
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength));
+  
+  USARTx->CR2 &= CR2_LBDL_Mask;
+  USARTx->CR2 |= USART_LINBreakDetectLength;  
+}
+
+/**
+  * @brief  Enables or disables the USART’s LIN mode.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  NewState: new state of the USART LIN mode.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the LIN mode by setting the LINEN bit in the CR2 register */
+    USARTx->CR2 |= CR2_LINEN_Set;
+  }
+  else
+  {
+    /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */
+    USARTx->CR2 &= CR2_LINEN_Reset;
+  }
+}
+
+/**
+  * @brief  Transmits single data through the USARTx peripheral.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  Data: the data to transmit.
+  * @retval None
+  */
+void USART_SendData(USART_TypeDef* USARTx, uint16_t Data)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_DATA(Data)); 
+    
+  /* Transmit Data */
+  USARTx->DR = (Data & (uint16_t)0x01FF);
+}
+
+/**
+  * @brief  Returns the most recent received data by the USARTx peripheral.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @retval The received data.
+  */
+uint16_t USART_ReceiveData(USART_TypeDef* USARTx)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  
+  /* Receive Data */
+  return (uint16_t)(USARTx->DR & (uint16_t)0x01FF);
+}
+
+/**
+  * @brief  Transmits break characters.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @retval None
+  */
+void USART_SendBreak(USART_TypeDef* USARTx)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  
+  /* Send break characters */
+  USARTx->CR1 |= CR1_SBK_Set;
+}
+
+/**
+  * @brief  Sets the specified USART guard time.
+  * @param  USARTx: where x can be 1, 2 or 3 to select the USART peripheral.
+  * @param  USART_GuardTime: specifies the guard time.
+  * @note The guard time bits are not available for UART4 and UART5.   
+  * @retval None
+  */
+void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime)
+{    
+  /* Check the parameters */
+  assert_param(IS_USART_123_PERIPH(USARTx));
+  
+  /* Clear the USART Guard time */
+  USARTx->GTPR &= GTPR_LSB_Mask;
+  /* Set the USART guard time */
+  USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08);
+}
+
+/**
+  * @brief  Sets the system clock prescaler.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_Prescaler: specifies the prescaler clock.  
+  * @note   The function is used for IrDA mode with UART4 and UART5.
+  * @retval None
+  */
+void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler)
+{ 
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  
+  /* Clear the USART prescaler */
+  USARTx->GTPR &= GTPR_MSB_Mask;
+  /* Set the USART prescaler */
+  USARTx->GTPR |= USART_Prescaler;
+}
+
+/**
+  * @brief  Enables or disables the USART’s Smart Card mode.
+  * @param  USARTx: where x can be 1, 2 or 3 to select the USART peripheral.
+  * @param  NewState: new state of the Smart Card mode.
+  *   This parameter can be: ENABLE or DISABLE.     
+  * @note The Smart Card mode is not available for UART4 and UART5. 
+  * @retval None
+  */
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_123_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the SC mode by setting the SCEN bit in the CR3 register */
+    USARTx->CR3 |= CR3_SCEN_Set;
+  }
+  else
+  {
+    /* Disable the SC mode by clearing the SCEN bit in the CR3 register */
+    USARTx->CR3 &= CR3_SCEN_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables NACK transmission.
+  * @param  USARTx: where x can be 1, 2 or 3 to select the USART peripheral. 
+  * @param  NewState: new state of the NACK transmission.
+  *   This parameter can be: ENABLE or DISABLE.  
+  * @note The Smart Card mode is not available for UART4 and UART5.
+  * @retval None
+  */
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_123_PERIPH(USARTx));  
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the NACK transmission by setting the NACK bit in the CR3 register */
+    USARTx->CR3 |= CR3_NACK_Set;
+  }
+  else
+  {
+    /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */
+    USARTx->CR3 &= CR3_NACK_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the USART’s Half Duplex communication.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  NewState: new state of the USART Communication.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */
+    USARTx->CR3 |= CR3_HDSEL_Set;
+  }
+  else
+  {
+    /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */
+    USARTx->CR3 &= CR3_HDSEL_Reset;
+  }
+}
+
+/**
+  * @brief  Configures the USART’s IrDA interface.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_IrDAMode: specifies the IrDA mode.
+  *   This parameter can be one of the following values:
+  *     @arg USART_IrDAMode_LowPower
+  *     @arg USART_IrDAMode_Normal
+  * @retval None
+  */
+void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_IRDA_MODE(USART_IrDAMode));
+    
+  USARTx->CR3 &= CR3_IRLP_Mask;
+  USARTx->CR3 |= USART_IrDAMode;
+}
+
+/**
+  * @brief  Enables or disables the USART’s IrDA interface.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  NewState: new state of the IrDA mode.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  if (NewState != DISABLE)
+  {
+    /* Enable the IrDA mode by setting the IREN bit in the CR3 register */
+    USARTx->CR3 |= CR3_IREN_Set;
+  }
+  else
+  {
+    /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */
+    USARTx->CR3 &= CR3_IREN_Reset;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified USART flag is set or not.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg USART_FLAG_CTS:  CTS Change flag (not available for UART4 and UART5)
+  *     @arg USART_FLAG_LBD:  LIN Break detection flag
+  *     @arg USART_FLAG_TXE:  Transmit data register empty flag
+  *     @arg USART_FLAG_TC:   Transmission Complete flag
+  *     @arg USART_FLAG_RXNE: Receive data register not empty flag
+  *     @arg USART_FLAG_IDLE: Idle Line detection flag
+  *     @arg USART_FLAG_ORE:  OverRun Error flag
+  *     @arg USART_FLAG_NE:   Noise Error flag
+  *     @arg USART_FLAG_FE:   Framing Error flag
+  *     @arg USART_FLAG_PE:   Parity Error flag
+  * @retval The new state of USART_FLAG (SET or RESET).
+  */
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_FLAG(USART_FLAG));
+  /* The CTS flag is not available for UART4 and UART5 */
+  if (USART_FLAG == USART_FLAG_CTS)
+  {
+    assert_param(IS_USART_123_PERIPH(USARTx));
+  }  
+  
+  if ((USARTx->SR & USART_FLAG) != (uint16_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the USARTx's pending flags.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_FLAG: specifies the flag to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg USART_FLAG_CTS:  CTS Change flag (not available for UART4 and UART5).
+  *     @arg USART_FLAG_LBD:  LIN Break detection flag.
+  *     @arg USART_FLAG_TC:   Transmission Complete flag.
+  *     @arg USART_FLAG_RXNE: Receive data register not empty flag.
+  *   
+  * @note
+  *   - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun 
+  *     error) and IDLE (Idle line detected) flags are cleared by software 
+  *     sequence: a read operation to USART_SR register (USART_GetFlagStatus()) 
+  *     followed by a read operation to USART_DR register (USART_ReceiveData()).
+  *   - RXNE flag can be also cleared by a read to the USART_DR register 
+  *     (USART_ReceiveData()).
+  *   - TC flag can be also cleared by software sequence: a read operation to 
+  *     USART_SR register (USART_GetFlagStatus()) followed by a write operation
+  *     to USART_DR register (USART_SendData()).
+  *   - TXE flag is cleared only by a write to the USART_DR register 
+  *     (USART_SendData()).
+  * @retval None
+  */
+void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_CLEAR_FLAG(USART_FLAG));
+  /* The CTS flag is not available for UART4 and UART5 */
+  if ((USART_FLAG & USART_FLAG_CTS) == USART_FLAG_CTS)
+  {
+    assert_param(IS_USART_123_PERIPH(USARTx));
+  } 
+   
+  USARTx->SR = (uint16_t)~USART_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified USART interrupt has occurred or not.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_IT: specifies the USART interrupt source to check.
+  *   This parameter can be one of the following values:
+  *     @arg USART_IT_CTS:  CTS change interrupt (not available for UART4 and UART5)
+  *     @arg USART_IT_LBD:  LIN Break detection interrupt
+  *     @arg USART_IT_TXE:  Tansmit Data Register empty interrupt
+  *     @arg USART_IT_TC:   Transmission complete interrupt
+  *     @arg USART_IT_RXNE: Receive Data register not empty interrupt
+  *     @arg USART_IT_IDLE: Idle line detection interrupt
+  *     @arg USART_IT_ORE:  OverRun Error interrupt
+  *     @arg USART_IT_NE:   Noise Error interrupt
+  *     @arg USART_IT_FE:   Framing Error interrupt
+  *     @arg USART_IT_PE:   Parity Error interrupt
+  * @retval The new state of USART_IT (SET or RESET).
+  */
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT)
+{
+  uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00;
+  ITStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_GET_IT(USART_IT));
+  /* The CTS interrupt is not available for UART4 and UART5 */ 
+  if (USART_IT == USART_IT_CTS)
+  {
+    assert_param(IS_USART_123_PERIPH(USARTx));
+  }   
+  
+  /* Get the USART register index */
+  usartreg = (((uint8_t)USART_IT) >> 0x05);
+  /* Get the interrupt position */
+  itmask = USART_IT & IT_Mask;
+  itmask = (uint32_t)0x01 << itmask;
+  
+  if (usartreg == 0x01) /* The IT  is in CR1 register */
+  {
+    itmask &= USARTx->CR1;
+  }
+  else if (usartreg == 0x02) /* The IT  is in CR2 register */
+  {
+    itmask &= USARTx->CR2;
+  }
+  else /* The IT  is in CR3 register */
+  {
+    itmask &= USARTx->CR3;
+  }
+  
+  bitpos = USART_IT >> 0x08;
+  bitpos = (uint32_t)0x01 << bitpos;
+  bitpos &= USARTx->SR;
+  if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  
+  return bitstatus;  
+}
+
+/**
+  * @brief  Clears the USARTx’s interrupt pending bits.
+  * @param  USARTx: Select the USART or the UART peripheral. 
+  *   This parameter can be one of the following values:
+  *   USART1, USART2, USART3, UART4 or UART5.
+  * @param  USART_IT: specifies the interrupt pending bit to clear.
+  *   This parameter can be one of the following values:
+  *     @arg USART_IT_CTS:  CTS change interrupt (not available for UART4 and UART5)
+  *     @arg USART_IT_LBD:  LIN Break detection interrupt
+  *     @arg USART_IT_TC:   Transmission complete interrupt. 
+  *     @arg USART_IT_RXNE: Receive Data register not empty interrupt.
+  *   
+  * @note
+  *   - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun 
+  *     error) and IDLE (Idle line detected) pending bits are cleared by 
+  *     software sequence: a read operation to USART_SR register 
+  *     (USART_GetITStatus()) followed by a read operation to USART_DR register 
+  *     (USART_ReceiveData()).
+  *   - RXNE pending bit can be also cleared by a read to the USART_DR register 
+  *     (USART_ReceiveData()).
+  *   - TC pending bit can be also cleared by software sequence: a read 
+  *     operation to USART_SR register (USART_GetITStatus()) followed by a write 
+  *     operation to USART_DR register (USART_SendData()).
+  *   - TXE pending bit is cleared only by a write to the USART_DR register 
+  *     (USART_SendData()).
+  * @retval None
+  */
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT)
+{
+  uint16_t bitpos = 0x00, itmask = 0x00;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_CLEAR_IT(USART_IT));
+  /* The CTS interrupt is not available for UART4 and UART5 */
+  if (USART_IT == USART_IT_CTS)
+  {
+    assert_param(IS_USART_123_PERIPH(USARTx));
+  }   
+  
+  bitpos = USART_IT >> 0x08;
+  itmask = ((uint16_t)0x01 << (uint16_t)bitpos);
+  USARTx->SR = (uint16_t)~itmask;
+}
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c
new file mode 100644
index 0000000000000000000000000000000000000000..e5b74afa8d3d068d5fdd8f96fa05073bc567507f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c
@@ -0,0 +1,223 @@
+/**
+  ******************************************************************************
+  * @file    stm32f10x_wwdg.c
+  * @author  MCD Application Team
+  * @version V3.1.2
+  * @date    09/28/2009
+  * @brief   This file provides all the WWDG firmware functions.
+  ******************************************************************************
+  * @copy
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f10x_wwdg.h"
+#include "stm32f10x_rcc.h"
+
+/** @addtogroup STM32F10x_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup WWDG 
+  * @brief WWDG driver modules
+  * @{
+  */
+
+/** @defgroup WWDG_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup WWDG_Private_Defines
+  * @{
+  */
+
+/* ----------- WWDG registers bit address in the alias region ----------- */
+#define WWDG_OFFSET       (WWDG_BASE - PERIPH_BASE)
+
+/* Alias word address of EWI bit */
+#define CFR_OFFSET        (WWDG_OFFSET + 0x04)
+#define EWI_BitNumber     0x09
+#define CFR_EWI_BB        (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4))
+
+/* --------------------- WWDG registers bit mask ------------------------ */
+
+/* CR register bit mask */
+#define CR_WDGA_Set       ((uint32_t)0x00000080)
+
+/* CFR register bit mask */
+#define CFR_WDGTB_Mask    ((uint32_t)0xFFFFFE7F)
+#define CFR_W_Mask        ((uint32_t)0xFFFFFF80)
+#define BIT_Mask          ((uint8_t)0x7F)
+
+/**
+  * @}
+  */
+
+/** @defgroup WWDG_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup WWDG_Private_Variables
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup WWDG_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @defgroup WWDG_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the WWDG peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void WWDG_DeInit(void)
+{
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE);
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE);
+}
+
+/**
+  * @brief  Sets the WWDG Prescaler.
+  * @param  WWDG_Prescaler: specifies the WWDG Prescaler.
+  *   This parameter can be one of the following values:
+  *     @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1
+  *     @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2
+  *     @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4
+  *     @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8
+  * @retval None
+  */
+void WWDG_SetPrescaler(uint32_t WWDG_Prescaler)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler));
+  /* Clear WDGTB[1:0] bits */
+  tmpreg = WWDG->CFR & CFR_WDGTB_Mask;
+  /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */
+  tmpreg |= WWDG_Prescaler;
+  /* Store the new value */
+  WWDG->CFR = tmpreg;
+}
+
+/**
+  * @brief  Sets the WWDG window value.
+  * @param  WindowValue: specifies the window value to be compared to the downcounter.
+  *   This parameter value must be lower than 0x80.
+  * @retval None
+  */
+void WWDG_SetWindowValue(uint8_t WindowValue)
+{
+  __IO uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_WWDG_WINDOW_VALUE(WindowValue));
+  /* Clear W[6:0] bits */
+
+  tmpreg = WWDG->CFR & CFR_W_Mask;
+
+  /* Set W[6:0] bits according to WindowValue value */
+  tmpreg |= WindowValue & (uint32_t) BIT_Mask;
+
+  /* Store the new value */
+  WWDG->CFR = tmpreg;
+}
+
+/**
+  * @brief  Enables the WWDG Early Wakeup interrupt(EWI).
+  * @param  None
+  * @retval None
+  */
+void WWDG_EnableIT(void)
+{
+  *(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE;
+}
+
+/**
+  * @brief  Sets the WWDG counter value.
+  * @param  Counter: specifies the watchdog counter value.
+  *   This parameter must be a number between 0x40 and 0x7F.
+  * @retval None
+  */
+void WWDG_SetCounter(uint8_t Counter)
+{
+  /* Check the parameters */
+  assert_param(IS_WWDG_COUNTER(Counter));
+  /* Write to T[6:0] bits to configure the counter value, no need to do
+     a read-modify-write; writing a 0 to WDGA bit does nothing */
+  WWDG->CR = Counter & BIT_Mask;
+}
+
+/**
+  * @brief  Enables WWDG and load the counter value.                  
+  * @param  Counter: specifies the watchdog counter value.
+  *   This parameter must be a number between 0x40 and 0x7F.
+  * @retval None
+  */
+void WWDG_Enable(uint8_t Counter)
+{
+  /* Check the parameters */
+  assert_param(IS_WWDG_COUNTER(Counter));
+  WWDG->CR = CR_WDGA_Set | Counter;
+}
+
+/**
+  * @brief  Checks whether the Early Wakeup interrupt flag is set or not.
+  * @param  None
+  * @retval The new state of the Early Wakeup interrupt flag (SET or RESET)
+  */
+FlagStatus WWDG_GetFlagStatus(void)
+{
+  return (FlagStatus)(WWDG->SR);
+}
+
+/**
+  * @brief  Clears Early Wakeup interrupt flag.
+  * @param  None
+  * @retval None
+  */
+void WWDG_ClearFlag(void)
+{
+  WWDG->SR = (uint32_t)RESET;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/Release_Notes.html b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/Release_Notes.html
new file mode 100644
index 0000000000000000000000000000000000000000..e2f21c3c52fff6fd5d19a8115c05452338775985
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/Release_Notes.html
@@ -0,0 +1,1100 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html xmlns:v="urn:schemas-microsoft-com:vml" xmlns:o="urn:schemas-microsoft-com:office:office" xmlns:w="urn:schemas-microsoft-com:office:word" xmlns:m="http://schemas.microsoft.com/office/2004/12/omml" xmlns="http://www.w3.org/TR/REC-html40"><head>
+<meta http-equiv="Content-Type" content="text/html; charset=windows-1252">
+<link rel="File-List" href="Release_Notes_for_STM32F45x_StdPeriph_Driver_files/filelist.xml">
+<link rel="Edit-Time-Data" href="Release_Notes_for_STM32F45x_StdPeriph_Driver_files/editdata.mso"><!--[if !mso]>
+<style>
+v\:* {behavior:url(#default#VML);}
+o\:* {behavior:url(#default#VML);}
+w\:* {behavior:url(#default#VML);}
+.shape {behavior:url(#default#VML);}
+</style>
+<![endif]-->
+
+
+
+<title>Release Notes for STM32F4xx Standard Peripherals Library Drivers</title><!--[if gte mso 9]><xml>
+ <o:DocumentProperties>
+  <o:Author>STMicroelectronics</o:Author>
+  <o:LastAuthor>Raouf Hosni</o:LastAuthor>
+  <o:Revision>39</o:Revision>
+  <o:TotalTime>137</o:TotalTime>
+  <o:Created>2009-02-27T19:26:00Z</o:Created>
+  <o:LastSaved>2010-10-15T11:07:00Z</o:LastSaved>
+  <o:Pages>3</o:Pages>
+  <o:Words>973</o:Words>
+  <o:Characters>5548</o:Characters>
+  <o:Company>STMicroelectronics</o:Company>
+  <o:Lines>46</o:Lines>
+  <o:Paragraphs>13</o:Paragraphs>
+  <o:CharactersWithSpaces>6508</o:CharactersWithSpaces>
+  <o:Version>12.00</o:Version>
+ </o:DocumentProperties>
+</xml><![endif]--><link rel="themeData" href="Release_Notes_for_STM32F45x_StdPeriph_Driver_files/themedata.thmx">
+<link rel="colorSchemeMapping" href="Release_Notes_for_STM32F45x_StdPeriph_Driver_files/colorschememapping.xml"><!--[if gte mso 9]><xml>
+ <w:WordDocument>
+  <w:Zoom>110</w:Zoom>
+  <w:TrackMoves>false</w:TrackMoves>
+  <w:TrackFormatting/>
+  <w:ValidateAgainstSchemas/>
+  <w:SaveIfXMLInvalid>false</w:SaveIfXMLInvalid>
+  <w:IgnoreMixedContent>false</w:IgnoreMixedContent>
+  <w:AlwaysShowPlaceholderText>false</w:AlwaysShowPlaceholderText>
+  <w:DoNotPromoteQF/>
+  <w:LidThemeOther>EN-US</w:LidThemeOther>
+  <w:LidThemeAsian>X-NONE</w:LidThemeAsian>
+  <w:LidThemeComplexScript>X-NONE</w:LidThemeComplexScript>
+  <w:Compatibility>
+   <w:BreakWrappedTables/>
+   <w:SnapToGridInCell/>
+   <w:WrapTextWithPunct/>
+   <w:UseAsianBreakRules/>
+   <w:DontGrowAutofit/>
+   <w:SplitPgBreakAndParaMark/>
+   <w:DontVertAlignCellWithSp/>
+   <w:DontBreakConstrainedForcedTables/>
+   <w:DontVertAlignInTxbx/>
+   <w:Word11KerningPairs/>
+   <w:CachedColBalance/>
+  </w:Compatibility>
+  <w:BrowserLevel>MicrosoftInternetExplorer4</w:BrowserLevel>
+  <m:mathPr>
+   <m:mathFont m:val="Cambria Math"/>
+   <m:brkBin m:val="before"/>
+   <m:brkBinSub m:val="&#45;-"/>
+   <m:smallFrac m:val="off"/>
+   <m:dispDef/>
+   <m:lMargin m:val="0"/>
+   <m:rMargin m:val="0"/>
+   <m:defJc m:val="centerGroup"/>
+   <m:wrapIndent m:val="1440"/>
+   <m:intLim m:val="subSup"/>
+   <m:naryLim m:val="undOvr"/>
+  </m:mathPr></w:WordDocument>
+</xml><![endif]--><!--[if gte mso 9]><xml>
+ <w:LatentStyles DefLockedState="false" DefUnhideWhenUsed="false"
+  DefSemiHidden="false" DefQFormat="false" LatentStyleCount="267">
+  <w:LsdException Locked="false" QFormat="true" Name="Normal"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 1"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 2"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 3"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 4"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 5"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 6"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 7"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 8"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 9"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="caption"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Title"/>
+  <w:LsdException Locked="false" Priority="1" Name="Default Paragraph Font"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Subtitle"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Strong"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Emphasis"/>
+  <w:LsdException Locked="false" Priority="99" Name="No List"/>
+  <w:LsdException Locked="false" Priority="99" SemiHidden="true"
+   Name="Placeholder Text"/>
+  <w:LsdException Locked="false" Priority="1" QFormat="true" Name="No Spacing"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 1"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 1"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 1"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="99" SemiHidden="true" Name="Revision"/>
+  <w:LsdException Locked="false" Priority="34" QFormat="true"
+   Name="List Paragraph"/>
+  <w:LsdException Locked="false" Priority="29" QFormat="true" Name="Quote"/>
+  <w:LsdException Locked="false" Priority="30" QFormat="true"
+   Name="Intense Quote"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 1"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 1"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 1"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 1"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 1"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 2"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 2"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 2"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 2"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 2"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 2"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 2"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 2"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 3"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 3"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 3"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 3"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 3"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 3"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 3"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 3"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 4"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 4"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 4"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 4"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 4"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 4"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 4"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 4"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 5"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 5"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 5"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 5"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 5"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 5"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 5"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 5"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 6"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 6"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 6"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 6"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 6"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 6"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 6"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 6"/>
+  <w:LsdException Locked="false" Priority="19" QFormat="true"
+   Name="Subtle Emphasis"/>
+  <w:LsdException Locked="false" Priority="21" QFormat="true"
+   Name="Intense Emphasis"/>
+  <w:LsdException Locked="false" Priority="31" QFormat="true"
+   Name="Subtle Reference"/>
+  <w:LsdException Locked="false" Priority="32" QFormat="true"
+   Name="Intense Reference"/>
+  <w:LsdException Locked="false" Priority="33" QFormat="true" Name="Book Title"/>
+  <w:LsdException Locked="false" Priority="37" SemiHidden="true"
+   UnhideWhenUsed="true" Name="Bibliography"/>
+  <w:LsdException Locked="false" Priority="39" SemiHidden="true"
+   UnhideWhenUsed="true" QFormat="true" Name="TOC Heading"/>
+ </w:LatentStyles>
+</xml><![endif]-->
+
+<style>
+<!--
+ /* Font Definitions */
+ @font-face
+	{font-family:"Cambria Math";
+	panose-1:2 4 5 3 5 4 6 3 2 4;
+	mso-font-charset:1;
+	mso-generic-font-family:roman;
+	mso-font-format:other;
+	mso-font-pitch:variable;
+	mso-font-signature:0 0 0 0 0 0;}
+@font-face
+	{font-family:Calibri;
+	panose-1:2 15 5 2 2 2 4 3 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:-1610611985 1073750139 0 0 159 0;}
+@font-face
+	{font-family:Tahoma;
+	panose-1:2 11 6 4 3 5 4 4 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:1627400839 -2147483648 8 0 66047 0;}
+@font-face
+	{font-family:Verdana;
+	panose-1:2 11 6 4 3 5 4 4 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:536871559 0 0 0 415 0;}
+ /* Style Definitions */
+ p.MsoNormal, li.MsoNormal, div.MsoNormal
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-parent:"";
+	margin:0in;
+	margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:12.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";}
+h1
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 1 Char";
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	mso-outline-level:1;
+	font-size:24.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;}
+h2
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 2 Char";
+	mso-style-next:Normal;
+	margin-top:12.0pt;
+	margin-right:0in;
+	margin-bottom:3.0pt;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	page-break-after:avoid;
+	mso-outline-level:2;
+	font-size:14.0pt;
+	font-family:"Arial","sans-serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;
+	font-style:italic;}
+h3
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 3 Char";
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	mso-outline-level:3;
+	font-size:13.5pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;}
+a:link, span.MsoHyperlink
+	{mso-style-unhide:no;
+	color:blue;
+	text-decoration:underline;
+	text-underline:single;}
+a:visited, span.MsoHyperlinkFollowed
+	{mso-style-unhide:no;
+	color:blue;
+	text-decoration:underline;
+	text-underline:single;}
+p
+	{mso-style-unhide:no;
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	font-size:12.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";}
+p.MsoAcetate, li.MsoAcetate, div.MsoAcetate
+	{mso-style-unhide:no;
+	mso-style-link:"Balloon Text Char";
+	margin:0in;
+	margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:8.0pt;
+	font-family:"Tahoma","sans-serif";
+	mso-fareast-font-family:"Times New Roman";}
+span.Heading1Char
+	{mso-style-name:"Heading 1 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 1";
+	mso-ansi-font-size:14.0pt;
+	mso-bidi-font-size:14.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#365F91;
+	mso-themecolor:accent1;
+	mso-themeshade:191;
+	font-weight:bold;}
+span.Heading2Char
+	{mso-style-name:"Heading 2 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 2";
+	mso-ansi-font-size:13.0pt;
+	mso-bidi-font-size:13.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#4F81BD;
+	mso-themecolor:accent1;
+	font-weight:bold;}
+span.Heading3Char
+	{mso-style-name:"Heading 3 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 3";
+	mso-ansi-font-size:12.0pt;
+	mso-bidi-font-size:12.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#4F81BD;
+	mso-themecolor:accent1;
+	font-weight:bold;}
+span.BalloonTextChar
+	{mso-style-name:"Balloon Text Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Balloon Text";
+	mso-ansi-font-size:8.0pt;
+	mso-bidi-font-size:8.0pt;
+	font-family:"Tahoma","sans-serif";
+	mso-ascii-font-family:Tahoma;
+	mso-hansi-font-family:Tahoma;
+	mso-bidi-font-family:Tahoma;}
+.MsoChpDefault
+	{mso-style-type:export-only;
+	mso-default-props:yes;
+	font-size:10.0pt;
+	mso-ansi-font-size:10.0pt;
+	mso-bidi-font-size:10.0pt;}
+@page WordSection1
+	{size:8.5in 11.0in;
+	margin:1.0in 1.25in 1.0in 1.25in;
+	mso-header-margin:.5in;
+	mso-footer-margin:.5in;
+	mso-paper-source:0;}
+div.WordSection1
+	{page:WordSection1;}
+ /* List Definitions */
+ @list l0
+	{mso-list-id:62067358;
+	mso-list-template-ids:-174943062;}
+@list l0:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l0:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1
+	{mso-list-id:128015942;
+	mso-list-template-ids:-90681214;}
+@list l1:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2
+	{mso-list-id:216556000;
+	mso-list-template-ids:925924412;}
+@list l2:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l2:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l2:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3
+	{mso-list-id:562446694;
+	mso-list-template-ids:913898366;}
+@list l3:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l3:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4
+	{mso-list-id:797802132;
+	mso-list-template-ids:-1971191336;}
+@list l4:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5
+	{mso-list-id:907304066;
+	mso-list-template-ids:1969781532;}
+@list l5:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6
+	{mso-list-id:1050613616;
+	mso-list-template-ids:-1009886748;}
+@list l6:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l6:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l6:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7
+	{mso-list-id:1234970193;
+	mso-list-template-ids:2055904002;}
+@list l7:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l7:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l7:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8
+	{mso-list-id:1846092290;
+	mso-list-template-ids:-768590846;}
+@list l8:level1
+	{mso-level-start-at:2;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9
+	{mso-list-id:1894656566;
+	mso-list-template-ids:1199983812;}
+@list l9:level1
+	{mso-level-start-at:2;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+ol
+	{margin-bottom:0in;}
+ul
+	{margin-bottom:0in;}
+-->
+</style><!--[if gte mso 10]>
+<style>
+ /* Style Definitions */
+ table.MsoNormalTable
+	{mso-style-name:"Table Normal";
+	mso-tstyle-rowband-size:0;
+	mso-tstyle-colband-size:0;
+	mso-style-noshow:yes;
+	mso-style-priority:99;
+	mso-style-qformat:yes;
+	mso-style-parent:"";
+	mso-padding-alt:0in 5.4pt 0in 5.4pt;
+	mso-para-margin:0in;
+	mso-para-margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:10.0pt;
+	font-family:"Times New Roman","serif";}
+</style>
+<![endif]--><!--[if gte mso 9]><xml>
+ <o:shapedefaults v:ext="edit" spidmax="7170"/>
+</xml><![endif]--><!--[if gte mso 9]><xml>
+ <o:shapelayout v:ext="edit">
+  <o:idmap v:ext="edit" data="1"/>
+ </o:shapelayout></xml><![endif]--></head>
+<body style="" lang="EN-US" link="blue" vlink="blue">
+
+<div class="WordSection1">
+
+<p class="MsoNormal"><span style="font-family: &quot;Arial&quot;,&quot;sans-serif&quot;;"><o:p>&nbsp;</o:p></span></p>
+
+<div align="center">
+
+<table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+ <tbody><tr style="">
+  <td style="padding: 0in;" valign="top">
+  <table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+   <tbody><tr style="">
+    <td style="padding: 0in 5.4pt;" valign="top">
+    <p class="MsoNormal"><span style="font-size: 8pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: blue;"><a href="../../Release_Notes.html">Back to Release page</a></span><span style="font-size: 10pt;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+   <tr style="">
+    <td style="padding: 1.5pt;">
+    <h1 style="margin-bottom: 0.25in; text-align: center;" align="center"><span style="font-size: 20pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: rgb(51, 102, 255);">Release Notes for STM32F4xx Standard
+    Peripherals&nbsp; Drivers</span><span style="font-size: 20pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><o:p></o:p></span></h1>
+    <p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: black;">Copyright
+    2013 STMicroelectronics</span><span style="color: black;"><u1:p></u1:p><o:p></o:p></span></p>
+    <p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: black;"><img id="_x0000_i1026" src="../../_htmresc/logo.bmp" border="0" height="65" width="86"></span><span style="font-size: 10pt;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+  </tbody></table>
+  <p class="MsoNormal"><span style="font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; display: none;"><o:p>&nbsp;</o:p></span></p>
+  <table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" width="900">
+   <tbody><tr style="">
+    <td style="padding: 0in;" valign="top">
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><span style="font-size: 12pt; color: white;">Contents<o:p></o:p></span></h2>
+    <ol style="margin-top: 0in;" start="1" type="1">
+     <li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><a href="#History">STM32F4xx&nbsp;Standard Peripherals Library Drivers
+         update History</a><o:p></o:p></span></li>
+     <li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><a href="#License">License</a><o:p></o:p></span></li>
+    </ol>
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="History"></a><span style="font-size: 12pt; color: white;">STM32F4xx
+    Standard Peripherals Library Drivers&nbsp; update History</span></h2><br><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 185px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.3.0 / 08-November-2013<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+
+            
+
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add support of <b>STM32F401xExx</b> devices</span><span style="font-size: 12pt; font-family: &quot;Times New Roman&quot;,&quot;serif&quot;;"><o:p></o:p></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">stm32f4xx_gpio.c/h</span><span style="font-size: 12pt; font-family: &quot;Times New Roman&quot;,&quot;serif&quot;;"> <o:p></o:p></span></li><ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Update
+      GPIOSpeed_TypeDef structure’s fields name to be in line with GPIO out
+      speed definition in the product Reference Manual</span><span style="font-size: 12pt; font-family: &quot;Times New Roman&quot;,&quot;serif&quot;;"> </span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><o:p></o:p></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add
+      a legacy defines to keep compatibility with previous version</span><span style="font-size: 12pt; font-family: &quot;Times New Roman&quot;,&quot;serif&quot;;"><o:p></o:p></span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">stm32f4xx_flash.c/h</span><span style="font-size: 12pt; font-family: &quot;Times New Roman&quot;,&quot;serif&quot;;"> <o:p></o:p></span></li><ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">File’s header comments: update
+      description of the maximum AHB frequency vs. voltage scaling
+      configuration <o:p></o:p></span></li></ul></ul>
+<h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 185px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.2.1 / 19-September-2013<o:p></o:p></span></h3>
+            <p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+
+            <ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">stm32f4xx_pwr.c/.h&nbsp;<span style="font-weight: bold;"></span></span></p></li><ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add
+new function to configure the Under-Drive STOP Mode : <span style="font-style: italic;">PWR_EnterUnderDriveSTOPMode(uint32_t
+PWR_Regulator, uint8_t PWR_STOPEntry) </span>only used in case of STM32F427/437/429/439xx devices.<o:p></o:p></span></p>
+</li></ul></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 185px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.2.0 / 11-September-2013<o:p></o:p></span></h3>
+            <p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+
+            <ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add
+support of <span style="font-weight: bold;">STM32F429/439xx</span> and <span style="font-weight: bold;">STM32F401xCxx</span> devices</span></p></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Update definition of <span style="font-weight: bold;">STM32F427/437xx</span> devices : </span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">extension
+of the features to include system clock up to 180MHz, dual bank Flash, reduced
+STOP Mode current, SAI, PCROP, SDRAM and DMA2D</span></li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add&nbsp;drivers for new 
+peripherals of </span><span style="font-size: 10pt; font-family: Verdana;">STM32F4xx&nbsp;</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><span style="font-weight: bold;">STM32F427/437xx </span>and<span style="font-weight: bold;"> </span></span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><span style="font-weight: bold;">STM32F429/439xx </span></span><span style="font-size: 10pt; font-family: Verdana;">devices:</span> 
+<ul style="font-weight: bold; font-style: italic;"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_dma2d.h/.c </span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_fmc.h/.c </span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_ltdc.h/.c </span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_sai.h/.c</span></li></ul></li></ul><ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">stm32f4xx_adc.c/.h<o:p></o:p></span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">&nbsp;<o:p></o:p></span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"></span></p></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Update
+the Temperature sensor channel for STM32F427/STM32F437x/STM32F429x/STM32F439x
+devices from Channel 16 to Channel 18</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;">
+
+
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add
+a note in <span style="font-style: italic;">ADC_VBATCmd()</span> header function to inform that the Voltage measured is
+VBAT/2 in case of STM3240xxx/41xxx and VBAT/4 in case of STM32F42xxx/43xxx.<o:p></o:p></span></p></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">In
+<span style="font-style: italic;">ADC_GetSoftwareStartConvStatus()</span> function, replace "<span style="font-style: italic;">ADC_CR2_JSWSTART"</span>
+by "<span style="font-style: italic;">ADC_CR2_SWSTART</span>"<o:p></o:p></span></p></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_flash.c/.h</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Update
+the header file descriptioon, add the table of number of wait states
+according to system frequency selected for all STM32F4xx family devices</span></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;">Update<span style="font-style: italic;"> FLASH_EraseAllSectors() </span>function to support the erase for all sectors within Bank1 and Bank2 in case of STM32F42/43xxx devices</span></small></li><li><small><span style="font-family: Verdana;">Add new FLASH Latency values:<span style="font-style: italic;"> FLASH_Latency_8, FLASH_Latency_9, FLASH_Latency_10, FLASH_Latency_11,</span></span></small><small><span style="font-family: Verdana;"><span style="font-style: italic;"> FLASH_Latency_12, FLASH_Latency_13, FLASH_Latency_14, FLASH_Latency_15.</span></span></small></li><li><small><span style="font-family: Verdana;">Add new flag error in FLASH_Status structure: <span style="font-style: italic;">" FLASH_ERROR_RD"</span></span></small></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;">Add<span style="font-style: italic;"> </span>new&nbsp;</span><span style="font-family: Verdana;"><span style="font-style: italic;"></span>functions:</span><span style="font-family: Verdana;"><span style="font-style: italic;">&nbsp;</span></span></small></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_EraseAllBank1Sectors():</span>&nbsp;</span></small><small><span style="font-family: Verdana;">mass erase in bank 1 (Half mass erase)</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;"></span></span><span style="font-family: Verdana;"></span><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_EraseAllBank2Sectors():</span> mass erase&nbsp;</span></small><small><span style="font-family: Verdana;">in Bank 2 (Half mass erase)</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_BootConfig()</span>: configure Dual bank boot mode</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_PCROPSelectionConfig():</span> select PCROP feature</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_WRP1Config():</span> configure write protection from Sector 12 to sector 23</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_PCROPConfig()</span>: configure PC read/write protection from Sector 0 to sector 11</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_PCROP1Config()</span>: configure PC read/write protection from Sector12 to sector23</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_GetWRP1()</span>: Read the write protected sectors from 12 to 23</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_GetPCROP()</span>: Read the PC read/write protected sectors from 0 to 11</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">FLASH_OB_GetPCROP1()</span>: Read the PC read/write protected sectors from 12 to 23</span></small></li></ul></ul></ul><ul style="margin-top: 0cm;" type="square"><li><small><span style="font-family: Verdana;">stm32f4xx_gpio.c/.h</span></small></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;">Update <span style="font-style: italic;">GPIO_DeInit()</span> function : Add GPIOJ, GPIOK clock reset/enable</span></small></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add a new alternate function for I2C2 and I2C3 :</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt; font-style: italic;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">#define
+GPIO_AF9_I2C2&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;
+((uint8_t)0x09)&nbsp; /* I2C2 Alternate Function mapping */</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><span style="font-style: italic;">#define
+GPIO_AF9_I2C3&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;
+((uint8_t)0x09)&nbsp; /* I2C3 Alternate Function mapping */</span></span></li></ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update all functions header 
+comments.<br></span></li></ul></ul><ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;">stm32f4xx_rcc.c/.h</span></small></li><ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add new definitions for new 
+peripherals:&nbsp;<span style="font-style: italic;"></span></span><small><span style="font-family: Verdana;"><span style="font-style: italic;">SAI1, LTDC, FMC</span></span></small> </li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;">Add a new parameter in <span style="font-style: italic;">RCC_PLLI2SConfig()</span> function : <span style="font-style: italic;">PLLI2SQ</span> to specifies the division factor for SAI1 clock</span></small></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;">Add new functions:&nbsp;</span></small></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">RCC_PLLSAIConfig(), RCC_PLLSAICmd()</span>:&nbsp;</span></small><small><span style="font-family: Verdana;">PLL SAI Clock configuration</span></small><small><span style="font-family: Verdana;"></span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;">Add new function&nbsp;<span style="font-style: italic;">RCC_SAICLKConfig()</span>:&nbsp;</span></small><small><span style="font-family: Verdana;">SAI clock division factors configuration</span></small></li></ul><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><small><span style="font-family: Verdana;"></span></small><small><span style="font-family: Verdana;"><span style="font-style: italic;">RCC_LCDCLKConfig()</span>: LCD</span></small><small><span style="font-family: Verdana;"> clock&nbsp;division factors configuration</span></small></li></ul></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32l1xx_syscfg.c/.h</span></li><ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add new SYSCFG port sources configurations : EXTI_PortSourceGPIOJ, EXTI_PortSourceGPIOK</span> 
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add new function <span style="font-style: italic;">SYSCFG_MemorySwappingBank()</span>: swap between bank 1 and Bank 2</span></li></ul></ul><ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">stm32f4xx_pwr.c/.h
+<o:p></o:p></span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">&nbsp;<o:p></o:p></span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"></span></p></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;">
+
+
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">Add
+more details and update comments in functions and groups description</span></p></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><span style=""></span>Add the following functions to
+configure the Over-drive and Under-drive Modes :<o:p></o:p></span></p></li><ul style="font-style: italic;"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">PWR_OverDriveCmd()<o:p></o:p></span></p></li></ul><ul style="font-style: italic;"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;">
+
+<p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">PWR_OverDriveSWCmd()</span></p></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">PWR_UnderDriveCmd()</span></li></ul></ul></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; width: 200px; margin-right: 500pt;"><span style="font-size: 10pt; color: white; font-family: Arial;">V1.1.0 / 
+11-Janury-2013<o:p></o:p></span></h3>
+<p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b><u><span style="font-size: 10pt; color: black; font-family: Verdana;">Main 
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Official release </span><span style="font-size: 10pt; font-family: Verdana;">for <span style="font-weight: bold;">STM32F427x/437x</span> devices.</span><span style="font-size: 10pt; font-family: 'Verdana','sans-serif';"></span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_cryp.c/.h</span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">Update CRYP_Init() </span>function : add the support 
+for new algorithms (GCM/CCM).</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add new function :<span style="font-style: italic;"> CRYP_PhaseConfig() </span>used for new AES-GCM and 
+AES-CCM algorithms.<span style="font-style: italic;"></span></span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">CRYP_InitTypeDef </span>structure : update all 
+structure fields from<span style="font-style: italic;"> uint16_t </span>to<span style="font-style: italic;"> uint32_t </span>and update all driver functions&nbsp; 
+parameters and the correpondant define to be declared with<span style="font-style: italic;"> uint32_t </span>type.</span>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Replace the<span style="font-style: italic;"> "CRYP_ContextSave-&gt;CR_bits9to2" by 
+"CRYP_ContextSave-&gt;CurrentConfig".</span></span></li></ul></li></ul>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_flash.c/.h</span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Update FLASH sectors numbers<span style="font-style: italic;"> "FLASH_Sector_x" with x = 
+0..23.</span></span></small>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Update<span style="font-style: italic;"> 
+FLASH_EraseAllSectors() </span>function to support&nbsp;mass erase 
+for&nbsp;</span></small><small><span style="font-family: Verdana;">STM32F427x/437x 
+devices.</span></small></li></ul></li></ul>
+<ul style="margin-top: 0cm;" type="square"><li><small><span style="font-family: Verdana;">stm32f4xx_gpio.c/.h</span></small>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Add Alternate functions for new peripherals:<span style="font-style: italic;"> SPI4, SPI5, SPI6, UART7, 
+UART8.</span></span></small></li></ul>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update all functions header 
+comment.<br></span></li></ul>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">stm32f4xx_hash.c/.h</span></small>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Update <span style="font-style: italic;">HASH_GetDigest()</span> function : add the 
+HASH_DIGEST structure.</span></small>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Add new function <span style="font-style: italic;">HASH_AutoStartDigest()</span>.</span></small>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Update HASH_MsgDigest structure: to support SHA-224 
+and SHA-256 modes.</span></small>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">&nbsp;Update <span style="font-style: italic;">HASH_Context</span> structure.</span></small>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Update some define using bit definitions already 
+declared in stm32f4xx.h.</span></small></li></ul>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">stm32f4xx_i2c.c/.h</span></small>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Add new functions:<br></span></small></li></ul>
+<ul><ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">I2C_AnalogFilterCmd()</span>: enable/disable the 
+analog I2C filters.</span></small></li></ul><ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;"><span style="font-style: italic;">I2C_DigitalFilterConfig()</span>: configure the 
+digital I2C filters.</span></small></li></ul></ul>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: 'Verdana','sans-serif';">stm32f4xx_pwr.c/.h 
+<o:p></o:p></span><span style="font-size: 10pt; font-family: 'Verdana','sans-serif';"></span><span style="font-size: 10pt; font-family: 'Verdana','sans-serif';"></span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: 'Verdana','sans-serif';">Add new argument 
+"<i>PWR_Regulator_Voltage_Scale3</i>" &nbsp;to <i>PWR_MainRegulatorModeConfig()</i> 
+function to be in line with Reference Manual 
+description.</span></li></ul></li></ul>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">stm32f4xx_rcc.c/.h</span></small>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Add new definitions for new 
+peripherals:&nbsp;<span style="font-style: italic;">SPI4, SPI5, 
+SPI6,</span>&nbsp;</span><small><span style="font-family: Verdana;"><span style="font-style: italic;">SAI1,&nbsp;UART7, UART8.</span></span></small> 
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Add a new parameter in <span style="font-style: italic;">RCC_PLLI2SConfig()</span> function : <span style="font-style: italic;">PLLI2SQ</span> to specifies the division factor for 
+SAI1 clock.</span></small>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><small><span style="font-family: Verdana;">Add&nbsp;<span style="font-style: italic;">RCC_TIMCLKPresConfig()</span> function 
+:</span></small><small><span style="font-family: Verdana;"> TIMER Prescaler 
+selection.&nbsp;</span></small></li></ul>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32l1xx_spi.c/.h</span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update to support SPI4, SPI5, 
+SPI6.</span> </li></ul>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update all functions header 
+comment.</span></li></ul>
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">stm32l1xx_usart.c/.h</span>
+<ul><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update to support UART7 and 
+UART8.</span> 
+</li><li class="MsoNormal" style="margin-top: 4.5pt; margin-bottom: 4.5pt; color: black;"><span style="font-size: 10pt; font-family: Verdana;">Update all functions header 
+comment.</span></li></ul></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 167px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.2 / 05-March-2012<o:p></o:p></span></h3>
+            <p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+
+            <ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">All source files:&nbsp;license disclaimer text update and add link to the License file on ST Internet.</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_dcmi.c</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">DCMI_GetFlagStatus()</span> function: fix test condition on RISR register, use&nbsp;<span style="font-style: italic;">if (dcmireg == 0x00)</span> instead of&nbsp;<span style="font-style: italic;">if (dcmireg == 0x01)</span></span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_pwr.c</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">PWR_PVDLevelConfig()</span>
+function: remove value of the voltage threshold corresponding to each
+PVD detection level, user should refer to the electrical
+characteristics of the STM32 device&nbsp;datasheet to have the correct
+value</span></li></ul></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 176px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.1 / 28-December-2011<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">All source files: update disclaimer to add reference to the&nbsp;new license agreement</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_rtc.c:&nbsp;</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">In <span style="font-style: italic;">“RTC_FLAGS_MASK”</span> define: add <span style="font-style: italic;">RTC_FLAG_RECALPF</span> and <span style="font-style: italic;">RTC_FLAG_SHPF</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">RTC_DeInit()</span> function: add reset of the following registers:&nbsp;<span style="font-style: italic;">SHIFTR</span>,&nbsp;<span style="font-style: italic;">CALR</span>,&nbsp;<span style="font-style: italic;">ALRMASSR</span> and&nbsp;<span style="font-style: italic;">ALRMBSSR</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">RTC_SetTime()</span> and <span style="font-style: italic;">RTC_SetDate()</span>&nbsp;functions: add test condition on </span><span style="font-size: 10pt; font-family: Verdana;">BYPSHAD flag before to test RSF flag </span><span style="font-size: 10pt; font-family: Verdana;">(when Bypass mode is enabled, the RSF bit is never set).<br><br></span></li></ul></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 198px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0 / 30-September-2011</span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">First official release for&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;">STM32F40x/41x</span> devices</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_rtc.c: remove useless code from <span style="font-style: italic;">RTC_GetDate()</span> function<br></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_rcc.c, stm32f4xx_spi.c, stm32f4xx_wwdg.c and stm32f4xx_syscfg.c: </span><span style="font-size: 10pt; font-family: Verdana;">driver's comments update</span></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 198px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0RC2 / 26-September-2011</span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Official version (V1.0.0) Release Candidate1<span style="font-weight: bold; font-style: italic;"> </span></span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;"> </span><span style="font-style: italic;">for</span><span style="font-weight: bold; font-style: italic;"> STM32F40x/</span></span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;">STM32F41x</span></span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;"> devices</span></span><span style="font-size: 10pt; font-family: Verdana;"></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_usart.h/.c</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Update procedure to check on&nbsp;overrun error interrupt pending bit, defines for the following flag are added:</span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">USART_IT_ORE_RX:</span> this flag is set if&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">overrun error interrupt</span><span style="font-size: 10pt; font-family: Verdana;"> occurs and&nbsp;RXNEIE bit is set</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">USART_IT_ORE_ER:</span> </span><span style="font-size: 10pt; font-family: Verdana;">this flag is&nbsp;set if&nbsp;</span><span style="font-size: 10pt; font-family: Verdana;">overrun error interrupt</span><span style="font-size: 10pt; font-family: Verdana;"> occurs and EIE bit is set</span></li></ul></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_tim.c</span><span style="font-size: 10pt; font-family: Verdana;"></span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">TIM_UpdateRequestConfig():&nbsp;</span>correct function header's comment&nbsp;</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;"><span style="font-style: italic;">TIM_ICInit(): </span>add&nbsp;assert macros to test&nbsp;if the passed TIM parameter has channel 2, 3 or 4</span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_pwr.h/.c</span><span style="font-size: 10pt; font-family: Verdana;"></span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Rename&nbsp;<span style="font-style: italic;">PWR_FLAG_REGRDY</span> constant to <span style="font-style: italic;">PWR_CSR_REGRDY</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Rename&nbsp;<span style="font-style: italic;">PWR_FLAG_VOSRDY </span></span><span style="font-size: 10pt; font-family: Verdana;">constant </span><span style="font-size: 10pt; font-family: Verdana;">to <span style="font-style: italic;">PWR_CSR_VOSRDY</span></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Rename<span style="font-style: italic;"> PWR_HighPerformanceModeCmd(FunctionalState NewState) </span>function to<span style="font-style: italic;"> PWR_MainRegulatorModeConfig(uint32_t PWR_Regulator_Voltage)<br></span></span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_rcc.h/.c</span><span style="font-size: 10pt; font-family: Verdana;"></span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">RCC_AHB1PeriphClockCmd(): add new constant <span style="font-style: italic;">RCC_AHB1Periph_CCMDATARAMEN </span>as value for<span style="font-style: italic;"> RCC_AHB1Periph </span>parameter</span></li></ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">stm32f4xx_spi.h</span><span style="font-size: 10pt; font-family: Verdana;"></span></li><ul><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">IS_I2S_EXT_PERIPH(): add check on&nbsp;<span style="font-style: italic;">I2S3ext</span> peripheral</span></li></ul></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 200px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0RC1 / 25-August-2011<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Official version (V1.0.0) Release Candidate1<span style="font-weight: bold; font-style: italic;"> for STM32F4xx devices</span></span></li></ul>
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="License"></a><span style="font-size: 12pt; color: white;">License<o:p></o:p></span></h2>
+    
+    
+    <p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use this&nbsp;</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">package</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"> except in compliance with the License. You may obtain a copy of the License at:<br><br></span></p><div style="text-align: center;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp; <a target="_blank" href="http://www.st.com/software_license_agreement_liberty_v2">http://www.st.com/software_license_agreement_liberty_v2</a></span><br><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"></span></div><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"><br>Unless
+required by applicable law or agreed to in writing, software
+distributed under the License is distributed on an "AS IS" BASIS, <br>WITHOUT
+WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See
+the License for the specific language governing permissions and
+limitations under the License.</span>
+    <div class="MsoNormal" style="text-align: center;" align="center"><span style="color: black;">
+    <hr align="center" size="2" width="100%">
+    </span></div>
+    <p class="MsoNormal" style="margin: 4.5pt 0in 4.5pt 0.25in; text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">For
+    complete documentation on </span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">STM32<span style="color: black;">
+    Microcontrollers visit </span><u><span style="color: blue;"><a href="http://www.st.com/internet/mcu/family/141.jsp" target="_blank">www.st.com/STM32</a></span></u></span><span style="color: black;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+  </tbody></table>
+  <p class="MsoNormal"><span style="font-size: 10pt;"><o:p></o:p></span></p>
+  </td>
+ </tr>
+</tbody></table>
+
+</div>
+
+<p class="MsoNormal"><o:p>&nbsp;</o:p></p>
+
+</div>
+
+</body></html>
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h
new file mode 100644
index 0000000000000000000000000000000000000000..9f5fe7acce4ccedf92efaae32a9e3a48c5a4d023
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_adc.h
@@ -0,0 +1,656 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_adc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the ADC firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_ADC_H
+#define __STM32F4xx_ADC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup ADC
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief   ADC Init structure definition  
+  */ 
+typedef struct
+{
+  uint32_t ADC_Resolution;                /*!< Configures the ADC resolution dual mode. 
+                                               This parameter can be a value of @ref ADC_resolution */                                   
+  FunctionalState ADC_ScanConvMode;       /*!< Specifies whether the conversion 
+                                               is performed in Scan (multichannels) 
+                                               or Single (one channel) mode.
+                                               This parameter can be set to ENABLE or DISABLE */ 
+  FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion 
+                                               is performed in Continuous or Single mode.
+                                               This parameter can be set to ENABLE or DISABLE. */
+  uint32_t ADC_ExternalTrigConvEdge;      /*!< Select the external trigger edge and
+                                               enable the trigger of a regular group. 
+                                               This parameter can be a value of 
+                                               @ref ADC_external_trigger_edge_for_regular_channels_conversion */
+  uint32_t ADC_ExternalTrigConv;          /*!< Select the external event used to trigger 
+                                               the start of conversion of a regular group.
+                                               This parameter can be a value of 
+                                               @ref ADC_extrenal_trigger_sources_for_regular_channels_conversion */
+  uint32_t ADC_DataAlign;                 /*!< Specifies whether the ADC data  alignment
+                                               is left or right. This parameter can be 
+                                               a value of @ref ADC_data_align */
+  uint8_t  ADC_NbrOfConversion;           /*!< Specifies the number of ADC conversions
+                                               that will be done using the sequencer for
+                                               regular channel group.
+                                               This parameter must range from 1 to 16. */
+}ADC_InitTypeDef;
+  
+/** 
+  * @brief   ADC Common Init structure definition  
+  */ 
+typedef struct 
+{
+  uint32_t ADC_Mode;                      /*!< Configures the ADC to operate in 
+                                               independent or multi mode. 
+                                               This parameter can be a value of @ref ADC_Common_mode */                                              
+  uint32_t ADC_Prescaler;                 /*!< Select the frequency of the clock 
+                                               to the ADC. The clock is common for all the ADCs.
+                                               This parameter can be a value of @ref ADC_Prescaler */
+  uint32_t ADC_DMAAccessMode;             /*!< Configures the Direct memory access 
+                                              mode for multi ADC mode.
+                                               This parameter can be a value of 
+                                               @ref ADC_Direct_memory_access_mode_for_multi_mode */
+  uint32_t ADC_TwoSamplingDelay;          /*!< Configures the Delay between 2 sampling phases.
+                                               This parameter can be a value of 
+                                               @ref ADC_delay_between_2_sampling_phases */
+  
+}ADC_CommonInitTypeDef;
+
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup ADC_Exported_Constants
+  * @{
+  */ 
+#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \
+                                   ((PERIPH) == ADC2) || \
+                                   ((PERIPH) == ADC3))  
+
+/** @defgroup ADC_Common_mode 
+  * @{
+  */ 
+#define ADC_Mode_Independent                       ((uint32_t)0x00000000)       
+#define ADC_DualMode_RegSimult_InjecSimult         ((uint32_t)0x00000001)
+#define ADC_DualMode_RegSimult_AlterTrig           ((uint32_t)0x00000002)
+#define ADC_DualMode_InjecSimult                   ((uint32_t)0x00000005)
+#define ADC_DualMode_RegSimult                     ((uint32_t)0x00000006)
+#define ADC_DualMode_Interl                        ((uint32_t)0x00000007)
+#define ADC_DualMode_AlterTrig                     ((uint32_t)0x00000009)
+#define ADC_TripleMode_RegSimult_InjecSimult       ((uint32_t)0x00000011)
+#define ADC_TripleMode_RegSimult_AlterTrig         ((uint32_t)0x00000012)
+#define ADC_TripleMode_InjecSimult                 ((uint32_t)0x00000015)
+#define ADC_TripleMode_RegSimult                   ((uint32_t)0x00000016)
+#define ADC_TripleMode_Interl                      ((uint32_t)0x00000017)
+#define ADC_TripleMode_AlterTrig                   ((uint32_t)0x00000019)
+#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \
+                           ((MODE) == ADC_DualMode_RegSimult_InjecSimult) || \
+                           ((MODE) == ADC_DualMode_RegSimult_AlterTrig) || \
+                           ((MODE) == ADC_DualMode_InjecSimult) || \
+                           ((MODE) == ADC_DualMode_RegSimult) || \
+                           ((MODE) == ADC_DualMode_Interl) || \
+                           ((MODE) == ADC_DualMode_AlterTrig) || \
+                           ((MODE) == ADC_TripleMode_RegSimult_InjecSimult) || \
+                           ((MODE) == ADC_TripleMode_RegSimult_AlterTrig) || \
+                           ((MODE) == ADC_TripleMode_InjecSimult) || \
+                           ((MODE) == ADC_TripleMode_RegSimult) || \
+                           ((MODE) == ADC_TripleMode_Interl) || \
+                           ((MODE) == ADC_TripleMode_AlterTrig))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_Prescaler 
+  * @{
+  */ 
+#define ADC_Prescaler_Div2                         ((uint32_t)0x00000000)
+#define ADC_Prescaler_Div4                         ((uint32_t)0x00010000)
+#define ADC_Prescaler_Div6                         ((uint32_t)0x00020000)
+#define ADC_Prescaler_Div8                         ((uint32_t)0x00030000)
+#define IS_ADC_PRESCALER(PRESCALER) (((PRESCALER) == ADC_Prescaler_Div2) || \
+                                     ((PRESCALER) == ADC_Prescaler_Div4) || \
+                                     ((PRESCALER) == ADC_Prescaler_Div6) || \
+                                     ((PRESCALER) == ADC_Prescaler_Div8))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_Direct_memory_access_mode_for_multi_mode 
+  * @{
+  */ 
+#define ADC_DMAAccessMode_Disabled      ((uint32_t)0x00000000)     /* DMA mode disabled */
+#define ADC_DMAAccessMode_1             ((uint32_t)0x00004000)     /* DMA mode 1 enabled (2 / 3 half-words one by one - 1 then 2 then 3)*/
+#define ADC_DMAAccessMode_2             ((uint32_t)0x00008000)     /* DMA mode 2 enabled (2 / 3 half-words by pairs - 2&1 then 1&3 then 3&2)*/
+#define ADC_DMAAccessMode_3             ((uint32_t)0x0000C000)     /* DMA mode 3 enabled (2 / 3 bytes by pairs - 2&1 then 1&3 then 3&2) */
+#define IS_ADC_DMA_ACCESS_MODE(MODE) (((MODE) == ADC_DMAAccessMode_Disabled) || \
+                                      ((MODE) == ADC_DMAAccessMode_1) || \
+                                      ((MODE) == ADC_DMAAccessMode_2) || \
+                                      ((MODE) == ADC_DMAAccessMode_3))
+                                     
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_delay_between_2_sampling_phases 
+  * @{
+  */ 
+#define ADC_TwoSamplingDelay_5Cycles               ((uint32_t)0x00000000)
+#define ADC_TwoSamplingDelay_6Cycles               ((uint32_t)0x00000100)
+#define ADC_TwoSamplingDelay_7Cycles               ((uint32_t)0x00000200)
+#define ADC_TwoSamplingDelay_8Cycles               ((uint32_t)0x00000300)
+#define ADC_TwoSamplingDelay_9Cycles               ((uint32_t)0x00000400)
+#define ADC_TwoSamplingDelay_10Cycles              ((uint32_t)0x00000500)
+#define ADC_TwoSamplingDelay_11Cycles              ((uint32_t)0x00000600)
+#define ADC_TwoSamplingDelay_12Cycles              ((uint32_t)0x00000700)
+#define ADC_TwoSamplingDelay_13Cycles              ((uint32_t)0x00000800)
+#define ADC_TwoSamplingDelay_14Cycles              ((uint32_t)0x00000900)
+#define ADC_TwoSamplingDelay_15Cycles              ((uint32_t)0x00000A00)
+#define ADC_TwoSamplingDelay_16Cycles              ((uint32_t)0x00000B00)
+#define ADC_TwoSamplingDelay_17Cycles              ((uint32_t)0x00000C00)
+#define ADC_TwoSamplingDelay_18Cycles              ((uint32_t)0x00000D00)
+#define ADC_TwoSamplingDelay_19Cycles              ((uint32_t)0x00000E00)
+#define ADC_TwoSamplingDelay_20Cycles              ((uint32_t)0x00000F00)
+#define IS_ADC_SAMPLING_DELAY(DELAY) (((DELAY) == ADC_TwoSamplingDelay_5Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_6Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_7Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_8Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_9Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_10Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_11Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_12Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_13Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_14Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_15Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_16Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_17Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_18Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_19Cycles) || \
+                                      ((DELAY) == ADC_TwoSamplingDelay_20Cycles))
+                                     
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_resolution 
+  * @{
+  */ 
+#define ADC_Resolution_12b                         ((uint32_t)0x00000000)
+#define ADC_Resolution_10b                         ((uint32_t)0x01000000)
+#define ADC_Resolution_8b                          ((uint32_t)0x02000000)
+#define ADC_Resolution_6b                          ((uint32_t)0x03000000)
+#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_Resolution_12b) || \
+                                       ((RESOLUTION) == ADC_Resolution_10b) || \
+                                       ((RESOLUTION) == ADC_Resolution_8b) || \
+                                       ((RESOLUTION) == ADC_Resolution_6b))
+                                      
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_external_trigger_edge_for_regular_channels_conversion 
+  * @{
+  */ 
+#define ADC_ExternalTrigConvEdge_None          ((uint32_t)0x00000000)
+#define ADC_ExternalTrigConvEdge_Rising        ((uint32_t)0x10000000)
+#define ADC_ExternalTrigConvEdge_Falling       ((uint32_t)0x20000000)
+#define ADC_ExternalTrigConvEdge_RisingFalling ((uint32_t)0x30000000)
+#define IS_ADC_EXT_TRIG_EDGE(EDGE) (((EDGE) == ADC_ExternalTrigConvEdge_None) || \
+                             ((EDGE) == ADC_ExternalTrigConvEdge_Rising) || \
+                             ((EDGE) == ADC_ExternalTrigConvEdge_Falling) || \
+                             ((EDGE) == ADC_ExternalTrigConvEdge_RisingFalling))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_extrenal_trigger_sources_for_regular_channels_conversion 
+  * @{
+  */ 
+#define ADC_ExternalTrigConv_T1_CC1                ((uint32_t)0x00000000)
+#define ADC_ExternalTrigConv_T1_CC2                ((uint32_t)0x01000000)
+#define ADC_ExternalTrigConv_T1_CC3                ((uint32_t)0x02000000)
+#define ADC_ExternalTrigConv_T2_CC2                ((uint32_t)0x03000000)
+#define ADC_ExternalTrigConv_T2_CC3                ((uint32_t)0x04000000)
+#define ADC_ExternalTrigConv_T2_CC4                ((uint32_t)0x05000000)
+#define ADC_ExternalTrigConv_T2_TRGO               ((uint32_t)0x06000000)
+#define ADC_ExternalTrigConv_T3_CC1                ((uint32_t)0x07000000)
+#define ADC_ExternalTrigConv_T3_TRGO               ((uint32_t)0x08000000)
+#define ADC_ExternalTrigConv_T4_CC4                ((uint32_t)0x09000000)
+#define ADC_ExternalTrigConv_T5_CC1                ((uint32_t)0x0A000000)
+#define ADC_ExternalTrigConv_T5_CC2                ((uint32_t)0x0B000000)
+#define ADC_ExternalTrigConv_T5_CC3                ((uint32_t)0x0C000000)
+#define ADC_ExternalTrigConv_T8_CC1                ((uint32_t)0x0D000000)
+#define ADC_ExternalTrigConv_T8_TRGO               ((uint32_t)0x0E000000)
+#define ADC_ExternalTrigConv_Ext_IT11              ((uint32_t)0x0F000000)
+#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T2_CC4) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T2_TRGO) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T5_CC2) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \
+                                  ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_data_align 
+  * @{
+  */ 
+#define ADC_DataAlign_Right                        ((uint32_t)0x00000000)
+#define ADC_DataAlign_Left                         ((uint32_t)0x00000800)
+#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \
+                                  ((ALIGN) == ADC_DataAlign_Left))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_channels 
+  * @{
+  */ 
+#define ADC_Channel_0                               ((uint8_t)0x00)
+#define ADC_Channel_1                               ((uint8_t)0x01)
+#define ADC_Channel_2                               ((uint8_t)0x02)
+#define ADC_Channel_3                               ((uint8_t)0x03)
+#define ADC_Channel_4                               ((uint8_t)0x04)
+#define ADC_Channel_5                               ((uint8_t)0x05)
+#define ADC_Channel_6                               ((uint8_t)0x06)
+#define ADC_Channel_7                               ((uint8_t)0x07)
+#define ADC_Channel_8                               ((uint8_t)0x08)
+#define ADC_Channel_9                               ((uint8_t)0x09)
+#define ADC_Channel_10                              ((uint8_t)0x0A)
+#define ADC_Channel_11                              ((uint8_t)0x0B)
+#define ADC_Channel_12                              ((uint8_t)0x0C)
+#define ADC_Channel_13                              ((uint8_t)0x0D)
+#define ADC_Channel_14                              ((uint8_t)0x0E)
+#define ADC_Channel_15                              ((uint8_t)0x0F)
+#define ADC_Channel_16                              ((uint8_t)0x10)
+#define ADC_Channel_17                              ((uint8_t)0x11)
+#define ADC_Channel_18                              ((uint8_t)0x12)
+
+#if defined (STM32F40_41xxx)
+#define ADC_Channel_TempSensor                      ((uint8_t)ADC_Channel_16)
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx) || defined (STM32F401xx)
+#define ADC_Channel_TempSensor                      ((uint8_t)ADC_Channel_18)
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F401xx */
+
+#define ADC_Channel_Vrefint                         ((uint8_t)ADC_Channel_17)
+#define ADC_Channel_Vbat                            ((uint8_t)ADC_Channel_18)
+
+#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || \
+                                 ((CHANNEL) == ADC_Channel_1) || \
+                                 ((CHANNEL) == ADC_Channel_2) || \
+                                 ((CHANNEL) == ADC_Channel_3) || \
+                                 ((CHANNEL) == ADC_Channel_4) || \
+                                 ((CHANNEL) == ADC_Channel_5) || \
+                                 ((CHANNEL) == ADC_Channel_6) || \
+                                 ((CHANNEL) == ADC_Channel_7) || \
+                                 ((CHANNEL) == ADC_Channel_8) || \
+                                 ((CHANNEL) == ADC_Channel_9) || \
+                                 ((CHANNEL) == ADC_Channel_10) || \
+                                 ((CHANNEL) == ADC_Channel_11) || \
+                                 ((CHANNEL) == ADC_Channel_12) || \
+                                 ((CHANNEL) == ADC_Channel_13) || \
+                                 ((CHANNEL) == ADC_Channel_14) || \
+                                 ((CHANNEL) == ADC_Channel_15) || \
+                                 ((CHANNEL) == ADC_Channel_16) || \
+                                 ((CHANNEL) == ADC_Channel_17) || \
+                                 ((CHANNEL) == ADC_Channel_18))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_sampling_times 
+  * @{
+  */ 
+#define ADC_SampleTime_3Cycles                    ((uint8_t)0x00)
+#define ADC_SampleTime_15Cycles                   ((uint8_t)0x01)
+#define ADC_SampleTime_28Cycles                   ((uint8_t)0x02)
+#define ADC_SampleTime_56Cycles                   ((uint8_t)0x03)
+#define ADC_SampleTime_84Cycles                   ((uint8_t)0x04)
+#define ADC_SampleTime_112Cycles                  ((uint8_t)0x05)
+#define ADC_SampleTime_144Cycles                  ((uint8_t)0x06)
+#define ADC_SampleTime_480Cycles                  ((uint8_t)0x07)
+#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_3Cycles) || \
+                                  ((TIME) == ADC_SampleTime_15Cycles) || \
+                                  ((TIME) == ADC_SampleTime_28Cycles) || \
+                                  ((TIME) == ADC_SampleTime_56Cycles) || \
+                                  ((TIME) == ADC_SampleTime_84Cycles) || \
+                                  ((TIME) == ADC_SampleTime_112Cycles) || \
+                                  ((TIME) == ADC_SampleTime_144Cycles) || \
+                                  ((TIME) == ADC_SampleTime_480Cycles))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_external_trigger_edge_for_injected_channels_conversion 
+  * @{
+  */ 
+#define ADC_ExternalTrigInjecConvEdge_None          ((uint32_t)0x00000000)
+#define ADC_ExternalTrigInjecConvEdge_Rising        ((uint32_t)0x00100000)
+#define ADC_ExternalTrigInjecConvEdge_Falling       ((uint32_t)0x00200000)
+#define ADC_ExternalTrigInjecConvEdge_RisingFalling ((uint32_t)0x00300000)
+#define IS_ADC_EXT_INJEC_TRIG_EDGE(EDGE) (((EDGE) == ADC_ExternalTrigInjecConvEdge_None) || \
+                                          ((EDGE) == ADC_ExternalTrigInjecConvEdge_Rising) || \
+                                          ((EDGE) == ADC_ExternalTrigInjecConvEdge_Falling) || \
+                                          ((EDGE) == ADC_ExternalTrigInjecConvEdge_RisingFalling))
+                                            
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_extrenal_trigger_sources_for_injected_channels_conversion 
+  * @{
+  */ 
+#define ADC_ExternalTrigInjecConv_T1_CC4            ((uint32_t)0x00000000)
+#define ADC_ExternalTrigInjecConv_T1_TRGO           ((uint32_t)0x00010000)
+#define ADC_ExternalTrigInjecConv_T2_CC1            ((uint32_t)0x00020000)
+#define ADC_ExternalTrigInjecConv_T2_TRGO           ((uint32_t)0x00030000)
+#define ADC_ExternalTrigInjecConv_T3_CC2            ((uint32_t)0x00040000)
+#define ADC_ExternalTrigInjecConv_T3_CC4            ((uint32_t)0x00050000)
+#define ADC_ExternalTrigInjecConv_T4_CC1            ((uint32_t)0x00060000)
+#define ADC_ExternalTrigInjecConv_T4_CC2            ((uint32_t)0x00070000)
+#define ADC_ExternalTrigInjecConv_T4_CC3            ((uint32_t)0x00080000)
+#define ADC_ExternalTrigInjecConv_T4_TRGO           ((uint32_t)0x00090000)
+#define ADC_ExternalTrigInjecConv_T5_CC4            ((uint32_t)0x000A0000)
+#define ADC_ExternalTrigInjecConv_T5_TRGO           ((uint32_t)0x000B0000)
+#define ADC_ExternalTrigInjecConv_T8_CC2            ((uint32_t)0x000C0000)
+#define ADC_ExternalTrigInjecConv_T8_CC3            ((uint32_t)0x000D0000)
+#define ADC_ExternalTrigInjecConv_T8_CC4            ((uint32_t)0x000E0000)
+#define ADC_ExternalTrigInjecConv_Ext_IT15          ((uint32_t)0x000F0000)
+#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC2) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC1) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC2) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC3) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \
+                                        ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_injected_channel_selection 
+  * @{
+  */ 
+#define ADC_InjectedChannel_1                       ((uint8_t)0x14)
+#define ADC_InjectedChannel_2                       ((uint8_t)0x18)
+#define ADC_InjectedChannel_3                       ((uint8_t)0x1C)
+#define ADC_InjectedChannel_4                       ((uint8_t)0x20)
+#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \
+                                          ((CHANNEL) == ADC_InjectedChannel_2) || \
+                                          ((CHANNEL) == ADC_InjectedChannel_3) || \
+                                          ((CHANNEL) == ADC_InjectedChannel_4))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_analog_watchdog_selection 
+  * @{
+  */ 
+#define ADC_AnalogWatchdog_SingleRegEnable         ((uint32_t)0x00800200)
+#define ADC_AnalogWatchdog_SingleInjecEnable       ((uint32_t)0x00400200)
+#define ADC_AnalogWatchdog_SingleRegOrInjecEnable  ((uint32_t)0x00C00200)
+#define ADC_AnalogWatchdog_AllRegEnable            ((uint32_t)0x00800000)
+#define ADC_AnalogWatchdog_AllInjecEnable          ((uint32_t)0x00400000)
+#define ADC_AnalogWatchdog_AllRegAllInjecEnable    ((uint32_t)0x00C00000)
+#define ADC_AnalogWatchdog_None                    ((uint32_t)0x00000000)
+#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \
+                                          ((WATCHDOG) == ADC_AnalogWatchdog_None))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_interrupts_definition 
+  * @{
+  */ 
+#define ADC_IT_EOC                                 ((uint16_t)0x0205)  
+#define ADC_IT_AWD                                 ((uint16_t)0x0106)  
+#define ADC_IT_JEOC                                ((uint16_t)0x0407)  
+#define ADC_IT_OVR                                 ((uint16_t)0x201A)  
+#define IS_ADC_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \
+                       ((IT) == ADC_IT_JEOC)|| ((IT) == ADC_IT_OVR)) 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_flags_definition 
+  * @{
+  */ 
+#define ADC_FLAG_AWD                               ((uint8_t)0x01)
+#define ADC_FLAG_EOC                               ((uint8_t)0x02)
+#define ADC_FLAG_JEOC                              ((uint8_t)0x04)
+#define ADC_FLAG_JSTRT                             ((uint8_t)0x08)
+#define ADC_FLAG_STRT                              ((uint8_t)0x10)
+#define ADC_FLAG_OVR                               ((uint8_t)0x20)   
+  
+#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xC0) == 0x00) && ((FLAG) != 0x00))   
+#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || \
+                               ((FLAG) == ADC_FLAG_EOC) || \
+                               ((FLAG) == ADC_FLAG_JEOC) || \
+                               ((FLAG)== ADC_FLAG_JSTRT) || \
+                               ((FLAG) == ADC_FLAG_STRT) || \
+                               ((FLAG)== ADC_FLAG_OVR))     
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_thresholds 
+  * @{
+  */ 
+#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF)
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_injected_offset 
+  * @{
+  */ 
+#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF)
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_injected_length 
+  * @{
+  */ 
+#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_injected_rank 
+  * @{
+  */ 
+#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_regular_length 
+  * @{
+  */ 
+#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_regular_rank 
+  * @{
+  */ 
+#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup ADC_regular_discontinuous_mode_number 
+  * @{
+  */ 
+#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8))
+/**
+  * @}
+  */ 
+
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/  
+
+/*  Function used to set the ADC configuration to the default reset state *****/  
+void ADC_DeInit(void);
+
+/* Initialization and Configuration functions *********************************/
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct);
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct);
+void ADC_CommonInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct);
+void ADC_CommonStructInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct);
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+
+/* Analog Watchdog configuration functions ************************************/
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog);
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold,uint16_t LowThreshold);
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel);
+
+/* Temperature Sensor, Vrefint and VBAT management functions ******************/
+void ADC_TempSensorVrefintCmd(FunctionalState NewState);
+void ADC_VBATCmd(FunctionalState NewState);
+
+/* Regular Channels Configuration functions ***********************************/
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
+void ADC_SoftwareStartConv(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx);
+void ADC_EOCOnEachRegularChannelCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_ContinuousModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number);
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx);
+uint32_t ADC_GetMultiModeConversionValue(void);
+
+/* Regular Channels DMA Configuration functions *******************************/
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_DMARequestAfterLastTransferCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_MultiModeDMARequestAfterLastTransferCmd(FunctionalState NewState);
+
+/* Injected channels Configuration functions **********************************/
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime);
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length);
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset);
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv);
+void ADC_ExternalTrigInjectedConvEdgeConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConvEdge);
+void ADC_SoftwareStartInjectedConv(ADC_TypeDef* ADCx);
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx);
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState);
+uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel);
+
+/* Interrupts and flags management functions **********************************/
+void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState);
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
+void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG);
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT);
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_ADC_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h
new file mode 100644
index 0000000000000000000000000000000000000000..cc3c50bde784194dd640fcc21fcf8bf3e73cca27
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_can.h
@@ -0,0 +1,644 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_can.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the CAN firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_CAN_H
+#define __STM32F4xx_CAN_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup CAN
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \
+                                   ((PERIPH) == CAN2))
+
+/** 
+  * @brief  CAN init structure definition
+  */
+typedef struct
+{
+  uint16_t CAN_Prescaler;   /*!< Specifies the length of a time quantum. 
+                                 It ranges from 1 to 1024. */
+  
+  uint8_t CAN_Mode;         /*!< Specifies the CAN operating mode.
+                                 This parameter can be a value of @ref CAN_operating_mode */
+
+  uint8_t CAN_SJW;          /*!< Specifies the maximum number of time quanta 
+                                 the CAN hardware is allowed to lengthen or 
+                                 shorten a bit to perform resynchronization.
+                                 This parameter can be a value of @ref CAN_synchronisation_jump_width */
+
+  uint8_t CAN_BS1;          /*!< Specifies the number of time quanta in Bit 
+                                 Segment 1. This parameter can be a value of 
+                                 @ref CAN_time_quantum_in_bit_segment_1 */
+
+  uint8_t CAN_BS2;          /*!< Specifies the number of time quanta in Bit Segment 2.
+                                 This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */
+  
+  FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered communication mode.
+                                This parameter can be set either to ENABLE or DISABLE. */
+  
+  FunctionalState CAN_ABOM;  /*!< Enable or disable the automatic bus-off management.
+                                  This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_AWUM;  /*!< Enable or disable the automatic wake-up mode. 
+                                  This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_NART;  /*!< Enable or disable the non-automatic retransmission mode.
+                                  This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_RFLM;  /*!< Enable or disable the Receive FIFO Locked mode.
+                                  This parameter can be set either to ENABLE or DISABLE. */
+
+  FunctionalState CAN_TXFP;  /*!< Enable or disable the transmit FIFO priority.
+                                  This parameter can be set either to ENABLE or DISABLE. */
+} CAN_InitTypeDef;
+
+/** 
+  * @brief  CAN filter init structure definition
+  */
+typedef struct
+{
+  uint16_t CAN_FilterIdHigh;         /*!< Specifies the filter identification number (MSBs for a 32-bit
+                                              configuration, first one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterIdLow;          /*!< Specifies the filter identification number (LSBs for a 32-bit
+                                              configuration, second one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterMaskIdHigh;     /*!< Specifies the filter mask number or identification number,
+                                              according to the mode (MSBs for a 32-bit configuration,
+                                              first one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterMaskIdLow;      /*!< Specifies the filter mask number or identification number,
+                                              according to the mode (LSBs for a 32-bit configuration,
+                                              second one for a 16-bit configuration).
+                                              This parameter can be a value between 0x0000 and 0xFFFF */
+
+  uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter.
+                                              This parameter can be a value of @ref CAN_filter_FIFO */
+  
+  uint8_t CAN_FilterNumber;          /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */
+
+  uint8_t CAN_FilterMode;            /*!< Specifies the filter mode to be initialized.
+                                              This parameter can be a value of @ref CAN_filter_mode */
+
+  uint8_t CAN_FilterScale;           /*!< Specifies the filter scale.
+                                              This parameter can be a value of @ref CAN_filter_scale */
+
+  FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter.
+                                              This parameter can be set either to ENABLE or DISABLE. */
+} CAN_FilterInitTypeDef;
+
+/** 
+  * @brief  CAN Tx message structure definition  
+  */
+typedef struct
+{
+  uint32_t StdId;  /*!< Specifies the standard identifier.
+                        This parameter can be a value between 0 to 0x7FF. */
+
+  uint32_t ExtId;  /*!< Specifies the extended identifier.
+                        This parameter can be a value between 0 to 0x1FFFFFFF. */
+
+  uint8_t IDE;     /*!< Specifies the type of identifier for the message that 
+                        will be transmitted. This parameter can be a value 
+                        of @ref CAN_identifier_type */
+
+  uint8_t RTR;     /*!< Specifies the type of frame for the message that will 
+                        be transmitted. This parameter can be a value of 
+                        @ref CAN_remote_transmission_request */
+
+  uint8_t DLC;     /*!< Specifies the length of the frame that will be 
+                        transmitted. This parameter can be a value between 
+                        0 to 8 */
+
+  uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 
+                        to 0xFF. */
+} CanTxMsg;
+
+/** 
+  * @brief  CAN Rx message structure definition  
+  */
+typedef struct
+{
+  uint32_t StdId;  /*!< Specifies the standard identifier.
+                        This parameter can be a value between 0 to 0x7FF. */
+
+  uint32_t ExtId;  /*!< Specifies the extended identifier.
+                        This parameter can be a value between 0 to 0x1FFFFFFF. */
+
+  uint8_t IDE;     /*!< Specifies the type of identifier for the message that 
+                        will be received. This parameter can be a value of 
+                        @ref CAN_identifier_type */
+
+  uint8_t RTR;     /*!< Specifies the type of frame for the received message.
+                        This parameter can be a value of 
+                        @ref CAN_remote_transmission_request */
+
+  uint8_t DLC;     /*!< Specifies the length of the frame that will be received.
+                        This parameter can be a value between 0 to 8 */
+
+  uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to 
+                        0xFF. */
+
+  uint8_t FMI;     /*!< Specifies the index of the filter the message stored in 
+                        the mailbox passes through. This parameter can be a 
+                        value between 0 to 0xFF */
+} CanRxMsg;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup CAN_Exported_Constants
+  * @{
+  */
+
+/** @defgroup CAN_InitStatus 
+  * @{
+  */
+
+#define CAN_InitStatus_Failed              ((uint8_t)0x00) /*!< CAN initialization failed */
+#define CAN_InitStatus_Success             ((uint8_t)0x01) /*!< CAN initialization OK */
+
+
+/* Legacy defines */
+#define CANINITFAILED    CAN_InitStatus_Failed
+#define CANINITOK        CAN_InitStatus_Success
+/**
+  * @}
+  */
+
+/** @defgroup CAN_operating_mode 
+  * @{
+  */
+
+#define CAN_Mode_Normal             ((uint8_t)0x00)  /*!< normal mode */
+#define CAN_Mode_LoopBack           ((uint8_t)0x01)  /*!< loopback mode */
+#define CAN_Mode_Silent             ((uint8_t)0x02)  /*!< silent mode */
+#define CAN_Mode_Silent_LoopBack    ((uint8_t)0x03)  /*!< loopback combined with silent mode */
+
+#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || \
+                           ((MODE) == CAN_Mode_LoopBack)|| \
+                           ((MODE) == CAN_Mode_Silent) || \
+                           ((MODE) == CAN_Mode_Silent_LoopBack))
+/**
+  * @}
+  */
+
+
+ /**
+  * @defgroup CAN_operating_mode 
+  * @{
+  */  
+#define CAN_OperatingMode_Initialization  ((uint8_t)0x00) /*!< Initialization mode */
+#define CAN_OperatingMode_Normal          ((uint8_t)0x01) /*!< Normal mode */
+#define CAN_OperatingMode_Sleep           ((uint8_t)0x02) /*!< sleep mode */
+
+
+#define IS_CAN_OPERATING_MODE(MODE) (((MODE) == CAN_OperatingMode_Initialization) ||\
+                                    ((MODE) == CAN_OperatingMode_Normal)|| \
+																		((MODE) == CAN_OperatingMode_Sleep))
+/**
+  * @}
+  */
+  
+/**
+  * @defgroup CAN_operating_mode_status
+  * @{
+  */  
+
+#define CAN_ModeStatus_Failed    ((uint8_t)0x00)                /*!< CAN entering the specific mode failed */
+#define CAN_ModeStatus_Success   ((uint8_t)!CAN_ModeStatus_Failed)   /*!< CAN entering the specific mode Succeed */
+/**
+  * @}
+  */
+
+/** @defgroup CAN_synchronisation_jump_width 
+  * @{
+  */
+#define CAN_SJW_1tq                 ((uint8_t)0x00)  /*!< 1 time quantum */
+#define CAN_SJW_2tq                 ((uint8_t)0x01)  /*!< 2 time quantum */
+#define CAN_SJW_3tq                 ((uint8_t)0x02)  /*!< 3 time quantum */
+#define CAN_SJW_4tq                 ((uint8_t)0x03)  /*!< 4 time quantum */
+
+#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \
+                         ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_time_quantum_in_bit_segment_1 
+  * @{
+  */
+#define CAN_BS1_1tq                 ((uint8_t)0x00)  /*!< 1 time quantum */
+#define CAN_BS1_2tq                 ((uint8_t)0x01)  /*!< 2 time quantum */
+#define CAN_BS1_3tq                 ((uint8_t)0x02)  /*!< 3 time quantum */
+#define CAN_BS1_4tq                 ((uint8_t)0x03)  /*!< 4 time quantum */
+#define CAN_BS1_5tq                 ((uint8_t)0x04)  /*!< 5 time quantum */
+#define CAN_BS1_6tq                 ((uint8_t)0x05)  /*!< 6 time quantum */
+#define CAN_BS1_7tq                 ((uint8_t)0x06)  /*!< 7 time quantum */
+#define CAN_BS1_8tq                 ((uint8_t)0x07)  /*!< 8 time quantum */
+#define CAN_BS1_9tq                 ((uint8_t)0x08)  /*!< 9 time quantum */
+#define CAN_BS1_10tq                ((uint8_t)0x09)  /*!< 10 time quantum */
+#define CAN_BS1_11tq                ((uint8_t)0x0A)  /*!< 11 time quantum */
+#define CAN_BS1_12tq                ((uint8_t)0x0B)  /*!< 12 time quantum */
+#define CAN_BS1_13tq                ((uint8_t)0x0C)  /*!< 13 time quantum */
+#define CAN_BS1_14tq                ((uint8_t)0x0D)  /*!< 14 time quantum */
+#define CAN_BS1_15tq                ((uint8_t)0x0E)  /*!< 15 time quantum */
+#define CAN_BS1_16tq                ((uint8_t)0x0F)  /*!< 16 time quantum */
+
+#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq)
+/**
+  * @}
+  */
+
+/** @defgroup CAN_time_quantum_in_bit_segment_2 
+  * @{
+  */
+#define CAN_BS2_1tq                 ((uint8_t)0x00)  /*!< 1 time quantum */
+#define CAN_BS2_2tq                 ((uint8_t)0x01)  /*!< 2 time quantum */
+#define CAN_BS2_3tq                 ((uint8_t)0x02)  /*!< 3 time quantum */
+#define CAN_BS2_4tq                 ((uint8_t)0x03)  /*!< 4 time quantum */
+#define CAN_BS2_5tq                 ((uint8_t)0x04)  /*!< 5 time quantum */
+#define CAN_BS2_6tq                 ((uint8_t)0x05)  /*!< 6 time quantum */
+#define CAN_BS2_7tq                 ((uint8_t)0x06)  /*!< 7 time quantum */
+#define CAN_BS2_8tq                 ((uint8_t)0x07)  /*!< 8 time quantum */
+
+#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq)
+/**
+  * @}
+  */
+
+/** @defgroup CAN_clock_prescaler 
+  * @{
+  */
+#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_number 
+  * @{
+  */
+#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27)
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_mode 
+  * @{
+  */
+#define CAN_FilterMode_IdMask       ((uint8_t)0x00)  /*!< identifier/mask mode */
+#define CAN_FilterMode_IdList       ((uint8_t)0x01)  /*!< identifier list mode */
+
+#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \
+                                  ((MODE) == CAN_FilterMode_IdList))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_scale 
+  * @{
+  */
+#define CAN_FilterScale_16bit       ((uint8_t)0x00) /*!< Two 16-bit filters */
+#define CAN_FilterScale_32bit       ((uint8_t)0x01) /*!< One 32-bit filter */
+
+#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \
+                                    ((SCALE) == CAN_FilterScale_32bit))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_filter_FIFO
+  * @{
+  */
+#define CAN_Filter_FIFO0             ((uint8_t)0x00)  /*!< Filter FIFO 0 assignment for filter x */
+#define CAN_Filter_FIFO1             ((uint8_t)0x01)  /*!< Filter FIFO 1 assignment for filter x */
+#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \
+                                  ((FIFO) == CAN_FilterFIFO1))
+
+/* Legacy defines */
+#define CAN_FilterFIFO0  CAN_Filter_FIFO0
+#define CAN_FilterFIFO1  CAN_Filter_FIFO1
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Start_bank_filter_for_slave_CAN 
+  * @{
+  */
+#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Tx 
+  * @{
+  */
+#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02))
+#define IS_CAN_STDID(STDID)   ((STDID) <= ((uint32_t)0x7FF))
+#define IS_CAN_EXTID(EXTID)   ((EXTID) <= ((uint32_t)0x1FFFFFFF))
+#define IS_CAN_DLC(DLC)       ((DLC) <= ((uint8_t)0x08))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_identifier_type 
+  * @{
+  */
+#define CAN_Id_Standard             ((uint32_t)0x00000000)  /*!< Standard Id */
+#define CAN_Id_Extended             ((uint32_t)0x00000004)  /*!< Extended Id */
+#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_Id_Standard) || \
+                               ((IDTYPE) == CAN_Id_Extended))
+
+/* Legacy defines */
+#define CAN_ID_STD      CAN_Id_Standard           
+#define CAN_ID_EXT      CAN_Id_Extended
+/**
+  * @}
+  */
+
+/** @defgroup CAN_remote_transmission_request 
+  * @{
+  */
+#define CAN_RTR_Data                ((uint32_t)0x00000000)  /*!< Data frame */
+#define CAN_RTR_Remote              ((uint32_t)0x00000002)  /*!< Remote frame */
+#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_Data) || ((RTR) == CAN_RTR_Remote))
+
+/* Legacy defines */
+#define CAN_RTR_DATA     CAN_RTR_Data         
+#define CAN_RTR_REMOTE   CAN_RTR_Remote
+/**
+  * @}
+  */
+
+/** @defgroup CAN_transmit_constants 
+  * @{
+  */
+#define CAN_TxStatus_Failed         ((uint8_t)0x00)/*!< CAN transmission failed */
+#define CAN_TxStatus_Ok             ((uint8_t)0x01) /*!< CAN transmission succeeded */
+#define CAN_TxStatus_Pending        ((uint8_t)0x02) /*!< CAN transmission pending */
+#define CAN_TxStatus_NoMailBox      ((uint8_t)0x04) /*!< CAN cell did not provide 
+                                                         an empty mailbox */
+/* Legacy defines */	
+#define CANTXFAILED                  CAN_TxStatus_Failed
+#define CANTXOK                      CAN_TxStatus_Ok
+#define CANTXPENDING                 CAN_TxStatus_Pending
+#define CAN_NO_MB                    CAN_TxStatus_NoMailBox
+/**
+  * @}
+  */
+
+/** @defgroup CAN_receive_FIFO_number_constants 
+  * @{
+  */
+#define CAN_FIFO0                 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */
+#define CAN_FIFO1                 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */
+
+#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1))
+/**
+  * @}
+  */
+
+/** @defgroup CAN_sleep_constants 
+  * @{
+  */
+#define CAN_Sleep_Failed     ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */
+#define CAN_Sleep_Ok         ((uint8_t)0x01) /*!< CAN entered the sleep mode */
+
+/* Legacy defines */	
+#define CANSLEEPFAILED   CAN_Sleep_Failed
+#define CANSLEEPOK       CAN_Sleep_Ok
+/**
+  * @}
+  */
+
+/** @defgroup CAN_wake_up_constants 
+  * @{
+  */
+#define CAN_WakeUp_Failed        ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */
+#define CAN_WakeUp_Ok            ((uint8_t)0x01) /*!< CAN leaved the sleep mode */
+
+/* Legacy defines */
+#define CANWAKEUPFAILED   CAN_WakeUp_Failed        
+#define CANWAKEUPOK       CAN_WakeUp_Ok        
+/**
+  * @}
+  */
+
+/**
+  * @defgroup CAN_Error_Code_constants
+  * @{
+  */                                                         
+#define CAN_ErrorCode_NoErr           ((uint8_t)0x00) /*!< No Error */ 
+#define	CAN_ErrorCode_StuffErr        ((uint8_t)0x10) /*!< Stuff Error */ 
+#define	CAN_ErrorCode_FormErr         ((uint8_t)0x20) /*!< Form Error */ 
+#define	CAN_ErrorCode_ACKErr          ((uint8_t)0x30) /*!< Acknowledgment Error */ 
+#define	CAN_ErrorCode_BitRecessiveErr ((uint8_t)0x40) /*!< Bit Recessive Error */ 
+#define	CAN_ErrorCode_BitDominantErr  ((uint8_t)0x50) /*!< Bit Dominant Error */ 
+#define	CAN_ErrorCode_CRCErr          ((uint8_t)0x60) /*!< CRC Error  */ 
+#define	CAN_ErrorCode_SoftwareSetErr  ((uint8_t)0x70) /*!< Software Set Error */ 
+/**
+  * @}
+  */
+
+/** @defgroup CAN_flags 
+  * @{
+  */
+/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus()
+   and CAN_ClearFlag() functions. */
+/* If the flag is 0x1XXXXXXX, it means that it can only be used with 
+   CAN_GetFlagStatus() function.  */
+
+/* Transmit Flags */
+#define CAN_FLAG_RQCP0             ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */
+#define CAN_FLAG_RQCP1             ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */
+#define CAN_FLAG_RQCP2             ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */
+
+/* Receive Flags */
+#define CAN_FLAG_FMP0              ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */
+#define CAN_FLAG_FF0               ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag            */
+#define CAN_FLAG_FOV0              ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag         */
+#define CAN_FLAG_FMP1              ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */
+#define CAN_FLAG_FF1               ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag            */
+#define CAN_FLAG_FOV1              ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag         */
+
+/* Operating Mode Flags */
+#define CAN_FLAG_WKU               ((uint32_t)0x31000008) /*!< Wake up Flag */
+#define CAN_FLAG_SLAK              ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */
+/* @note When SLAK interrupt is disabled (SLKIE=0), no polling on SLAKI is possible. 
+         In this case the SLAK bit can be polled.*/
+
+/* Error Flags */
+#define CAN_FLAG_EWG               ((uint32_t)0x10F00001) /*!< Error Warning Flag   */
+#define CAN_FLAG_EPV               ((uint32_t)0x10F00002) /*!< Error Passive Flag   */
+#define CAN_FLAG_BOF               ((uint32_t)0x10F00004) /*!< Bus-Off Flag         */
+#define CAN_FLAG_LEC               ((uint32_t)0x30F00070) /*!< Last error code Flag */
+
+#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC)  || ((FLAG) == CAN_FLAG_BOF)   || \
+                               ((FLAG) == CAN_FLAG_EPV)  || ((FLAG) == CAN_FLAG_EWG)   || \
+                               ((FLAG) == CAN_FLAG_WKU)  || ((FLAG) == CAN_FLAG_FOV0)  || \
+                               ((FLAG) == CAN_FLAG_FF0)  || ((FLAG) == CAN_FLAG_FMP0)  || \
+                               ((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1)   || \
+                               ((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \
+                               ((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \
+                               ((FLAG) == CAN_FLAG_SLAK ))
+
+#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \
+                                ((FLAG) == CAN_FLAG_RQCP1)  || ((FLAG) == CAN_FLAG_RQCP0) || \
+                                ((FLAG) == CAN_FLAG_FF0)  || ((FLAG) == CAN_FLAG_FOV0) ||\
+                                ((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \
+                                ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK))
+/**
+  * @}
+  */
+
+  
+/** @defgroup CAN_interrupts 
+  * @{
+  */ 
+#define CAN_IT_TME                  ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/
+
+/* Receive Interrupts */
+#define CAN_IT_FMP0                 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/
+#define CAN_IT_FF0                  ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/
+#define CAN_IT_FOV0                 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/
+#define CAN_IT_FMP1                 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/
+#define CAN_IT_FF1                  ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/
+#define CAN_IT_FOV1                 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/
+
+/* Operating Mode Interrupts */
+#define CAN_IT_WKU                  ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/
+#define CAN_IT_SLK                  ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/
+
+/* Error Interrupts */
+#define CAN_IT_EWG                  ((uint32_t)0x00000100) /*!< Error warning Interrupt*/
+#define CAN_IT_EPV                  ((uint32_t)0x00000200) /*!< Error passive Interrupt*/
+#define CAN_IT_BOF                  ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/
+#define CAN_IT_LEC                  ((uint32_t)0x00000800) /*!< Last error code Interrupt*/
+#define CAN_IT_ERR                  ((uint32_t)0x00008000) /*!< Error Interrupt*/
+
+/* Flags named as Interrupts : kept only for FW compatibility */
+#define CAN_IT_RQCP0   CAN_IT_TME
+#define CAN_IT_RQCP1   CAN_IT_TME
+#define CAN_IT_RQCP2   CAN_IT_TME
+
+
+#define IS_CAN_IT(IT)        (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0)  ||\
+                             ((IT) == CAN_IT_FF0)  || ((IT) == CAN_IT_FOV0)  ||\
+                             ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1)   ||\
+                             ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG)   ||\
+                             ((IT) == CAN_IT_EPV)  || ((IT) == CAN_IT_BOF)   ||\
+                             ((IT) == CAN_IT_LEC)  || ((IT) == CAN_IT_ERR)   ||\
+                             ((IT) == CAN_IT_WKU)  || ((IT) == CAN_IT_SLK))
+
+#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0)    ||\
+                             ((IT) == CAN_IT_FOV0)|| ((IT) == CAN_IT_FF1)    ||\
+                             ((IT) == CAN_IT_FOV1)|| ((IT) == CAN_IT_EWG)    ||\
+                             ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF)    ||\
+                             ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR)    ||\
+                             ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/  
+
+/*  Function used to set the CAN configuration to the default reset state *****/ 
+void CAN_DeInit(CAN_TypeDef* CANx);
+
+/* Initialization and Configuration functions *********************************/ 
+uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct);
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct);
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct);
+void CAN_SlaveStartBank(uint8_t CAN_BankNumber); 
+void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState);
+void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState);
+
+/* CAN Frames Transmission functions ******************************************/
+uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage);
+uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox);
+void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox);
+
+/* CAN Frames Reception functions *********************************************/
+void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage);
+void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber);
+uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber);
+
+/* Operation modes functions **************************************************/
+uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode);
+uint8_t CAN_Sleep(CAN_TypeDef* CANx);
+uint8_t CAN_WakeUp(CAN_TypeDef* CANx);
+
+/* CAN Bus Error management functions *****************************************/
+uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx);
+uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx);
+uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx);
+
+/* Interrupts and flags management functions **********************************/
+void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState);
+FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG);
+void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG);
+ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT);
+void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_CAN_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h
new file mode 100644
index 0000000000000000000000000000000000000000..06c68188a98ccf783a9a066328ff7ca3debe5e3b
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_crc.h
@@ -0,0 +1,83 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_crc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the CRC firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_CRC_H
+#define __STM32F4xx_CRC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup CRC
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup CRC_Exported_Constants
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/  
+
+void CRC_ResetDR(void);
+uint32_t CRC_CalcCRC(uint32_t Data);
+uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength);
+uint32_t CRC_GetCRC(void);
+void CRC_SetIDRegister(uint8_t IDValue);
+uint8_t CRC_GetIDRegister(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_CRC_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h
new file mode 100644
index 0000000000000000000000000000000000000000..d560eea4e140f63a8f77e6981141d02f11d4a516
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_cryp.h
@@ -0,0 +1,384 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_cryp.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the Cryptographic
+  *          processor(CRYP) firmware library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_CRYP_H
+#define __STM32F4xx_CRYP_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup CRYP
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief   CRYP Init structure definition  
+  */ 
+typedef struct
+{
+  uint32_t CRYP_AlgoDir;   /*!< Encrypt or Decrypt. This parameter can be a 
+                                value of @ref CRYP_Algorithm_Direction */
+  uint32_t CRYP_AlgoMode;  /*!< TDES-ECB, TDES-CBC, DES-ECB, DES-CBC, AES-ECB, 
+                                AES-CBC, AES-CTR, AES-Key, AES-GCM and AES-CCM.
+                                This parameter can be a value of @ref CRYP_Algorithm_Mode */
+  uint32_t CRYP_DataType;  /*!< 32-bit data, 16-bit data, bit data or bit string.
+                                This parameter can be a value of @ref CRYP_Data_Type */ 
+  uint32_t CRYP_KeySize;   /*!< Used only in AES mode only : 128, 192 or 256 bit 
+                                key length. This parameter can be a value of 
+                                @ref CRYP_Key_Size_for_AES_only */
+}CRYP_InitTypeDef;
+
+/** 
+  * @brief   CRYP Key(s) structure definition  
+  */ 
+typedef struct
+{
+  uint32_t CRYP_Key0Left;  /*!< Key 0 Left  */
+  uint32_t CRYP_Key0Right; /*!< Key 0 Right */
+  uint32_t CRYP_Key1Left;  /*!< Key 1 left  */
+  uint32_t CRYP_Key1Right; /*!< Key 1 Right */
+  uint32_t CRYP_Key2Left;  /*!< Key 2 left  */
+  uint32_t CRYP_Key2Right; /*!< Key 2 Right */
+  uint32_t CRYP_Key3Left;  /*!< Key 3 left  */
+  uint32_t CRYP_Key3Right; /*!< Key 3 Right */
+}CRYP_KeyInitTypeDef;
+/** 
+  * @brief   CRYP Initialization Vectors (IV) structure definition  
+  */ 
+typedef struct
+{
+  uint32_t CRYP_IV0Left;  /*!< Init Vector 0 Left  */
+  uint32_t CRYP_IV0Right; /*!< Init Vector 0 Right */
+  uint32_t CRYP_IV1Left;  /*!< Init Vector 1 left  */
+  uint32_t CRYP_IV1Right; /*!< Init Vector 1 Right */
+}CRYP_IVInitTypeDef;
+
+/** 
+  * @brief  CRYP context swapping structure definition  
+  */ 
+typedef struct
+{
+  /*!< Current Configuration */
+  uint32_t CR_CurrentConfig;
+  /*!< IV */
+  uint32_t CRYP_IV0LR;
+  uint32_t CRYP_IV0RR;
+  uint32_t CRYP_IV1LR;
+  uint32_t CRYP_IV1RR;
+  /*!< KEY */
+  uint32_t CRYP_K0LR;
+  uint32_t CRYP_K0RR;
+  uint32_t CRYP_K1LR;
+  uint32_t CRYP_K1RR;
+  uint32_t CRYP_K2LR;
+  uint32_t CRYP_K2RR;
+  uint32_t CRYP_K3LR;
+  uint32_t CRYP_K3RR;
+  uint32_t CRYP_CSGCMCCMR[8];
+  uint32_t CRYP_CSGCMR[8];
+}CRYP_Context;
+
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup CRYP_Exported_Constants
+  * @{
+  */
+
+/** @defgroup CRYP_Algorithm_Direction 
+  * @{
+  */
+#define CRYP_AlgoDir_Encrypt      ((uint16_t)0x0000)
+#define CRYP_AlgoDir_Decrypt      ((uint16_t)0x0004)
+#define IS_CRYP_ALGODIR(ALGODIR) (((ALGODIR) == CRYP_AlgoDir_Encrypt) || \
+                                  ((ALGODIR) == CRYP_AlgoDir_Decrypt))
+
+/**
+  * @}
+  */ 
+ 
+/** @defgroup CRYP_Algorithm_Mode 
+  * @{
+  */
+
+/*!< TDES Modes */
+#define CRYP_AlgoMode_TDES_ECB    ((uint32_t)0x00000000)
+#define CRYP_AlgoMode_TDES_CBC    ((uint32_t)0x00000008)
+
+/*!< DES Modes */
+#define CRYP_AlgoMode_DES_ECB     ((uint32_t)0x00000010)
+#define CRYP_AlgoMode_DES_CBC     ((uint32_t)0x00000018)
+
+/*!< AES Modes */
+#define CRYP_AlgoMode_AES_ECB     ((uint32_t)0x00000020)
+#define CRYP_AlgoMode_AES_CBC     ((uint32_t)0x00000028)
+#define CRYP_AlgoMode_AES_CTR     ((uint32_t)0x00000030)
+#define CRYP_AlgoMode_AES_Key     ((uint32_t)0x00000038)
+#define CRYP_AlgoMode_AES_GCM     ((uint32_t)0x00080000)
+#define CRYP_AlgoMode_AES_CCM     ((uint32_t)0x00080008)
+
+#define IS_CRYP_ALGOMODE(ALGOMODE) (((ALGOMODE) == CRYP_AlgoMode_TDES_ECB) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_TDES_CBC)|| \
+                                   ((ALGOMODE) == CRYP_AlgoMode_DES_ECB) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_DES_CBC) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_AES_ECB) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_AES_CBC) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_AES_CTR) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_AES_Key) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_AES_GCM) || \
+                                   ((ALGOMODE) == CRYP_AlgoMode_AES_CCM))
+/**
+  * @}
+  */ 
+
+/** @defgroup CRYP_Phase 
+  * @{
+  */
+
+/*!< The phases are valid only for AES-GCM and AES-CCM modes */
+#define CRYP_Phase_Init           ((uint32_t)0x00000000)
+#define CRYP_Phase_Header         CRYP_CR_GCM_CCMPH_0
+#define CRYP_Phase_Payload        CRYP_CR_GCM_CCMPH_1
+#define CRYP_Phase_Final          CRYP_CR_GCM_CCMPH
+
+#define IS_CRYP_PHASE(PHASE) (((PHASE) == CRYP_Phase_Init)    || \
+                              ((PHASE) == CRYP_Phase_Header)  || \
+                              ((PHASE) == CRYP_Phase_Payload) || \
+                              ((PHASE) == CRYP_Phase_Final))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup CRYP_Data_Type 
+  * @{
+  */
+#define CRYP_DataType_32b         ((uint16_t)0x0000)
+#define CRYP_DataType_16b         ((uint16_t)0x0040)
+#define CRYP_DataType_8b          ((uint16_t)0x0080)
+#define CRYP_DataType_1b          ((uint16_t)0x00C0)
+#define IS_CRYP_DATATYPE(DATATYPE) (((DATATYPE) == CRYP_DataType_32b) || \
+                                    ((DATATYPE) == CRYP_DataType_16b)|| \
+                                    ((DATATYPE) == CRYP_DataType_8b)|| \
+                                    ((DATATYPE) == CRYP_DataType_1b))  
+/**
+  * @}
+  */
+                                     
+/** @defgroup CRYP_Key_Size_for_AES_only 
+  * @{
+  */
+#define CRYP_KeySize_128b         ((uint16_t)0x0000)
+#define CRYP_KeySize_192b         ((uint16_t)0x0100)
+#define CRYP_KeySize_256b         ((uint16_t)0x0200)
+#define IS_CRYP_KEYSIZE(KEYSIZE) (((KEYSIZE) == CRYP_KeySize_128b)|| \
+                                  ((KEYSIZE) == CRYP_KeySize_192b)|| \
+                                  ((KEYSIZE) == CRYP_KeySize_256b))
+/**
+  * @}
+  */
+
+/** @defgroup CRYP_flags_definition 
+  * @{
+  */
+#define CRYP_FLAG_BUSY            ((uint8_t)0x10)  /*!< The CRYP core is currently 
+                                                        processing a block of data 
+                                                        or a key preparation (for 
+                                                        AES decryption). */
+#define CRYP_FLAG_IFEM            ((uint8_t)0x01)  /*!< Input Fifo Empty */
+#define CRYP_FLAG_IFNF            ((uint8_t)0x02)  /*!< Input Fifo is Not Full */
+#define CRYP_FLAG_INRIS           ((uint8_t)0x22)  /*!< Raw interrupt pending */
+#define CRYP_FLAG_OFNE            ((uint8_t)0x04)  /*!< Input Fifo service raw 
+                                                        interrupt status */
+#define CRYP_FLAG_OFFU            ((uint8_t)0x08)  /*!< Output Fifo is Full */
+#define CRYP_FLAG_OUTRIS          ((uint8_t)0x21)  /*!< Output Fifo service raw 
+                                                        interrupt status */
+
+#define IS_CRYP_GET_FLAG(FLAG) (((FLAG) == CRYP_FLAG_IFEM)  || \
+                                ((FLAG) == CRYP_FLAG_IFNF)  || \
+                                ((FLAG) == CRYP_FLAG_OFNE)  || \
+                                ((FLAG) == CRYP_FLAG_OFFU)  || \
+                                ((FLAG) == CRYP_FLAG_BUSY)  || \
+                                ((FLAG) == CRYP_FLAG_OUTRIS)|| \
+                                ((FLAG) == CRYP_FLAG_INRIS))
+/**
+  * @}
+  */
+
+/** @defgroup CRYP_interrupts_definition 
+  * @{
+  */
+#define CRYP_IT_INI               ((uint8_t)0x01) /*!< IN Fifo Interrupt */
+#define CRYP_IT_OUTI              ((uint8_t)0x02) /*!< OUT Fifo Interrupt */
+#define IS_CRYP_CONFIG_IT(IT) ((((IT) & (uint8_t)0xFC) == 0x00) && ((IT) != 0x00))
+#define IS_CRYP_GET_IT(IT) (((IT) == CRYP_IT_INI) || ((IT) == CRYP_IT_OUTI))
+
+/**
+  * @}
+  */
+
+/** @defgroup CRYP_Encryption_Decryption_modes_definition 
+  * @{
+  */
+#define MODE_ENCRYPT             ((uint8_t)0x01)
+#define MODE_DECRYPT             ((uint8_t)0x00)
+
+/**
+  * @}
+  */
+
+/** @defgroup CRYP_DMA_transfer_requests 
+  * @{
+  */
+#define CRYP_DMAReq_DataIN             ((uint8_t)0x01)
+#define CRYP_DMAReq_DataOUT            ((uint8_t)0x02)
+#define IS_CRYP_DMAREQ(DMAREQ) ((((DMAREQ) & (uint8_t)0xFC) == 0x00) && ((DMAREQ) != 0x00))
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/*  Function used to set the CRYP configuration to the default reset state ****/
+void CRYP_DeInit(void);
+
+/* CRYP Initialization and Configuration functions ****************************/
+void CRYP_Init(CRYP_InitTypeDef* CRYP_InitStruct);
+void CRYP_StructInit(CRYP_InitTypeDef* CRYP_InitStruct);
+void CRYP_KeyInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct);
+void CRYP_KeyStructInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct);
+void CRYP_IVInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct);
+void CRYP_IVStructInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct);
+void CRYP_Cmd(FunctionalState NewState);
+void CRYP_PhaseConfig(uint32_t CRYP_Phase);
+void CRYP_FIFOFlush(void);
+/* CRYP Data processing functions *********************************************/
+void CRYP_DataIn(uint32_t Data);
+uint32_t CRYP_DataOut(void);
+
+/* CRYP Context swapping functions ********************************************/
+ErrorStatus CRYP_SaveContext(CRYP_Context* CRYP_ContextSave,
+                             CRYP_KeyInitTypeDef* CRYP_KeyInitStruct);
+void CRYP_RestoreContext(CRYP_Context* CRYP_ContextRestore);
+
+/* CRYP DMA interface function ************************************************/
+void CRYP_DMACmd(uint8_t CRYP_DMAReq, FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void CRYP_ITConfig(uint8_t CRYP_IT, FunctionalState NewState);
+ITStatus CRYP_GetITStatus(uint8_t CRYP_IT);
+FunctionalState CRYP_GetCmdStatus(void);
+FlagStatus CRYP_GetFlagStatus(uint8_t CRYP_FLAG);
+
+/* High Level AES functions **************************************************/
+ErrorStatus CRYP_AES_ECB(uint8_t Mode,
+                         uint8_t *Key, uint16_t Keysize,
+                         uint8_t *Input, uint32_t Ilength,
+                         uint8_t *Output);
+
+ErrorStatus CRYP_AES_CBC(uint8_t Mode,
+                         uint8_t InitVectors[16],
+                         uint8_t *Key, uint16_t Keysize,
+                         uint8_t *Input, uint32_t Ilength,
+                         uint8_t *Output);
+
+ErrorStatus CRYP_AES_CTR(uint8_t Mode,
+                         uint8_t InitVectors[16],
+                         uint8_t *Key, uint16_t Keysize,
+                         uint8_t *Input, uint32_t Ilength,
+                         uint8_t *Output);
+
+ErrorStatus CRYP_AES_GCM(uint8_t Mode, uint8_t InitVectors[16],
+                         uint8_t *Key, uint16_t Keysize,
+                         uint8_t *Input, uint32_t ILength,
+                         uint8_t *Header, uint32_t HLength,
+                         uint8_t *Output, uint8_t *AuthTAG);
+
+ErrorStatus CRYP_AES_CCM(uint8_t Mode, 
+                         uint8_t* Nonce, uint32_t NonceSize,
+                         uint8_t* Key, uint16_t Keysize,
+                         uint8_t* Input, uint32_t ILength,
+                         uint8_t* Header, uint32_t HLength, uint8_t *HBuffer,
+                         uint8_t* Output,
+                         uint8_t* AuthTAG, uint32_t TAGSize);
+
+/* High Level TDES functions **************************************************/
+ErrorStatus CRYP_TDES_ECB(uint8_t Mode,
+                           uint8_t Key[24], 
+                           uint8_t *Input, uint32_t Ilength,
+                           uint8_t *Output);
+
+ErrorStatus CRYP_TDES_CBC(uint8_t Mode,
+                          uint8_t Key[24],
+                          uint8_t InitVectors[8],
+                          uint8_t *Input, uint32_t Ilength,
+                          uint8_t *Output);
+
+/* High Level DES functions **************************************************/
+ErrorStatus CRYP_DES_ECB(uint8_t Mode,
+                         uint8_t Key[8],
+                         uint8_t *Input, uint32_t Ilength,
+                         uint8_t *Output);
+
+ErrorStatus CRYP_DES_CBC(uint8_t Mode,
+                         uint8_t Key[8],
+                         uint8_t InitVectors[8],
+                         uint8_t *Input,uint32_t Ilength,
+                         uint8_t *Output);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_CRYP_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h
new file mode 100644
index 0000000000000000000000000000000000000000..224bec1a1cfabcf6c4e6dd5aaf3fcf1f4d0480d8
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dac.h
@@ -0,0 +1,304 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dac.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the DAC firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_DAC_H
+#define __STM32F4xx_DAC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DAC
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  DAC Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t DAC_Trigger;                      /*!< Specifies the external trigger for the selected DAC channel.
+                                                  This parameter can be a value of @ref DAC_trigger_selection */
+
+  uint32_t DAC_WaveGeneration;               /*!< Specifies whether DAC channel noise waves or triangle waves
+                                                  are generated, or whether no wave is generated.
+                                                  This parameter can be a value of @ref DAC_wave_generation */
+
+  uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or
+                                                  the maximum amplitude triangle generation for the DAC channel. 
+                                                  This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */
+
+  uint32_t DAC_OutputBuffer;                 /*!< Specifies whether the DAC channel output buffer is enabled or disabled.
+                                                  This parameter can be a value of @ref DAC_output_buffer */
+}DAC_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup DAC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup DAC_trigger_selection 
+  * @{
+  */
+
+#define DAC_Trigger_None                   ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register 
+                                                                       has been loaded, and not by external trigger */
+#define DAC_Trigger_T2_TRGO                ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T4_TRGO                ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T5_TRGO                ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T6_TRGO                ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T7_TRGO                ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_T8_TRGO                ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel */                                                                       
+
+#define DAC_Trigger_Ext_IT9                ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */
+#define DAC_Trigger_Software               ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */
+
+#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \
+                                 ((TRIGGER) == DAC_Trigger_T6_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T8_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T7_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T5_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T2_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_T4_TRGO) || \
+                                 ((TRIGGER) == DAC_Trigger_Ext_IT9) || \
+                                 ((TRIGGER) == DAC_Trigger_Software))
+
+/**
+  * @}
+  */
+
+/** @defgroup DAC_wave_generation 
+  * @{
+  */
+
+#define DAC_WaveGeneration_None            ((uint32_t)0x00000000)
+#define DAC_WaveGeneration_Noise           ((uint32_t)0x00000040)
+#define DAC_WaveGeneration_Triangle        ((uint32_t)0x00000080)
+#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \
+                                    ((WAVE) == DAC_WaveGeneration_Noise) || \
+                                    ((WAVE) == DAC_WaveGeneration_Triangle))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_lfsrunmask_triangleamplitude
+  * @{
+  */
+
+#define DAC_LFSRUnmask_Bit0                ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */
+#define DAC_LFSRUnmask_Bits1_0             ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits2_0             ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits3_0             ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits4_0             ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits5_0             ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits6_0             ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits7_0             ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits8_0             ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits9_0             ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits10_0            ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */
+#define DAC_LFSRUnmask_Bits11_0            ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */
+#define DAC_TriangleAmplitude_1            ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */
+#define DAC_TriangleAmplitude_3            ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */
+#define DAC_TriangleAmplitude_7            ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */
+#define DAC_TriangleAmplitude_15           ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */
+#define DAC_TriangleAmplitude_31           ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */
+#define DAC_TriangleAmplitude_63           ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */
+#define DAC_TriangleAmplitude_127          ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */
+#define DAC_TriangleAmplitude_255          ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */
+#define DAC_TriangleAmplitude_511          ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */
+#define DAC_TriangleAmplitude_1023         ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */
+#define DAC_TriangleAmplitude_2047         ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */
+#define DAC_TriangleAmplitude_4095         ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */
+
+#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \
+                                                      ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_1) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_3) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_7) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_15) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_31) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_63) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_127) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_255) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_511) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_1023) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_2047) || \
+                                                      ((VALUE) == DAC_TriangleAmplitude_4095))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_output_buffer 
+  * @{
+  */
+
+#define DAC_OutputBuffer_Enable            ((uint32_t)0x00000000)
+#define DAC_OutputBuffer_Disable           ((uint32_t)0x00000002)
+#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \
+                                           ((STATE) == DAC_OutputBuffer_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Channel_selection 
+  * @{
+  */
+
+#define DAC_Channel_1                      ((uint32_t)0x00000000)
+#define DAC_Channel_2                      ((uint32_t)0x00000010)
+#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \
+                                 ((CHANNEL) == DAC_Channel_2))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_data_alignement 
+  * @{
+  */
+
+#define DAC_Align_12b_R                    ((uint32_t)0x00000000)
+#define DAC_Align_12b_L                    ((uint32_t)0x00000004)
+#define DAC_Align_8b_R                     ((uint32_t)0x00000008)
+#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \
+                             ((ALIGN) == DAC_Align_12b_L) || \
+                             ((ALIGN) == DAC_Align_8b_R))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_wave_generation 
+  * @{
+  */
+
+#define DAC_Wave_Noise                     ((uint32_t)0x00000040)
+#define DAC_Wave_Triangle                  ((uint32_t)0x00000080)
+#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \
+                           ((WAVE) == DAC_Wave_Triangle))
+/**
+  * @}
+  */
+
+/** @defgroup DAC_data 
+  * @{
+  */
+
+#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) 
+/**
+  * @}
+  */
+  
+/** @defgroup DAC_interrupts_definition 
+  * @{
+  */   
+#define DAC_IT_DMAUDR                      ((uint32_t)0x00002000)  
+#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR)) 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup DAC_flags_definition 
+  * @{
+  */ 
+  
+#define DAC_FLAG_DMAUDR                    ((uint32_t)0x00002000)  
+#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR))  
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/  
+
+/*  Function used to set the DAC configuration to the default reset state *****/  
+void DAC_DeInit(void);
+
+/*  DAC channels configuration: trigger, output buffer, data format functions */
+void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct);
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct);
+void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState);
+void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState);
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState);
+void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState);
+void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data);
+void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data);
+void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1);
+uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel);
+
+/* DMA management functions ***************************************************/
+void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState);
+FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG);
+void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG);
+ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT);
+void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_DAC_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h
new file mode 100644
index 0000000000000000000000000000000000000000..83ae133b047c9d1f7ef51c33438eba16f4c4d425
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dbgmcu.h
@@ -0,0 +1,109 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dbgmcu.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the DBGMCU firmware library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_DBGMCU_H
+#define __STM32F4xx_DBGMCU_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DBGMCU
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup DBGMCU_Exported_Constants
+  * @{
+  */ 
+#define DBGMCU_SLEEP                 ((uint32_t)0x00000001)
+#define DBGMCU_STOP                  ((uint32_t)0x00000002)
+#define DBGMCU_STANDBY               ((uint32_t)0x00000004)
+#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFF8) == 0x00) && ((PERIPH) != 0x00))
+
+#define DBGMCU_TIM2_STOP             ((uint32_t)0x00000001)
+#define DBGMCU_TIM3_STOP             ((uint32_t)0x00000002)
+#define DBGMCU_TIM4_STOP             ((uint32_t)0x00000004)
+#define DBGMCU_TIM5_STOP             ((uint32_t)0x00000008)
+#define DBGMCU_TIM6_STOP             ((uint32_t)0x00000010)
+#define DBGMCU_TIM7_STOP             ((uint32_t)0x00000020)
+#define DBGMCU_TIM12_STOP            ((uint32_t)0x00000040)
+#define DBGMCU_TIM13_STOP            ((uint32_t)0x00000080)
+#define DBGMCU_TIM14_STOP            ((uint32_t)0x00000100)
+#define DBGMCU_RTC_STOP              ((uint32_t)0x00000400)
+#define DBGMCU_WWDG_STOP             ((uint32_t)0x00000800)
+#define DBGMCU_IWDG_STOP             ((uint32_t)0x00001000)
+#define DBGMCU_I2C1_SMBUS_TIMEOUT    ((uint32_t)0x00200000)
+#define DBGMCU_I2C2_SMBUS_TIMEOUT    ((uint32_t)0x00400000)
+#define DBGMCU_I2C3_SMBUS_TIMEOUT    ((uint32_t)0x00800000)
+#define DBGMCU_CAN1_STOP             ((uint32_t)0x02000000)
+#define DBGMCU_CAN2_STOP             ((uint32_t)0x04000000)
+#define IS_DBGMCU_APB1PERIPH(PERIPH) ((((PERIPH) & 0xF91FE200) == 0x00) && ((PERIPH) != 0x00))
+
+#define DBGMCU_TIM1_STOP             ((uint32_t)0x00000001)
+#define DBGMCU_TIM8_STOP             ((uint32_t)0x00000002)
+#define DBGMCU_TIM9_STOP             ((uint32_t)0x00010000)
+#define DBGMCU_TIM10_STOP            ((uint32_t)0x00020000)
+#define DBGMCU_TIM11_STOP            ((uint32_t)0x00040000)
+#define IS_DBGMCU_APB2PERIPH(PERIPH) ((((PERIPH) & 0xFFF8FFFC) == 0x00) && ((PERIPH) != 0x00))
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+uint32_t DBGMCU_GetREVID(void);
+uint32_t DBGMCU_GetDEVID(void);
+void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState);
+void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState);
+void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_DBGMCU_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h
new file mode 100644
index 0000000000000000000000000000000000000000..5297587647c5345dcba12d07fd38e0e05119b846
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dcmi.h
@@ -0,0 +1,312 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dcmi.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the DCMI firmware library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_DCMI_H
+#define __STM32F4xx_DCMI_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DCMI
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+/** 
+  * @brief   DCMI Init structure definition  
+  */ 
+typedef struct
+{
+  uint16_t DCMI_CaptureMode;      /*!< Specifies the Capture Mode: Continuous or Snapshot.
+                                       This parameter can be a value of @ref DCMI_Capture_Mode */
+
+  uint16_t DCMI_SynchroMode;      /*!< Specifies the Synchronization Mode: Hardware or Embedded.
+                                       This parameter can be a value of @ref DCMI_Synchronization_Mode */
+
+  uint16_t DCMI_PCKPolarity;      /*!< Specifies the Pixel clock polarity: Falling or Rising.
+                                       This parameter can be a value of @ref DCMI_PIXCK_Polarity */
+
+  uint16_t DCMI_VSPolarity;       /*!< Specifies the Vertical synchronization polarity: High or Low.
+                                       This parameter can be a value of @ref DCMI_VSYNC_Polarity */
+
+  uint16_t DCMI_HSPolarity;       /*!< Specifies the Horizontal synchronization polarity: High or Low.
+                                       This parameter can be a value of @ref DCMI_HSYNC_Polarity */
+
+  uint16_t DCMI_CaptureRate;      /*!< Specifies the frequency of frame capture: All, 1/2 or 1/4.
+                                       This parameter can be a value of @ref DCMI_Capture_Rate */
+
+  uint16_t DCMI_ExtendedDataMode; /*!< Specifies the data width: 8-bit, 10-bit, 12-bit or 14-bit.
+                                       This parameter can be a value of @ref DCMI_Extended_Data_Mode */
+} DCMI_InitTypeDef;
+
+/** 
+  * @brief   DCMI CROP Init structure definition  
+  */ 
+typedef struct
+{
+  uint16_t DCMI_VerticalStartLine;      /*!< Specifies the Vertical start line count from which the image capture
+                                             will start. This parameter can be a value between 0x00 and 0x1FFF */
+
+  uint16_t DCMI_HorizontalOffsetCount;  /*!< Specifies the number of pixel clocks to count before starting a capture.
+                                             This parameter can be a value between 0x00 and 0x3FFF */
+
+  uint16_t DCMI_VerticalLineCount;      /*!< Specifies the number of lines to be captured from the starting point.
+                                             This parameter can be a value between 0x00 and 0x3FFF */
+
+  uint16_t DCMI_CaptureCount;           /*!< Specifies the number of pixel clocks to be captured from the starting
+                                             point on the same line.
+                                             This parameter can be a value between 0x00 and 0x3FFF */
+} DCMI_CROPInitTypeDef;
+
+/** 
+  * @brief   DCMI Embedded Synchronisation CODE Init structure definition  
+  */ 
+typedef struct
+{
+  uint8_t DCMI_FrameStartCode; /*!< Specifies the code of the frame start delimiter. */
+  uint8_t DCMI_LineStartCode;  /*!< Specifies the code of the line start delimiter. */
+  uint8_t DCMI_LineEndCode;    /*!< Specifies the code of the line end delimiter. */
+  uint8_t DCMI_FrameEndCode;   /*!< Specifies the code of the frame end delimiter. */
+} DCMI_CodesInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup DCMI_Exported_Constants
+  * @{
+  */
+
+/** @defgroup DCMI_Capture_Mode 
+  * @{
+  */ 
+#define DCMI_CaptureMode_Continuous    ((uint16_t)0x0000) /*!< The received data are transferred continuously 
+                                                               into the destination memory through the DMA */
+#define DCMI_CaptureMode_SnapShot      ((uint16_t)0x0002) /*!< Once activated, the interface waits for the start of 
+                                                               frame and then transfers a single frame through the DMA */
+#define IS_DCMI_CAPTURE_MODE(MODE)(((MODE) == DCMI_CaptureMode_Continuous) || \
+                                   ((MODE) == DCMI_CaptureMode_SnapShot))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_Synchronization_Mode
+  * @{
+  */ 
+#define DCMI_SynchroMode_Hardware    ((uint16_t)0x0000) /*!< Hardware synchronization data capture (frame/line start/stop)
+                                                             is synchronized with the HSYNC/VSYNC signals */
+#define DCMI_SynchroMode_Embedded    ((uint16_t)0x0010) /*!< Embedded synchronization data capture is synchronized with 
+                                                             synchronization codes embedded in the data flow */
+#define IS_DCMI_SYNCHRO(MODE)(((MODE) == DCMI_SynchroMode_Hardware) || \
+                              ((MODE) == DCMI_SynchroMode_Embedded))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_PIXCK_Polarity 
+  * @{
+  */ 
+#define DCMI_PCKPolarity_Falling    ((uint16_t)0x0000) /*!< Pixel clock active on Falling edge */
+#define DCMI_PCKPolarity_Rising     ((uint16_t)0x0020) /*!< Pixel clock active on Rising edge */
+#define IS_DCMI_PCKPOLARITY(POLARITY)(((POLARITY) == DCMI_PCKPolarity_Falling) || \
+                                      ((POLARITY) == DCMI_PCKPolarity_Rising))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_VSYNC_Polarity 
+  * @{
+  */ 
+#define DCMI_VSPolarity_Low     ((uint16_t)0x0000) /*!< Vertical synchronization active Low */
+#define DCMI_VSPolarity_High    ((uint16_t)0x0080) /*!< Vertical synchronization active High */
+#define IS_DCMI_VSPOLARITY(POLARITY)(((POLARITY) == DCMI_VSPolarity_Low) || \
+                                     ((POLARITY) == DCMI_VSPolarity_High))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_HSYNC_Polarity 
+  * @{
+  */ 
+#define DCMI_HSPolarity_Low     ((uint16_t)0x0000) /*!< Horizontal synchronization active Low */
+#define DCMI_HSPolarity_High    ((uint16_t)0x0040) /*!< Horizontal synchronization active High */
+#define IS_DCMI_HSPOLARITY(POLARITY)(((POLARITY) == DCMI_HSPolarity_Low) || \
+                                     ((POLARITY) == DCMI_HSPolarity_High))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_Capture_Rate 
+  * @{
+  */ 
+#define DCMI_CaptureRate_All_Frame     ((uint16_t)0x0000) /*!< All frames are captured */
+#define DCMI_CaptureRate_1of2_Frame    ((uint16_t)0x0100) /*!< Every alternate frame captured */
+#define DCMI_CaptureRate_1of4_Frame    ((uint16_t)0x0200) /*!< One frame in 4 frames captured */
+#define IS_DCMI_CAPTURE_RATE(RATE) (((RATE) == DCMI_CaptureRate_All_Frame) || \
+                                    ((RATE) == DCMI_CaptureRate_1of2_Frame) ||\
+                                    ((RATE) == DCMI_CaptureRate_1of4_Frame))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_Extended_Data_Mode 
+  * @{
+  */ 
+#define DCMI_ExtendedDataMode_8b     ((uint16_t)0x0000) /*!< Interface captures 8-bit data on every pixel clock */
+#define DCMI_ExtendedDataMode_10b    ((uint16_t)0x0400) /*!< Interface captures 10-bit data on every pixel clock */
+#define DCMI_ExtendedDataMode_12b    ((uint16_t)0x0800) /*!< Interface captures 12-bit data on every pixel clock */
+#define DCMI_ExtendedDataMode_14b    ((uint16_t)0x0C00) /*!< Interface captures 14-bit data on every pixel clock */
+#define IS_DCMI_EXTENDED_DATA(DATA)(((DATA) == DCMI_ExtendedDataMode_8b) || \
+                                    ((DATA) == DCMI_ExtendedDataMode_10b) ||\
+                                    ((DATA) == DCMI_ExtendedDataMode_12b) ||\
+                                    ((DATA) == DCMI_ExtendedDataMode_14b))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_interrupt_sources 
+  * @{
+  */ 
+#define DCMI_IT_FRAME    ((uint16_t)0x0001)
+#define DCMI_IT_OVF      ((uint16_t)0x0002)
+#define DCMI_IT_ERR      ((uint16_t)0x0004)
+#define DCMI_IT_VSYNC    ((uint16_t)0x0008)
+#define DCMI_IT_LINE     ((uint16_t)0x0010)
+#define IS_DCMI_CONFIG_IT(IT) ((((IT) & (uint16_t)0xFFE0) == 0x0000) && ((IT) != 0x0000))
+#define IS_DCMI_GET_IT(IT) (((IT) == DCMI_IT_FRAME) || \
+                            ((IT) == DCMI_IT_OVF) || \
+                            ((IT) == DCMI_IT_ERR) || \
+                            ((IT) == DCMI_IT_VSYNC) || \
+                            ((IT) == DCMI_IT_LINE))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DCMI_Flags 
+  * @{
+  */ 
+/** 
+  * @brief   DCMI SR register  
+  */ 
+#define DCMI_FLAG_HSYNC     ((uint16_t)0x2001)
+#define DCMI_FLAG_VSYNC     ((uint16_t)0x2002)
+#define DCMI_FLAG_FNE       ((uint16_t)0x2004)
+/** 
+  * @brief   DCMI RISR register  
+  */ 
+#define DCMI_FLAG_FRAMERI    ((uint16_t)0x0001)
+#define DCMI_FLAG_OVFRI      ((uint16_t)0x0002)
+#define DCMI_FLAG_ERRRI      ((uint16_t)0x0004)
+#define DCMI_FLAG_VSYNCRI    ((uint16_t)0x0008)
+#define DCMI_FLAG_LINERI     ((uint16_t)0x0010)
+/** 
+  * @brief   DCMI MISR register  
+  */ 
+#define DCMI_FLAG_FRAMEMI    ((uint16_t)0x1001)
+#define DCMI_FLAG_OVFMI      ((uint16_t)0x1002)
+#define DCMI_FLAG_ERRMI      ((uint16_t)0x1004)
+#define DCMI_FLAG_VSYNCMI    ((uint16_t)0x1008)
+#define DCMI_FLAG_LINEMI     ((uint16_t)0x1010)
+#define IS_DCMI_GET_FLAG(FLAG) (((FLAG) == DCMI_FLAG_HSYNC) || \
+                                ((FLAG) == DCMI_FLAG_VSYNC) || \
+                                ((FLAG) == DCMI_FLAG_FNE) || \
+                                ((FLAG) == DCMI_FLAG_FRAMERI) || \
+                                ((FLAG) == DCMI_FLAG_OVFRI) || \
+                                ((FLAG) == DCMI_FLAG_ERRRI) || \
+                                ((FLAG) == DCMI_FLAG_VSYNCRI) || \
+                                ((FLAG) == DCMI_FLAG_LINERI) || \
+                                ((FLAG) == DCMI_FLAG_FRAMEMI) || \
+                                ((FLAG) == DCMI_FLAG_OVFMI) || \
+                                ((FLAG) == DCMI_FLAG_ERRMI) || \
+                                ((FLAG) == DCMI_FLAG_VSYNCMI) || \
+                                ((FLAG) == DCMI_FLAG_LINEMI))
+                                
+#define IS_DCMI_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFE0) == 0x0000) && ((FLAG) != 0x0000))
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the DCMI configuration to the default reset state ****/ 
+void DCMI_DeInit(void);
+
+/* Initialization and Configuration functions *********************************/
+void DCMI_Init(DCMI_InitTypeDef* DCMI_InitStruct);
+void DCMI_StructInit(DCMI_InitTypeDef* DCMI_InitStruct);
+void DCMI_CROPConfig(DCMI_CROPInitTypeDef* DCMI_CROPInitStruct);
+void DCMI_CROPCmd(FunctionalState NewState);
+void DCMI_SetEmbeddedSynchroCodes(DCMI_CodesInitTypeDef* DCMI_CodesInitStruct);
+void DCMI_JPEGCmd(FunctionalState NewState);
+
+/* Image capture functions ****************************************************/
+void DCMI_Cmd(FunctionalState NewState);
+void DCMI_CaptureCmd(FunctionalState NewState);
+uint32_t DCMI_ReadData(void);
+
+/* Interrupts and flags management functions **********************************/
+void DCMI_ITConfig(uint16_t DCMI_IT, FunctionalState NewState);
+FlagStatus DCMI_GetFlagStatus(uint16_t DCMI_FLAG);
+void DCMI_ClearFlag(uint16_t DCMI_FLAG);
+ITStatus DCMI_GetITStatus(uint16_t DCMI_IT);
+void DCMI_ClearITPendingBit(uint16_t DCMI_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_DCMI_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h
new file mode 100644
index 0000000000000000000000000000000000000000..3a105d1b451fc998ba70a82e508f8be9e58e9c21
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma.h
@@ -0,0 +1,609 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dma.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the DMA firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_DMA_H
+#define __STM32F4xx_DMA_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DMA
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  DMA Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t DMA_Channel;            /*!< Specifies the channel used for the specified stream. 
+                                        This parameter can be a value of @ref DMA_channel */
+ 
+  uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Streamx. */
+
+  uint32_t DMA_Memory0BaseAddr;    /*!< Specifies the memory 0 base address for DMAy Streamx. 
+                                        This memory is the default memory used when double buffer mode is
+                                        not enabled. */
+
+  uint32_t DMA_DIR;                /*!< Specifies if the data will be transferred from memory to peripheral, 
+                                        from memory to memory or from peripheral to memory.
+                                        This parameter can be a value of @ref DMA_data_transfer_direction */
+
+  uint32_t DMA_BufferSize;         /*!< Specifies the buffer size, in data unit, of the specified Stream. 
+                                        The data unit is equal to the configuration set in DMA_PeripheralDataSize
+                                        or DMA_MemoryDataSize members depending in the transfer direction. */
+
+  uint32_t DMA_PeripheralInc;      /*!< Specifies whether the Peripheral address register should be incremented or not.
+                                        This parameter can be a value of @ref DMA_peripheral_incremented_mode */
+
+  uint32_t DMA_MemoryInc;          /*!< Specifies whether the memory address register should be incremented or not.
+                                        This parameter can be a value of @ref DMA_memory_incremented_mode */
+
+  uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width.
+                                        This parameter can be a value of @ref DMA_peripheral_data_size */
+
+  uint32_t DMA_MemoryDataSize;     /*!< Specifies the Memory data width.
+                                        This parameter can be a value of @ref DMA_memory_data_size */
+
+  uint32_t DMA_Mode;               /*!< Specifies the operation mode of the DMAy Streamx.
+                                        This parameter can be a value of @ref DMA_circular_normal_mode
+                                        @note The circular buffer mode cannot be used if the memory-to-memory
+                                              data transfer is configured on the selected Stream */
+
+  uint32_t DMA_Priority;           /*!< Specifies the software priority for the DMAy Streamx.
+                                        This parameter can be a value of @ref DMA_priority_level */
+
+  uint32_t DMA_FIFOMode;          /*!< Specifies if the FIFO mode or Direct mode will be used for the specified Stream.
+                                        This parameter can be a value of @ref DMA_fifo_direct_mode
+                                        @note The Direct mode (FIFO mode disabled) cannot be used if the 
+                                               memory-to-memory data transfer is configured on the selected Stream */
+
+  uint32_t DMA_FIFOThreshold;      /*!< Specifies the FIFO threshold level.
+                                        This parameter can be a value of @ref DMA_fifo_threshold_level */
+
+  uint32_t DMA_MemoryBurst;        /*!< Specifies the Burst transfer configuration for the memory transfers. 
+                                        It specifies the amount of data to be transferred in a single non interruptable 
+                                        transaction. This parameter can be a value of @ref DMA_memory_burst 
+                                        @note The burst mode is possible only if the address Increment mode is enabled. */
+
+  uint32_t DMA_PeripheralBurst;    /*!< Specifies the Burst transfer configuration for the peripheral transfers. 
+                                        It specifies the amount of data to be transferred in a single non interruptable 
+                                        transaction. This parameter can be a value of @ref DMA_peripheral_burst
+                                        @note The burst mode is possible only if the address Increment mode is enabled. */  
+}DMA_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup DMA_Exported_Constants
+  * @{
+  */
+
+#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Stream0) || \
+                                   ((PERIPH) == DMA1_Stream1) || \
+                                   ((PERIPH) == DMA1_Stream2) || \
+                                   ((PERIPH) == DMA1_Stream3) || \
+                                   ((PERIPH) == DMA1_Stream4) || \
+                                   ((PERIPH) == DMA1_Stream5) || \
+                                   ((PERIPH) == DMA1_Stream6) || \
+                                   ((PERIPH) == DMA1_Stream7) || \
+                                   ((PERIPH) == DMA2_Stream0) || \
+                                   ((PERIPH) == DMA2_Stream1) || \
+                                   ((PERIPH) == DMA2_Stream2) || \
+                                   ((PERIPH) == DMA2_Stream3) || \
+                                   ((PERIPH) == DMA2_Stream4) || \
+                                   ((PERIPH) == DMA2_Stream5) || \
+                                   ((PERIPH) == DMA2_Stream6) || \
+                                   ((PERIPH) == DMA2_Stream7))
+
+#define IS_DMA_ALL_CONTROLLER(CONTROLLER) (((CONTROLLER) == DMA1) || \
+                                           ((CONTROLLER) == DMA2))
+
+/** @defgroup DMA_channel 
+  * @{
+  */ 
+#define DMA_Channel_0                     ((uint32_t)0x00000000)
+#define DMA_Channel_1                     ((uint32_t)0x02000000)
+#define DMA_Channel_2                     ((uint32_t)0x04000000)
+#define DMA_Channel_3                     ((uint32_t)0x06000000)
+#define DMA_Channel_4                     ((uint32_t)0x08000000)
+#define DMA_Channel_5                     ((uint32_t)0x0A000000)
+#define DMA_Channel_6                     ((uint32_t)0x0C000000)
+#define DMA_Channel_7                     ((uint32_t)0x0E000000)
+
+#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_Channel_0) || \
+                                 ((CHANNEL) == DMA_Channel_1) || \
+                                 ((CHANNEL) == DMA_Channel_2) || \
+                                 ((CHANNEL) == DMA_Channel_3) || \
+                                 ((CHANNEL) == DMA_Channel_4) || \
+                                 ((CHANNEL) == DMA_Channel_5) || \
+                                 ((CHANNEL) == DMA_Channel_6) || \
+                                 ((CHANNEL) == DMA_Channel_7))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_data_transfer_direction 
+  * @{
+  */ 
+#define DMA_DIR_PeripheralToMemory        ((uint32_t)0x00000000)
+#define DMA_DIR_MemoryToPeripheral        ((uint32_t)0x00000040) 
+#define DMA_DIR_MemoryToMemory            ((uint32_t)0x00000080)
+
+#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_DIR_PeripheralToMemory ) || \
+                                     ((DIRECTION) == DMA_DIR_MemoryToPeripheral)  || \
+                                     ((DIRECTION) == DMA_DIR_MemoryToMemory)) 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_data_buffer_size 
+  * @{
+  */ 
+#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_peripheral_incremented_mode 
+  * @{
+  */ 
+#define DMA_PeripheralInc_Enable          ((uint32_t)0x00000200)
+#define DMA_PeripheralInc_Disable         ((uint32_t)0x00000000)
+
+#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \
+                                            ((STATE) == DMA_PeripheralInc_Disable))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_memory_incremented_mode 
+  * @{
+  */ 
+#define DMA_MemoryInc_Enable              ((uint32_t)0x00000400)
+#define DMA_MemoryInc_Disable             ((uint32_t)0x00000000)
+
+#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \
+                                        ((STATE) == DMA_MemoryInc_Disable))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_peripheral_data_size 
+  * @{
+  */ 
+#define DMA_PeripheralDataSize_Byte       ((uint32_t)0x00000000) 
+#define DMA_PeripheralDataSize_HalfWord   ((uint32_t)0x00000800) 
+#define DMA_PeripheralDataSize_Word       ((uint32_t)0x00001000)
+
+#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte)  || \
+                                           ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \
+                                           ((SIZE) == DMA_PeripheralDataSize_Word))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_memory_data_size 
+  * @{
+  */ 
+#define DMA_MemoryDataSize_Byte           ((uint32_t)0x00000000) 
+#define DMA_MemoryDataSize_HalfWord       ((uint32_t)0x00002000) 
+#define DMA_MemoryDataSize_Word           ((uint32_t)0x00004000)
+
+#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte)  || \
+                                       ((SIZE) == DMA_MemoryDataSize_HalfWord) || \
+                                       ((SIZE) == DMA_MemoryDataSize_Word ))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_circular_normal_mode 
+  * @{
+  */ 
+#define DMA_Mode_Normal                   ((uint32_t)0x00000000) 
+#define DMA_Mode_Circular                 ((uint32_t)0x00000100)
+
+#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Normal ) || \
+                           ((MODE) == DMA_Mode_Circular)) 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_priority_level 
+  * @{
+  */ 
+#define DMA_Priority_Low                  ((uint32_t)0x00000000)
+#define DMA_Priority_Medium               ((uint32_t)0x00010000) 
+#define DMA_Priority_High                 ((uint32_t)0x00020000)
+#define DMA_Priority_VeryHigh             ((uint32_t)0x00030000)
+
+#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_Low )   || \
+                                   ((PRIORITY) == DMA_Priority_Medium) || \
+                                   ((PRIORITY) == DMA_Priority_High)   || \
+                                   ((PRIORITY) == DMA_Priority_VeryHigh)) 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_fifo_direct_mode 
+  * @{
+  */ 
+#define DMA_FIFOMode_Disable              ((uint32_t)0x00000000) 
+#define DMA_FIFOMode_Enable               ((uint32_t)0x00000004)
+
+#define IS_DMA_FIFO_MODE_STATE(STATE) (((STATE) == DMA_FIFOMode_Disable ) || \
+                                       ((STATE) == DMA_FIFOMode_Enable)) 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_fifo_threshold_level 
+  * @{
+  */ 
+#define DMA_FIFOThreshold_1QuarterFull    ((uint32_t)0x00000000)
+#define DMA_FIFOThreshold_HalfFull        ((uint32_t)0x00000001) 
+#define DMA_FIFOThreshold_3QuartersFull   ((uint32_t)0x00000002)
+#define DMA_FIFOThreshold_Full            ((uint32_t)0x00000003)
+
+#define IS_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == DMA_FIFOThreshold_1QuarterFull ) || \
+                                          ((THRESHOLD) == DMA_FIFOThreshold_HalfFull)      || \
+                                          ((THRESHOLD) == DMA_FIFOThreshold_3QuartersFull) || \
+                                          ((THRESHOLD) == DMA_FIFOThreshold_Full)) 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_memory_burst 
+  * @{
+  */ 
+#define DMA_MemoryBurst_Single            ((uint32_t)0x00000000)
+#define DMA_MemoryBurst_INC4              ((uint32_t)0x00800000)  
+#define DMA_MemoryBurst_INC8              ((uint32_t)0x01000000)
+#define DMA_MemoryBurst_INC16             ((uint32_t)0x01800000)
+
+#define IS_DMA_MEMORY_BURST(BURST) (((BURST) == DMA_MemoryBurst_Single) || \
+                                    ((BURST) == DMA_MemoryBurst_INC4)  || \
+                                    ((BURST) == DMA_MemoryBurst_INC8)  || \
+                                    ((BURST) == DMA_MemoryBurst_INC16))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_peripheral_burst 
+  * @{
+  */ 
+#define DMA_PeripheralBurst_Single        ((uint32_t)0x00000000)
+#define DMA_PeripheralBurst_INC4          ((uint32_t)0x00200000)  
+#define DMA_PeripheralBurst_INC8          ((uint32_t)0x00400000)
+#define DMA_PeripheralBurst_INC16         ((uint32_t)0x00600000)
+
+#define IS_DMA_PERIPHERAL_BURST(BURST) (((BURST) == DMA_PeripheralBurst_Single) || \
+                                        ((BURST) == DMA_PeripheralBurst_INC4)  || \
+                                        ((BURST) == DMA_PeripheralBurst_INC8)  || \
+                                        ((BURST) == DMA_PeripheralBurst_INC16))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_fifo_status_level 
+  * @{
+  */
+#define DMA_FIFOStatus_Less1QuarterFull   ((uint32_t)0x00000000 << 3)
+#define DMA_FIFOStatus_1QuarterFull       ((uint32_t)0x00000001 << 3)
+#define DMA_FIFOStatus_HalfFull           ((uint32_t)0x00000002 << 3) 
+#define DMA_FIFOStatus_3QuartersFull      ((uint32_t)0x00000003 << 3)
+#define DMA_FIFOStatus_Empty              ((uint32_t)0x00000004 << 3)
+#define DMA_FIFOStatus_Full               ((uint32_t)0x00000005 << 3)
+
+#define IS_DMA_FIFO_STATUS(STATUS) (((STATUS) == DMA_FIFOStatus_Less1QuarterFull ) || \
+                                    ((STATUS) == DMA_FIFOStatus_HalfFull)          || \
+                                    ((STATUS) == DMA_FIFOStatus_1QuarterFull)      || \
+                                    ((STATUS) == DMA_FIFOStatus_3QuartersFull)     || \
+                                    ((STATUS) == DMA_FIFOStatus_Full)              || \
+                                    ((STATUS) == DMA_FIFOStatus_Empty)) 
+/**
+  * @}
+  */ 
+
+/** @defgroup DMA_flags_definition 
+  * @{
+  */
+#define DMA_FLAG_FEIF0                    ((uint32_t)0x10800001)
+#define DMA_FLAG_DMEIF0                   ((uint32_t)0x10800004)
+#define DMA_FLAG_TEIF0                    ((uint32_t)0x10000008)
+#define DMA_FLAG_HTIF0                    ((uint32_t)0x10000010)
+#define DMA_FLAG_TCIF0                    ((uint32_t)0x10000020)
+#define DMA_FLAG_FEIF1                    ((uint32_t)0x10000040)
+#define DMA_FLAG_DMEIF1                   ((uint32_t)0x10000100)
+#define DMA_FLAG_TEIF1                    ((uint32_t)0x10000200)
+#define DMA_FLAG_HTIF1                    ((uint32_t)0x10000400)
+#define DMA_FLAG_TCIF1                    ((uint32_t)0x10000800)
+#define DMA_FLAG_FEIF2                    ((uint32_t)0x10010000)
+#define DMA_FLAG_DMEIF2                   ((uint32_t)0x10040000)
+#define DMA_FLAG_TEIF2                    ((uint32_t)0x10080000)
+#define DMA_FLAG_HTIF2                    ((uint32_t)0x10100000)
+#define DMA_FLAG_TCIF2                    ((uint32_t)0x10200000)
+#define DMA_FLAG_FEIF3                    ((uint32_t)0x10400000)
+#define DMA_FLAG_DMEIF3                   ((uint32_t)0x11000000)
+#define DMA_FLAG_TEIF3                    ((uint32_t)0x12000000)
+#define DMA_FLAG_HTIF3                    ((uint32_t)0x14000000)
+#define DMA_FLAG_TCIF3                    ((uint32_t)0x18000000)
+#define DMA_FLAG_FEIF4                    ((uint32_t)0x20000001)
+#define DMA_FLAG_DMEIF4                   ((uint32_t)0x20000004)
+#define DMA_FLAG_TEIF4                    ((uint32_t)0x20000008)
+#define DMA_FLAG_HTIF4                    ((uint32_t)0x20000010)
+#define DMA_FLAG_TCIF4                    ((uint32_t)0x20000020)
+#define DMA_FLAG_FEIF5                    ((uint32_t)0x20000040)
+#define DMA_FLAG_DMEIF5                   ((uint32_t)0x20000100)
+#define DMA_FLAG_TEIF5                    ((uint32_t)0x20000200)
+#define DMA_FLAG_HTIF5                    ((uint32_t)0x20000400)
+#define DMA_FLAG_TCIF5                    ((uint32_t)0x20000800)
+#define DMA_FLAG_FEIF6                    ((uint32_t)0x20010000)
+#define DMA_FLAG_DMEIF6                   ((uint32_t)0x20040000)
+#define DMA_FLAG_TEIF6                    ((uint32_t)0x20080000)
+#define DMA_FLAG_HTIF6                    ((uint32_t)0x20100000)
+#define DMA_FLAG_TCIF6                    ((uint32_t)0x20200000)
+#define DMA_FLAG_FEIF7                    ((uint32_t)0x20400000)
+#define DMA_FLAG_DMEIF7                   ((uint32_t)0x21000000)
+#define DMA_FLAG_TEIF7                    ((uint32_t)0x22000000)
+#define DMA_FLAG_HTIF7                    ((uint32_t)0x24000000)
+#define DMA_FLAG_TCIF7                    ((uint32_t)0x28000000)
+
+#define IS_DMA_CLEAR_FLAG(FLAG) ((((FLAG) & 0x30000000) != 0x30000000) && (((FLAG) & 0x30000000) != 0) && \
+                                 (((FLAG) & 0xC002F082) == 0x00) && ((FLAG) != 0x00))
+
+#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA_FLAG_TCIF0)  || ((FLAG) == DMA_FLAG_HTIF0)  || \
+                               ((FLAG) == DMA_FLAG_TEIF0)  || ((FLAG) == DMA_FLAG_DMEIF0) || \
+                               ((FLAG) == DMA_FLAG_FEIF0)  || ((FLAG) == DMA_FLAG_TCIF1)  || \
+                               ((FLAG) == DMA_FLAG_HTIF1)  || ((FLAG) == DMA_FLAG_TEIF1)  || \
+                               ((FLAG) == DMA_FLAG_DMEIF1) || ((FLAG) == DMA_FLAG_FEIF1)  || \
+                               ((FLAG) == DMA_FLAG_TCIF2)  || ((FLAG) == DMA_FLAG_HTIF2)  || \
+                               ((FLAG) == DMA_FLAG_TEIF2)  || ((FLAG) == DMA_FLAG_DMEIF2) || \
+                               ((FLAG) == DMA_FLAG_FEIF2)  || ((FLAG) == DMA_FLAG_TCIF3)  || \
+                               ((FLAG) == DMA_FLAG_HTIF3)  || ((FLAG) == DMA_FLAG_TEIF3)  || \
+                               ((FLAG) == DMA_FLAG_DMEIF3) || ((FLAG) == DMA_FLAG_FEIF3)  || \
+                               ((FLAG) == DMA_FLAG_TCIF4)  || ((FLAG) == DMA_FLAG_HTIF4)  || \
+                               ((FLAG) == DMA_FLAG_TEIF4)  || ((FLAG) == DMA_FLAG_DMEIF4) || \
+                               ((FLAG) == DMA_FLAG_FEIF4)  || ((FLAG) == DMA_FLAG_TCIF5)  || \
+                               ((FLAG) == DMA_FLAG_HTIF5)  || ((FLAG) == DMA_FLAG_TEIF5)  || \
+                               ((FLAG) == DMA_FLAG_DMEIF5) || ((FLAG) == DMA_FLAG_FEIF5)  || \
+                               ((FLAG) == DMA_FLAG_TCIF6)  || ((FLAG) == DMA_FLAG_HTIF6)  || \
+                               ((FLAG) == DMA_FLAG_TEIF6)  || ((FLAG) == DMA_FLAG_DMEIF6) || \
+                               ((FLAG) == DMA_FLAG_FEIF6)  || ((FLAG) == DMA_FLAG_TCIF7)  || \
+                               ((FLAG) == DMA_FLAG_HTIF7)  || ((FLAG) == DMA_FLAG_TEIF7)  || \
+                               ((FLAG) == DMA_FLAG_DMEIF7) || ((FLAG) == DMA_FLAG_FEIF7))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_interrupt_enable_definitions 
+  * @{
+  */ 
+#define DMA_IT_TC                         ((uint32_t)0x00000010)
+#define DMA_IT_HT                         ((uint32_t)0x00000008)
+#define DMA_IT_TE                         ((uint32_t)0x00000004)
+#define DMA_IT_DME                        ((uint32_t)0x00000002)
+#define DMA_IT_FE                         ((uint32_t)0x00000080)
+
+#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFF61) == 0x00) && ((IT) != 0x00))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_interrupts_definitions 
+  * @{
+  */ 
+#define DMA_IT_FEIF0                      ((uint32_t)0x90000001)
+#define DMA_IT_DMEIF0                     ((uint32_t)0x10001004)
+#define DMA_IT_TEIF0                      ((uint32_t)0x10002008)
+#define DMA_IT_HTIF0                      ((uint32_t)0x10004010)
+#define DMA_IT_TCIF0                      ((uint32_t)0x10008020)
+#define DMA_IT_FEIF1                      ((uint32_t)0x90000040)
+#define DMA_IT_DMEIF1                     ((uint32_t)0x10001100)
+#define DMA_IT_TEIF1                      ((uint32_t)0x10002200)
+#define DMA_IT_HTIF1                      ((uint32_t)0x10004400)
+#define DMA_IT_TCIF1                      ((uint32_t)0x10008800)
+#define DMA_IT_FEIF2                      ((uint32_t)0x90010000)
+#define DMA_IT_DMEIF2                     ((uint32_t)0x10041000)
+#define DMA_IT_TEIF2                      ((uint32_t)0x10082000)
+#define DMA_IT_HTIF2                      ((uint32_t)0x10104000)
+#define DMA_IT_TCIF2                      ((uint32_t)0x10208000)
+#define DMA_IT_FEIF3                      ((uint32_t)0x90400000)
+#define DMA_IT_DMEIF3                     ((uint32_t)0x11001000)
+#define DMA_IT_TEIF3                      ((uint32_t)0x12002000)
+#define DMA_IT_HTIF3                      ((uint32_t)0x14004000)
+#define DMA_IT_TCIF3                      ((uint32_t)0x18008000)
+#define DMA_IT_FEIF4                      ((uint32_t)0xA0000001)
+#define DMA_IT_DMEIF4                     ((uint32_t)0x20001004)
+#define DMA_IT_TEIF4                      ((uint32_t)0x20002008)
+#define DMA_IT_HTIF4                      ((uint32_t)0x20004010)
+#define DMA_IT_TCIF4                      ((uint32_t)0x20008020)
+#define DMA_IT_FEIF5                      ((uint32_t)0xA0000040)
+#define DMA_IT_DMEIF5                     ((uint32_t)0x20001100)
+#define DMA_IT_TEIF5                      ((uint32_t)0x20002200)
+#define DMA_IT_HTIF5                      ((uint32_t)0x20004400)
+#define DMA_IT_TCIF5                      ((uint32_t)0x20008800)
+#define DMA_IT_FEIF6                      ((uint32_t)0xA0010000)
+#define DMA_IT_DMEIF6                     ((uint32_t)0x20041000)
+#define DMA_IT_TEIF6                      ((uint32_t)0x20082000)
+#define DMA_IT_HTIF6                      ((uint32_t)0x20104000)
+#define DMA_IT_TCIF6                      ((uint32_t)0x20208000)
+#define DMA_IT_FEIF7                      ((uint32_t)0xA0400000)
+#define DMA_IT_DMEIF7                     ((uint32_t)0x21001000)
+#define DMA_IT_TEIF7                      ((uint32_t)0x22002000)
+#define DMA_IT_HTIF7                      ((uint32_t)0x24004000)
+#define DMA_IT_TCIF7                      ((uint32_t)0x28008000)
+
+#define IS_DMA_CLEAR_IT(IT) ((((IT) & 0x30000000) != 0x30000000) && \
+                             (((IT) & 0x30000000) != 0) && ((IT) != 0x00) && \
+                             (((IT) & 0x40820082) == 0x00))
+
+#define IS_DMA_GET_IT(IT) (((IT) == DMA_IT_TCIF0) || ((IT) == DMA_IT_HTIF0)  || \
+                           ((IT) == DMA_IT_TEIF0) || ((IT) == DMA_IT_DMEIF0) || \
+                           ((IT) == DMA_IT_FEIF0) || ((IT) == DMA_IT_TCIF1)  || \
+                           ((IT) == DMA_IT_HTIF1) || ((IT) == DMA_IT_TEIF1)  || \
+                           ((IT) == DMA_IT_DMEIF1)|| ((IT) == DMA_IT_FEIF1)  || \
+                           ((IT) == DMA_IT_TCIF2) || ((IT) == DMA_IT_HTIF2)  || \
+                           ((IT) == DMA_IT_TEIF2) || ((IT) == DMA_IT_DMEIF2) || \
+                           ((IT) == DMA_IT_FEIF2) || ((IT) == DMA_IT_TCIF3)  || \
+                           ((IT) == DMA_IT_HTIF3) || ((IT) == DMA_IT_TEIF3)  || \
+                           ((IT) == DMA_IT_DMEIF3)|| ((IT) == DMA_IT_FEIF3)  || \
+                           ((IT) == DMA_IT_TCIF4) || ((IT) == DMA_IT_HTIF4)  || \
+                           ((IT) == DMA_IT_TEIF4) || ((IT) == DMA_IT_DMEIF4) || \
+                           ((IT) == DMA_IT_FEIF4) || ((IT) == DMA_IT_TCIF5)  || \
+                           ((IT) == DMA_IT_HTIF5) || ((IT) == DMA_IT_TEIF5)  || \
+                           ((IT) == DMA_IT_DMEIF5)|| ((IT) == DMA_IT_FEIF5)  || \
+                           ((IT) == DMA_IT_TCIF6) || ((IT) == DMA_IT_HTIF6)  || \
+                           ((IT) == DMA_IT_TEIF6) || ((IT) == DMA_IT_DMEIF6) || \
+                           ((IT) == DMA_IT_FEIF6) || ((IT) == DMA_IT_TCIF7)  || \
+                           ((IT) == DMA_IT_HTIF7) || ((IT) == DMA_IT_TEIF7)  || \
+                           ((IT) == DMA_IT_DMEIF7)|| ((IT) == DMA_IT_FEIF7))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_peripheral_increment_offset 
+  * @{
+  */ 
+#define DMA_PINCOS_Psize                  ((uint32_t)0x00000000)
+#define DMA_PINCOS_WordAligned            ((uint32_t)0x00008000)
+
+#define IS_DMA_PINCOS_SIZE(SIZE) (((SIZE) == DMA_PINCOS_Psize) || \
+                                  ((SIZE) == DMA_PINCOS_WordAligned))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_flow_controller_definitions 
+  * @{
+  */ 
+#define DMA_FlowCtrl_Memory               ((uint32_t)0x00000000)
+#define DMA_FlowCtrl_Peripheral           ((uint32_t)0x00000020)
+
+#define IS_DMA_FLOW_CTRL(CTRL) (((CTRL) == DMA_FlowCtrl_Memory) || \
+                                ((CTRL) == DMA_FlowCtrl_Peripheral))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup DMA_memory_targets_definitions 
+  * @{
+  */ 
+#define DMA_Memory_0                      ((uint32_t)0x00000000)
+#define DMA_Memory_1                      ((uint32_t)0x00080000)
+
+#define IS_DMA_CURRENT_MEM(MEM) (((MEM) == DMA_Memory_0) || ((MEM) == DMA_Memory_1))
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the DMA configuration to the default reset state *****/ 
+void DMA_DeInit(DMA_Stream_TypeDef* DMAy_Streamx);
+
+/* Initialization and Configuration functions *********************************/
+void DMA_Init(DMA_Stream_TypeDef* DMAy_Streamx, DMA_InitTypeDef* DMA_InitStruct);
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct);
+void DMA_Cmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState);
+
+/* Optional Configuration functions *******************************************/
+void DMA_PeriphIncOffsetSizeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_Pincos);
+void DMA_FlowControllerConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FlowCtrl);
+
+/* Data Counter functions *****************************************************/
+void DMA_SetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx, uint16_t Counter);
+uint16_t DMA_GetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx);
+
+/* Double Buffer mode functions ***********************************************/
+void DMA_DoubleBufferModeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t Memory1BaseAddr,
+                                uint32_t DMA_CurrentMemory);
+void DMA_DoubleBufferModeCmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState);
+void DMA_MemoryTargetConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t MemoryBaseAddr,
+                            uint32_t DMA_MemoryTarget);
+uint32_t DMA_GetCurrentMemoryTarget(DMA_Stream_TypeDef* DMAy_Streamx);
+
+/* Interrupts and flags management functions **********************************/
+FunctionalState DMA_GetCmdStatus(DMA_Stream_TypeDef* DMAy_Streamx);
+uint32_t DMA_GetFIFOStatus(DMA_Stream_TypeDef* DMAy_Streamx);
+FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG);
+void DMA_ClearFlag(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG);
+void DMA_ITConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState);
+ITStatus DMA_GetITStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT);
+void DMA_ClearITPendingBit(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_DMA_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma2d.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma2d.h
new file mode 100644
index 0000000000000000000000000000000000000000..b0e7966feeb405170f8e5434042eebc65d83c871
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_dma2d.h
@@ -0,0 +1,469 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dma2d.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the DMA2D firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_DMA2D_H
+#define __STM32F4xx_DMA2D_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup DMA2D
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+ 
+/** 
+  * @brief  DMA2D Init structure definition  
+  */
+
+typedef struct
+{
+  uint32_t DMA2D_Mode;                           /*!< configures the DMA2D transfer mode.
+                                                 This parameter can be one value of @ref DMA2D_MODE */
+  
+  uint32_t DMA2D_CMode;                          /*!< configures the color format of the output image.
+                                                 This parameter can be one value of @ref DMA2D_CMODE */
+
+  uint32_t DMA2D_OutputBlue;                     /*!< configures the blue value of the output image. 
+                                                 This parameter must range:
+                                                 - from 0x00 to 0xFF if ARGB8888 color mode is slected
+                                                 - from 0x00 to 0xFF if RGB888 color mode is slected
+                                                 - from 0x00 to 0x1F if RGB565 color mode is slected
+                                                 - from 0x00 to 0x1F if ARGB1555 color mode is slected
+                                                 - from 0x00 to 0x0F if ARGB4444 color mode is slected  */
+
+  uint32_t DMA2D_OutputGreen;                    /*!< configures the green value of the output image. 
+                                                 This parameter must range:
+                                                 - from 0x00 to 0xFF if ARGB8888 color mode is slected
+                                                 - from 0x00 to 0xFF if RGB888 color mode is slected
+                                                 - from 0x00 to 0x2F if RGB565 color mode is slected
+                                                 - from 0x00 to 0x1F if ARGB1555 color mode is slected
+                                                 - from 0x00 to 0x0F if ARGB4444 color mode is slected  */
+            
+  uint32_t DMA2D_OutputRed;                      /*!< configures the red value of the output image. 
+                                                 This parameter must range:
+                                                 - from 0x00 to 0xFF if ARGB8888 color mode is slected
+                                                 - from 0x00 to 0xFF if RGB888 color mode is slected
+                                                 - from 0x00 to 0x1F if RGB565 color mode is slected
+                                                 - from 0x00 to 0x1F if ARGB1555 color mode is slected
+                                                 - from 0x00 to 0x0F if ARGB4444 color mode is slected  */
+  
+  uint32_t DMA2D_OutputAlpha;                    /*!< configures the alpha channel of the output color. 
+                                                 This parameter must range:
+                                                 - from 0x00 to 0xFF if ARGB8888 color mode is slected
+                                                 - from 0x00 to 0x01 if ARGB1555 color mode is slected
+                                                 - from 0x00 to 0x0F if ARGB4444 color mode is slected  */
+
+  uint32_t DMA2D_OutputMemoryAdd;                /*!< Specifies the memory address. This parameter 
+                                                 must be range from 0x00000000 to 0xFFFFFFFF. */
+
+  uint32_t DMA2D_OutputOffset;                   /*!< Specifies the Offset value. This parameter must be range from
+                                                 0x0000 to 0x3FFF. */
+
+  uint32_t DMA2D_NumberOfLine;                   /*!< Configures the number of line of the area to be transfered.
+                                                 This parameter must range from 0x0000 to 0xFFFF */
+            
+  uint32_t DMA2D_PixelPerLine;                   /*!< Configures the number pixel per line of the area to be transfered.
+                                                 This parameter must range from 0x0000 to 0x3FFF */
+} DMA2D_InitTypeDef;
+
+
+
+typedef struct
+{
+  uint32_t DMA2D_FGMA;                           /*!< configures the DMA2D foreground memory address.
+                                                 This parameter must be range from 0x00000000 to 0xFFFFFFFF. */
+  
+  uint32_t DMA2D_FGO;                            /*!< configures the DMA2D foreground offset.
+                                                 This parameter must be range from 0x0000 to 0x3FFF. */
+
+  uint32_t DMA2D_FGCM;                           /*!< configures the DMA2D foreground color mode . 
+                                                 This parameter can be one value of @ref DMA2D_FGCM */
+
+  uint32_t DMA2D_FG_CLUT_CM;                     /*!< configures the DMA2D foreground CLUT color mode. 
+                                                 This parameter can be one value of @ref DMA2D_FG_CLUT_CM */
+            
+  uint32_t DMA2D_FG_CLUT_SIZE;                   /*!< configures the DMA2D foreground CLUT size. 
+                                                 This parameter must range from 0x00 to 0xFF. */
+  
+  uint32_t DMA2D_FGPFC_ALPHA_MODE;               /*!< configures the DMA2D foreground alpha mode. 
+                                                 This parameter can be one value of @ref DMA2D_FGPFC_ALPHA_MODE */
+
+  uint32_t DMA2D_FGPFC_ALPHA_VALUE;              /*!< Specifies the DMA2D foreground alpha value 
+                                                 must be range from 0x00 to 0xFF. */
+
+  uint32_t DMA2D_FGC_BLUE;                       /*!< Specifies the DMA2D foreground blue value 
+                                                 must be range from 0x00 to 0xFF. */
+
+  uint32_t DMA2D_FGC_GREEN;                      /*!< Specifies the DMA2D foreground green value 
+                                                 must be range from 0x00 to 0xFF. */
+
+  uint32_t DMA2D_FGC_RED;                        /*!< Specifies the DMA2D foreground red value 
+                                                 must be range from 0x00 to 0xFF. */
+            
+  uint32_t DMA2D_FGCMAR;                         /*!< Configures the DMA2D foreground CLUT memory address.
+                                                 This parameter must range from 0x00000000 to 0xFFFFFFFF. */
+} DMA2D_FG_InitTypeDef;
+
+
+typedef struct
+{
+  uint32_t DMA2D_BGMA;                           /*!< configures the DMA2D background memory address.
+                                                 This parameter must be range from 0x00000000 to 0xFFFFFFFF. */
+  
+  uint32_t DMA2D_BGO;                            /*!< configures the DMA2D background offset.
+                                                 This parameter must be range from 0x0000 to 0x3FFF. */
+
+  uint32_t DMA2D_BGCM;                           /*!< configures the DMA2D background color mode . 
+                                                 This parameter can be one value of @ref DMA2D_FGCM */
+
+  uint32_t DMA2D_BG_CLUT_CM;                     /*!< configures the DMA2D background CLUT color mode. 
+                                                 This parameter can be one value of @ref DMA2D_FG_CLUT_CM */
+            
+  uint32_t DMA2D_BG_CLUT_SIZE;                   /*!< configures the DMA2D background CLUT size. 
+                                                 This parameter must range from 0x00 to 0xFF. */
+  
+  uint32_t DMA2D_BGPFC_ALPHA_MODE;               /*!< configures the DMA2D background alpha mode. 
+                                                 This parameter can be one value of @ref DMA2D_FGPFC_ALPHA_MODE */
+
+  uint32_t DMA2D_BGPFC_ALPHA_VALUE;              /*!< Specifies the DMA2D background alpha value 
+                                                 must be range from 0x00 to 0xFF. */
+
+  uint32_t DMA2D_BGC_BLUE;                       /*!< Specifies the DMA2D background blue value 
+                                                 must be range from 0x00 to 0xFF. */
+
+  uint32_t DMA2D_BGC_GREEN;                      /*!< Specifies the DMA2D background green value 
+                                                 must be range from 0x00 to 0xFF. */
+
+  uint32_t DMA2D_BGC_RED;                        /*!< Specifies the DMA2D background red value 
+                                                 must be range from 0x00 to 0xFF. */
+            
+  uint32_t DMA2D_BGCMAR;                         /*!< Configures the DMA2D background CLUT memory address.
+                                                 This parameter must range from 0x00000000 to 0xFFFFFFFF. */
+} DMA2D_BG_InitTypeDef;
+
+
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup DMA2D_Exported_Constants
+  * @{
+  */  
+
+/** @defgroup DMA2D_MODE 
+  * @{
+  */
+
+
+#define DMA2D_M2M                            ((uint32_t)0x00000000)
+#define DMA2D_M2M_PFC                        ((uint32_t)0x00010000)
+#define DMA2D_M2M_BLEND                      ((uint32_t)0x00020000)
+#define DMA2D_R2M                            ((uint32_t)0x00030000)
+
+#define IS_DMA2D_MODE(MODE) (((MODE) == DMA2D_M2M) || ((MODE) == DMA2D_M2M_PFC) || \
+                             ((MODE) == DMA2D_M2M_BLEND) || ((MODE) == DMA2D_R2M))
+
+
+/**
+  * @}
+  */  
+
+/** @defgroup DMA2D_CMODE 
+  * @{
+  */
+#define DMA2D_ARGB8888                       ((uint32_t)0x00000000)
+#define DMA2D_RGB888                         ((uint32_t)0x00000001)
+#define DMA2D_RGB565                         ((uint32_t)0x00000002)
+#define DMA2D_ARGB1555                       ((uint32_t)0x00000003)
+#define DMA2D_ARGB4444                       ((uint32_t)0x00000004)
+
+#define IS_DMA2D_CMODE(MODE_ARGB) (((MODE_ARGB) == DMA2D_ARGB8888) || ((MODE_ARGB) == DMA2D_RGB888) || \
+                                   ((MODE_ARGB) == DMA2D_RGB565) || ((MODE_ARGB) == DMA2D_ARGB1555) || \
+                                   ((MODE_ARGB) == DMA2D_ARGB4444))
+
+
+/**
+  * @}
+  */  
+
+/** @defgroup DMA2D_OUTPUT_COLOR 
+  * @{
+  */
+#define DMA2D_Output_Color                 ((uint32_t)0x000000FF)
+
+#define IS_DMA2D_OGREEN(OGREEN) ((OGREEN) <= DMA2D_Output_Color)
+#define IS_DMA2D_ORED(ORED)     ((ORED) <= DMA2D_Output_Color)
+#define IS_DMA2D_OBLUE(OBLUE)   ((OBLUE) <= DMA2D_Output_Color)
+#define IS_DMA2D_OALPHA(OALPHA) ((OALPHA) <= DMA2D_Output_Color)
+
+/**
+  * @}
+  */  
+
+/** @defgroup DMA2D_OUTPUT_OFFSET 
+  * @{
+  */
+#define DMA2D_OUTPUT_OFFSET      ((uint32_t)0x00003FFF)
+
+#define IS_DMA2D_OUTPUT_OFFSET(OOFFSET) ((OOFFSET) <= DMA2D_OUTPUT_OFFSET)
+
+
+/**
+  * @}
+  */  
+
+/** @defgroup DMA2D_SIZE 
+  * @{
+  */
+
+#define DMA2D_pixel          ((uint32_t)0x00003FFF)
+#define DMA2D_Line           ((uint32_t)0x0000FFFF)
+
+#define IS_DMA2D_LINE(LINE)  ((LINE) <= DMA2D_Line)
+#define IS_DMA2D_PIXEL(PIXEL) ((PIXEL) <= DMA2D_pixel)
+
+
+/**
+  * @}
+  */  
+
+/** @defgroup DMA2D_OFFSET
+  * @{
+  */
+#define OFFSET               ((uint32_t)0x00003FFF)
+
+#define IS_DMA2D_FGO(FGO)  ((FGO) <= OFFSET)
+
+#define IS_DMA2D_BGO(BGO)  ((BGO) <= OFFSET) 
+
+/**
+  * @}
+  */  
+
+
+/** @defgroup DMA2D_FGCM
+  * @{
+  */
+
+#define CM_ARGB8888        ((uint32_t)0x00000000)
+#define CM_RGB888          ((uint32_t)0x00000001)
+#define CM_RGB565          ((uint32_t)0x00000002)
+#define CM_ARGB1555        ((uint32_t)0x00000003)
+#define CM_ARGB4444        ((uint32_t)0x00000004)
+#define CM_L8              ((uint32_t)0x00000005)
+#define CM_AL44            ((uint32_t)0x00000006)
+#define CM_AL88            ((uint32_t)0x00000007)
+#define CM_L4              ((uint32_t)0x00000008)
+#define CM_A8              ((uint32_t)0x00000009)
+#define CM_A4              ((uint32_t)0x0000000A)
+
+#define IS_DMA2D_FGCM(FGCM) (((FGCM) == CM_ARGB8888) || ((FGCM) == CM_RGB888) || \
+                             ((FGCM) == CM_RGB565) || ((FGCM) == CM_ARGB1555) || \
+                             ((FGCM) == CM_ARGB4444) || ((FGCM) == CM_L8) || \
+                             ((FGCM) == CM_AL44) || ((FGCM) == CM_AL88) || \
+                             ((FGCM) == CM_L4) || ((FGCM) == CM_A8) || \
+                             ((FGCM) == CM_A4))
+
+#define IS_DMA2D_BGCM(BGCM) (((BGCM) == CM_ARGB8888) || ((BGCM) == CM_RGB888) || \
+                             ((BGCM) == CM_RGB565) || ((BGCM) == CM_ARGB1555) || \
+                             ((BGCM) == CM_ARGB4444) || ((BGCM) == CM_L8) || \
+                             ((BGCM) == CM_AL44) || ((BGCM) == CM_AL88) || \
+                             ((BGCM) == CM_L4) || ((BGCM) == CM_A8) || \
+                             ((BGCM) == CM_A4))
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA2D_FG_CLUT_CM
+  * @{
+  */
+
+#define CLUT_CM_ARGB8888        ((uint32_t)0x00000000)
+#define CLUT_CM_RGB888          ((uint32_t)0x00000001)
+
+#define IS_DMA2D_FG_CLUT_CM(FG_CLUT_CM) (((FG_CLUT_CM) == CLUT_CM_ARGB8888) || ((FG_CLUT_CM) == CLUT_CM_RGB888))
+
+#define IS_DMA2D_BG_CLUT_CM(BG_CLUT_CM) (((BG_CLUT_CM) == CLUT_CM_ARGB8888) || ((BG_CLUT_CM) == CLUT_CM_RGB888))
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA2D_FG_COLOR_VALUE
+  * @{
+  */
+
+#define COLOR_VALUE             ((uint32_t)0x000000FF)
+
+#define IS_DMA2D_FG_CLUT_SIZE(FG_CLUT_SIZE) ((FG_CLUT_SIZE) <= COLOR_VALUE)
+
+#define IS_DMA2D_FG_ALPHA_VALUE(FG_ALPHA_VALUE) ((FG_ALPHA_VALUE) <= COLOR_VALUE)
+#define IS_DMA2D_FGC_BLUE(FGC_BLUE) ((FGC_BLUE) <= COLOR_VALUE)
+#define IS_DMA2D_FGC_GREEN(FGC_GREEN) ((FGC_GREEN) <= COLOR_VALUE)
+#define IS_DMA2D_FGC_RED(FGC_RED) ((FGC_RED) <= COLOR_VALUE)
+
+#define IS_DMA2D_BG_CLUT_SIZE(BG_CLUT_SIZE) ((BG_CLUT_SIZE) <= COLOR_VALUE)
+
+#define IS_DMA2D_BG_ALPHA_VALUE(BG_ALPHA_VALUE) ((BG_ALPHA_VALUE) <= COLOR_VALUE)
+#define IS_DMA2D_BGC_BLUE(BGC_BLUE) ((BGC_BLUE) <= COLOR_VALUE)
+#define IS_DMA2D_BGC_GREEN(BGC_GREEN) ((BGC_GREEN) <= COLOR_VALUE)
+#define IS_DMA2D_BGC_RED(BGC_RED) ((BGC_RED) <= COLOR_VALUE)
+
+/**
+  * @}
+  */
+
+/** DMA2D_FGPFC_ALPHA_MODE
+  * @{
+  */
+
+#define NO_MODIF_ALPHA_VALUE       ((uint32_t)0x00000000)
+#define REPLACE_ALPHA_VALUE        ((uint32_t)0x00000001)
+#define COMBINE_ALPHA_VALUE        ((uint32_t)0x00000002)
+
+#define IS_DMA2D_FG_ALPHA_MODE(FG_ALPHA_MODE) (((FG_ALPHA_MODE) ==  NO_MODIF_ALPHA_VALUE) || \
+                                              ((FG_ALPHA_MODE) == REPLACE_ALPHA_VALUE) || \
+                                              ((FG_ALPHA_MODE) == COMBINE_ALPHA_VALUE))
+
+#define IS_DMA2D_BG_ALPHA_MODE(BG_ALPHA_MODE) (((BG_ALPHA_MODE) ==  NO_MODIF_ALPHA_VALUE) || \
+                                              ((BG_ALPHA_MODE) == REPLACE_ALPHA_VALUE) || \
+                                              ((BG_ALPHA_MODE) == COMBINE_ALPHA_VALUE))
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA2D_Interrupts 
+  * @{
+  */
+
+#define DMA2D_IT_CE                      DMA2D_CR_CEIE
+#define DMA2D_IT_CTC                     DMA2D_CR_CTCIE
+#define DMA2D_IT_CAE                     DMA2D_CR_CAEIE
+#define DMA2D_IT_TW                      DMA2D_CR_TWIE
+#define DMA2D_IT_TC                      DMA2D_CR_TCIE
+#define DMA2D_IT_TE                      DMA2D_CR_TEIE
+
+#define IS_DMA2D_IT(IT) (((IT) == DMA2D_IT_CTC) || ((IT) == DMA2D_IT_CAE) || \
+                        ((IT) == DMA2D_IT_TW) || ((IT) == DMA2D_IT_TC) || \
+                        ((IT) == DMA2D_IT_TE) || ((IT) == DMA2D_IT_CE))
+
+/**
+  * @}
+  */
+      
+/** @defgroup DMA2D_Flag 
+  * @{
+  */
+
+#define DMA2D_FLAG_CE                      DMA2D_ISR_CEIF
+#define DMA2D_FLAG_CTC                     DMA2D_ISR_CTCIF
+#define DMA2D_FLAG_CAE                     DMA2D_ISR_CAEIF
+#define DMA2D_FLAG_TW                      DMA2D_ISR_TWIF
+#define DMA2D_FLAG_TC                      DMA2D_ISR_TCIF
+#define DMA2D_FLAG_TE                      DMA2D_ISR_TEIF
+
+
+#define IS_DMA2D_GET_FLAG(FLAG) (((FLAG) == DMA2D_FLAG_CTC) || ((FLAG) == DMA2D_FLAG_CAE) || \
+                                ((FLAG) == DMA2D_FLAG_TW) || ((FLAG) == DMA2D_FLAG_TC) || \
+                                ((FLAG) == DMA2D_FLAG_TE) || ((FLAG) == DMA2D_FLAG_CE)) 
+
+
+/**
+  * @}
+  */
+      
+/** @defgroup DMA2D_DeadTime 
+  * @{
+  */
+
+#define DEADTIME                  ((uint32_t)0x000000FF)
+  
+#define IS_DMA2D_DEAD_TIME(DEAD_TIME) ((DEAD_TIME) <= DEADTIME)
+
+
+#define LINE_WATERMARK            DMA2D_LWR_LW
+
+#define IS_DMA2D_LineWatermark(LineWatermark) ((LineWatermark) <= LINE_WATERMARK)
+
+/**
+  * @}
+  */
+  
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+/*  Function used to set the DMA2D configuration to the default reset state *****/
+void DMA2D_DeInit(void);
+
+/* Initialization and Configuration functions *********************************/
+void DMA2D_Init(DMA2D_InitTypeDef* DMA2D_InitStruct);
+void DMA2D_StructInit(DMA2D_InitTypeDef* DMA2D_InitStruct);
+void DMA2D_StartTransfer(void);
+void DMA2D_AbortTransfer(void);
+void DMA2D_Suspend(FunctionalState NewState);
+void DMA2D_FGConfig(DMA2D_FG_InitTypeDef* DMA2D_FG_InitStruct);
+void DMA2D_FG_StructInit(DMA2D_FG_InitTypeDef* DMA2D_FG_InitStruct);
+void DMA2D_BGConfig(DMA2D_BG_InitTypeDef* DMA2D_BG_InitStruct);
+void DMA2D_BG_StructInit(DMA2D_BG_InitTypeDef* DMA2D_BG_InitStruct);
+void DMA2D_FGStart(FunctionalState NewState);
+void DMA2D_BGStart(FunctionalState NewState);
+void DMA2D_DeadTimeConfig(uint32_t DMA2D_DeadTime, FunctionalState NewState);
+void DMA2D_LineWatermarkConfig(uint32_t DMA2D_LWatermarkConfig);
+
+/* Interrupts and flags management functions **********************************/
+void DMA2D_ITConfig(uint32_t DMA2D_IT, FunctionalState NewState);
+FlagStatus DMA2D_GetFlagStatus(uint32_t DMA2D_FLAG);
+void DMA2D_ClearFlag(uint32_t DMA2D_FLAG);
+ITStatus DMA2D_GetITStatus(uint32_t DMA2D_IT);
+void DMA2D_ClearITPendingBit(uint32_t DMA2D_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_DMA2D_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h
new file mode 100644
index 0000000000000000000000000000000000000000..39105e3b7e9043d8402c8b5f0c6ef7cc2b1f443d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_exti.h
@@ -0,0 +1,183 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_exti.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the EXTI firmware
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_EXTI_H
+#define __STM32F4xx_EXTI_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup EXTI
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  EXTI mode enumeration  
+  */
+
+typedef enum
+{
+  EXTI_Mode_Interrupt = 0x00,
+  EXTI_Mode_Event = 0x04
+}EXTIMode_TypeDef;
+
+#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event))
+
+/** 
+  * @brief  EXTI Trigger enumeration  
+  */
+
+typedef enum
+{
+  EXTI_Trigger_Rising = 0x08,
+  EXTI_Trigger_Falling = 0x0C,  
+  EXTI_Trigger_Rising_Falling = 0x10
+}EXTITrigger_TypeDef;
+
+#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \
+                                  ((TRIGGER) == EXTI_Trigger_Falling) || \
+                                  ((TRIGGER) == EXTI_Trigger_Rising_Falling))
+/** 
+  * @brief  EXTI Init Structure definition  
+  */
+
+typedef struct
+{
+  uint32_t EXTI_Line;               /*!< Specifies the EXTI lines to be enabled or disabled.
+                                         This parameter can be any combination value of @ref EXTI_Lines */
+   
+  EXTIMode_TypeDef EXTI_Mode;       /*!< Specifies the mode for the EXTI lines.
+                                         This parameter can be a value of @ref EXTIMode_TypeDef */
+
+  EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines.
+                                         This parameter can be a value of @ref EXTITrigger_TypeDef */
+
+  FunctionalState EXTI_LineCmd;     /*!< Specifies the new state of the selected EXTI lines.
+                                         This parameter can be set either to ENABLE or DISABLE */ 
+}EXTI_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup EXTI_Exported_Constants
+  * @{
+  */
+
+/** @defgroup EXTI_Lines 
+  * @{
+  */
+
+#define EXTI_Line0       ((uint32_t)0x00001)     /*!< External interrupt line 0 */
+#define EXTI_Line1       ((uint32_t)0x00002)     /*!< External interrupt line 1 */
+#define EXTI_Line2       ((uint32_t)0x00004)     /*!< External interrupt line 2 */
+#define EXTI_Line3       ((uint32_t)0x00008)     /*!< External interrupt line 3 */
+#define EXTI_Line4       ((uint32_t)0x00010)     /*!< External interrupt line 4 */
+#define EXTI_Line5       ((uint32_t)0x00020)     /*!< External interrupt line 5 */
+#define EXTI_Line6       ((uint32_t)0x00040)     /*!< External interrupt line 6 */
+#define EXTI_Line7       ((uint32_t)0x00080)     /*!< External interrupt line 7 */
+#define EXTI_Line8       ((uint32_t)0x00100)     /*!< External interrupt line 8 */
+#define EXTI_Line9       ((uint32_t)0x00200)     /*!< External interrupt line 9 */
+#define EXTI_Line10      ((uint32_t)0x00400)     /*!< External interrupt line 10 */
+#define EXTI_Line11      ((uint32_t)0x00800)     /*!< External interrupt line 11 */
+#define EXTI_Line12      ((uint32_t)0x01000)     /*!< External interrupt line 12 */
+#define EXTI_Line13      ((uint32_t)0x02000)     /*!< External interrupt line 13 */
+#define EXTI_Line14      ((uint32_t)0x04000)     /*!< External interrupt line 14 */
+#define EXTI_Line15      ((uint32_t)0x08000)     /*!< External interrupt line 15 */
+#define EXTI_Line16      ((uint32_t)0x10000)     /*!< External interrupt line 16 Connected to the PVD Output */
+#define EXTI_Line17      ((uint32_t)0x20000)     /*!< External interrupt line 17 Connected to the RTC Alarm event */
+#define EXTI_Line18      ((uint32_t)0x40000)     /*!< External interrupt line 18 Connected to the USB OTG FS Wakeup from suspend event */                                    
+#define EXTI_Line19      ((uint32_t)0x80000)     /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */
+#define EXTI_Line20      ((uint32_t)0x00100000)  /*!< External interrupt line 20 Connected to the USB OTG HS (configured in FS) Wakeup event  */
+#define EXTI_Line21      ((uint32_t)0x00200000)  /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */                                               
+#define EXTI_Line22      ((uint32_t)0x00400000)  /*!< External interrupt line 22 Connected to the RTC Wakeup event */                                               
+                                          
+#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFF800000) == 0x00) && ((LINE) != (uint16_t)0x00))
+
+#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \
+                                ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \
+                                ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \
+                                ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \
+                                ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \
+                                ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \
+                                ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \
+                                ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \
+                                ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \
+                                ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19) || \
+                                ((LINE) == EXTI_Line20) || ((LINE) == EXTI_Line21) ||\
+                                ((LINE) == EXTI_Line22))
+                    
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/*  Function used to set the EXTI configuration to the default reset state *****/
+void EXTI_DeInit(void);
+
+/* Initialization and Configuration functions *********************************/
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct);
+void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line);
+
+/* Interrupts and flags management functions **********************************/
+FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line);
+void EXTI_ClearFlag(uint32_t EXTI_Line);
+ITStatus EXTI_GetITStatus(uint32_t EXTI_Line);
+void EXTI_ClearITPendingBit(uint32_t EXTI_Line);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_EXTI_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h
new file mode 100644
index 0000000000000000000000000000000000000000..ee3e9a9feb92e22e5e5cd127840673a798ff3763
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_flash.h
@@ -0,0 +1,482 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_flash.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the FLASH 
+  *          firmware library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_FLASH_H
+#define __STM32F4xx_FLASH_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup FLASH
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+/** 
+  * @brief FLASH Status  
+  */ 
+typedef enum
+{ 
+  FLASH_BUSY = 1,
+  FLASH_ERROR_RD,
+  FLASH_ERROR_PGS,
+  FLASH_ERROR_PGP,
+  FLASH_ERROR_PGA,
+  FLASH_ERROR_WRP,
+  FLASH_ERROR_PROGRAM,
+  FLASH_ERROR_OPERATION,
+  FLASH_COMPLETE
+}FLASH_Status;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup FLASH_Exported_Constants
+  * @{
+  */  
+
+/** @defgroup Flash_Latency 
+  * @{
+  */ 
+#define FLASH_Latency_0                ((uint8_t)0x0000)  /*!< FLASH Zero Latency cycle      */
+#define FLASH_Latency_1                ((uint8_t)0x0001)  /*!< FLASH One Latency cycle       */
+#define FLASH_Latency_2                ((uint8_t)0x0002)  /*!< FLASH Two Latency cycles      */
+#define FLASH_Latency_3                ((uint8_t)0x0003)  /*!< FLASH Three Latency cycles    */
+#define FLASH_Latency_4                ((uint8_t)0x0004)  /*!< FLASH Four Latency cycles     */
+#define FLASH_Latency_5                ((uint8_t)0x0005)  /*!< FLASH Five Latency cycles     */
+#define FLASH_Latency_6                ((uint8_t)0x0006)  /*!< FLASH Six Latency cycles      */
+#define FLASH_Latency_7                ((uint8_t)0x0007)  /*!< FLASH Seven Latency cycles    */
+#define FLASH_Latency_8                ((uint8_t)0x0008)  /*!< FLASH Eight Latency cycles    */
+#define FLASH_Latency_9                ((uint8_t)0x0009)  /*!< FLASH Nine Latency cycles     */
+#define FLASH_Latency_10               ((uint8_t)0x000A)  /*!< FLASH Ten Latency cycles      */
+#define FLASH_Latency_11               ((uint8_t)0x000B)  /*!< FLASH Eleven Latency cycles   */
+#define FLASH_Latency_12               ((uint8_t)0x000C)  /*!< FLASH Twelve Latency cycles   */
+#define FLASH_Latency_13               ((uint8_t)0x000D)  /*!< FLASH Thirteen Latency cycles */
+#define FLASH_Latency_14               ((uint8_t)0x000E)  /*!< FLASH Fourteen Latency cycles */
+#define FLASH_Latency_15               ((uint8_t)0x000F)  /*!< FLASH Fifteen Latency cycles  */
+
+
+#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0)  || \
+                                   ((LATENCY) == FLASH_Latency_1)  || \
+                                   ((LATENCY) == FLASH_Latency_2)  || \
+                                   ((LATENCY) == FLASH_Latency_3)  || \
+                                   ((LATENCY) == FLASH_Latency_4)  || \
+                                   ((LATENCY) == FLASH_Latency_5)  || \
+                                   ((LATENCY) == FLASH_Latency_6)  || \
+                                   ((LATENCY) == FLASH_Latency_7)  || \
+                                   ((LATENCY) == FLASH_Latency_8)  || \
+                                   ((LATENCY) == FLASH_Latency_9)  || \
+                                   ((LATENCY) == FLASH_Latency_10) || \
+                                   ((LATENCY) == FLASH_Latency_11) || \
+                                   ((LATENCY) == FLASH_Latency_12) || \
+                                   ((LATENCY) == FLASH_Latency_13) || \
+                                   ((LATENCY) == FLASH_Latency_14) || \
+                                   ((LATENCY) == FLASH_Latency_15))
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Voltage_Range 
+  * @{
+  */ 
+#define VoltageRange_1        ((uint8_t)0x00)  /*!< Device operating range: 1.8V to 2.1V */
+#define VoltageRange_2        ((uint8_t)0x01)  /*!<Device operating range: 2.1V to 2.7V */
+#define VoltageRange_3        ((uint8_t)0x02)  /*!<Device operating range: 2.7V to 3.6V */
+#define VoltageRange_4        ((uint8_t)0x03)  /*!<Device operating range: 2.7V to 3.6V + External Vpp */
+
+#define IS_VOLTAGERANGE(RANGE)(((RANGE) == VoltageRange_1) || \
+                               ((RANGE) == VoltageRange_2) || \
+                               ((RANGE) == VoltageRange_3) || \
+                               ((RANGE) == VoltageRange_4))                                                                                                               
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Sectors
+  * @{
+  */
+#define FLASH_Sector_0     ((uint16_t)0x0000) /*!< Sector Number 0   */
+#define FLASH_Sector_1     ((uint16_t)0x0008) /*!< Sector Number 1   */
+#define FLASH_Sector_2     ((uint16_t)0x0010) /*!< Sector Number 2   */
+#define FLASH_Sector_3     ((uint16_t)0x0018) /*!< Sector Number 3   */
+#define FLASH_Sector_4     ((uint16_t)0x0020) /*!< Sector Number 4   */
+#define FLASH_Sector_5     ((uint16_t)0x0028) /*!< Sector Number 5   */
+#define FLASH_Sector_6     ((uint16_t)0x0030) /*!< Sector Number 6   */
+#define FLASH_Sector_7     ((uint16_t)0x0038) /*!< Sector Number 7   */
+#define FLASH_Sector_8     ((uint16_t)0x0040) /*!< Sector Number 8   */
+#define FLASH_Sector_9     ((uint16_t)0x0048) /*!< Sector Number 9   */
+#define FLASH_Sector_10    ((uint16_t)0x0050) /*!< Sector Number 10  */
+#define FLASH_Sector_11    ((uint16_t)0x0058) /*!< Sector Number 11  */
+#define FLASH_Sector_12    ((uint16_t)0x0080) /*!< Sector Number 12  */
+#define FLASH_Sector_13    ((uint16_t)0x0088) /*!< Sector Number 13  */
+#define FLASH_Sector_14    ((uint16_t)0x0090) /*!< Sector Number 14  */
+#define FLASH_Sector_15    ((uint16_t)0x0098) /*!< Sector Number 15  */
+#define FLASH_Sector_16    ((uint16_t)0x00A0) /*!< Sector Number 16  */
+#define FLASH_Sector_17    ((uint16_t)0x00A8) /*!< Sector Number 17  */
+#define FLASH_Sector_18    ((uint16_t)0x00B0) /*!< Sector Number 18  */
+#define FLASH_Sector_19    ((uint16_t)0x00B8) /*!< Sector Number 19  */
+#define FLASH_Sector_20    ((uint16_t)0x00C0) /*!< Sector Number 20  */
+#define FLASH_Sector_21    ((uint16_t)0x00C8) /*!< Sector Number 21  */
+#define FLASH_Sector_22    ((uint16_t)0x00D0) /*!< Sector Number 22  */
+#define FLASH_Sector_23    ((uint16_t)0x00D8) /*!< Sector Number 23  */
+
+#define IS_FLASH_SECTOR(SECTOR) (((SECTOR) == FLASH_Sector_0)   || ((SECTOR) == FLASH_Sector_1)   ||\
+                                 ((SECTOR) == FLASH_Sector_2)   || ((SECTOR) == FLASH_Sector_3)   ||\
+                                 ((SECTOR) == FLASH_Sector_4)   || ((SECTOR) == FLASH_Sector_5)   ||\
+                                 ((SECTOR) == FLASH_Sector_6)   || ((SECTOR) == FLASH_Sector_7)   ||\
+                                 ((SECTOR) == FLASH_Sector_8)   || ((SECTOR) == FLASH_Sector_9)   ||\
+                                 ((SECTOR) == FLASH_Sector_10)  || ((SECTOR) == FLASH_Sector_11)  ||\
+                                 ((SECTOR) == FLASH_Sector_12)  || ((SECTOR) == FLASH_Sector_13)  ||\
+                                 ((SECTOR) == FLASH_Sector_14)  || ((SECTOR) == FLASH_Sector_15)  ||\
+                                 ((SECTOR) == FLASH_Sector_16)  || ((SECTOR) == FLASH_Sector_17)  ||\
+                                 ((SECTOR) == FLASH_Sector_18)  || ((SECTOR) == FLASH_Sector_19)  ||\
+                                 ((SECTOR) == FLASH_Sector_20)  || ((SECTOR) == FLASH_Sector_21)  ||\
+                                 ((SECTOR) == FLASH_Sector_22)  || ((SECTOR) == FLASH_Sector_23))
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x081FFFFF)) ||\
+                                   (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F)))  
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#if defined (STM32F40_41xxx)
+#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) ||\
+                                   (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F))) 
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F401xx)                                   
+#define IS_FLASH_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x0803FFFF)) ||\
+                                   (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F)))                                                                       
+#endif /* STM32F401xx */
+/**
+  * @}
+  */ 
+
+/** @defgroup Option_Bytes_Write_Protection 
+  * @{
+  */ 
+#define OB_WRP_Sector_0       ((uint32_t)0x00000001) /*!< Write protection of Sector0     */
+#define OB_WRP_Sector_1       ((uint32_t)0x00000002) /*!< Write protection of Sector1     */
+#define OB_WRP_Sector_2       ((uint32_t)0x00000004) /*!< Write protection of Sector2     */
+#define OB_WRP_Sector_3       ((uint32_t)0x00000008) /*!< Write protection of Sector3     */
+#define OB_WRP_Sector_4       ((uint32_t)0x00000010) /*!< Write protection of Sector4     */
+#define OB_WRP_Sector_5       ((uint32_t)0x00000020) /*!< Write protection of Sector5     */
+#define OB_WRP_Sector_6       ((uint32_t)0x00000040) /*!< Write protection of Sector6     */
+#define OB_WRP_Sector_7       ((uint32_t)0x00000080) /*!< Write protection of Sector7     */
+#define OB_WRP_Sector_8       ((uint32_t)0x00000100) /*!< Write protection of Sector8     */
+#define OB_WRP_Sector_9       ((uint32_t)0x00000200) /*!< Write protection of Sector9     */
+#define OB_WRP_Sector_10      ((uint32_t)0x00000400) /*!< Write protection of Sector10    */
+#define OB_WRP_Sector_11      ((uint32_t)0x00000800) /*!< Write protection of Sector11    */
+#define OB_WRP_Sector_12      ((uint32_t)0x00000001) /*!< Write protection of Sector12    */
+#define OB_WRP_Sector_13      ((uint32_t)0x00000002) /*!< Write protection of Sector13    */
+#define OB_WRP_Sector_14      ((uint32_t)0x00000004) /*!< Write protection of Sector14    */
+#define OB_WRP_Sector_15      ((uint32_t)0x00000008) /*!< Write protection of Sector15    */
+#define OB_WRP_Sector_16      ((uint32_t)0x00000010) /*!< Write protection of Sector16    */
+#define OB_WRP_Sector_17      ((uint32_t)0x00000020) /*!< Write protection of Sector17    */
+#define OB_WRP_Sector_18      ((uint32_t)0x00000040) /*!< Write protection of Sector18    */
+#define OB_WRP_Sector_19      ((uint32_t)0x00000080) /*!< Write protection of Sector19    */
+#define OB_WRP_Sector_20      ((uint32_t)0x00000100) /*!< Write protection of Sector20    */
+#define OB_WRP_Sector_21      ((uint32_t)0x00000200) /*!< Write protection of Sector21    */
+#define OB_WRP_Sector_22      ((uint32_t)0x00000400) /*!< Write protection of Sector22    */
+#define OB_WRP_Sector_23      ((uint32_t)0x00000800) /*!< Write protection of Sector23    */
+#define OB_WRP_Sector_All     ((uint32_t)0x00000FFF) /*!< Write protection of all Sectors */
+
+#define IS_OB_WRP(SECTOR)((((SECTOR) & (uint32_t)0xFFFFF000) == 0x00000000) && ((SECTOR) != 0x00000000))
+/**
+  * @}
+  */
+
+/** @defgroup  Selection_Protection_Mode
+  * @{
+  */
+#define OB_PcROP_Disable   ((uint8_t)0x00) /*!< Disabled PcROP, nWPRi bits used for Write Protection on sector i */
+#define OB_PcROP_Enable    ((uint8_t)0x80) /*!< Enable PcROP, nWPRi bits used for PCRoP Protection on sector i   */
+#define IS_OB_PCROP_SELECT(PCROP) (((PCROP) == OB_PcROP_Disable) || ((PCROP) == OB_PcROP_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup Option_Bytes_PC_ReadWrite_Protection 
+  * @{
+  */ 
+#define OB_PCROP_Sector_0        ((uint32_t)0x00000001) /*!< PC Read/Write protection of Sector0      */
+#define OB_PCROP_Sector_1        ((uint32_t)0x00000002) /*!< PC Read/Write protection of Sector1      */
+#define OB_PCROP_Sector_2        ((uint32_t)0x00000004) /*!< PC Read/Write protection of Sector2      */
+#define OB_PCROP_Sector_3        ((uint32_t)0x00000008) /*!< PC Read/Write protection of Sector3      */
+#define OB_PCROP_Sector_4        ((uint32_t)0x00000010) /*!< PC Read/Write protection of Sector4      */
+#define OB_PCROP_Sector_5        ((uint32_t)0x00000020) /*!< PC Read/Write protection of Sector5      */
+#define OB_PCROP_Sector_6        ((uint32_t)0x00000040) /*!< PC Read/Write protection of Sector6      */
+#define OB_PCROP_Sector_7        ((uint32_t)0x00000080) /*!< PC Read/Write protection of Sector7      */
+#define OB_PCROP_Sector_8        ((uint32_t)0x00000100) /*!< PC Read/Write protection of Sector8      */
+#define OB_PCROP_Sector_9        ((uint32_t)0x00000200) /*!< PC Read/Write protection of Sector9      */
+#define OB_PCROP_Sector_10       ((uint32_t)0x00000400) /*!< PC Read/Write protection of Sector10     */
+#define OB_PCROP_Sector_11       ((uint32_t)0x00000800) /*!< PC Read/Write protection of Sector11     */
+#define OB_PCROP_Sector_12       ((uint32_t)0x00000001) /*!< PC Read/Write protection of Sector12     */
+#define OB_PCROP_Sector_13       ((uint32_t)0x00000002) /*!< PC Read/Write protection of Sector13     */
+#define OB_PCROP_Sector_14       ((uint32_t)0x00000004) /*!< PC Read/Write protection of Sector14     */
+#define OB_PCROP_Sector_15       ((uint32_t)0x00000008) /*!< PC Read/Write protection of Sector15     */
+#define OB_PCROP_Sector_16       ((uint32_t)0x00000010) /*!< PC Read/Write protection of Sector16     */
+#define OB_PCROP_Sector_17       ((uint32_t)0x00000020) /*!< PC Read/Write protection of Sector17     */
+#define OB_PCROP_Sector_18       ((uint32_t)0x00000040) /*!< PC Read/Write protection of Sector18     */
+#define OB_PCROP_Sector_19       ((uint32_t)0x00000080) /*!< PC Read/Write protection of Sector19     */
+#define OB_PCROP_Sector_20       ((uint32_t)0x00000100) /*!< PC Read/Write protection of Sector20     */
+#define OB_PCROP_Sector_21       ((uint32_t)0x00000200) /*!< PC Read/Write protection of Sector21     */
+#define OB_PCROP_Sector_22       ((uint32_t)0x00000400) /*!< PC Read/Write protection of Sector22     */
+#define OB_PCROP_Sector_23       ((uint32_t)0x00000800) /*!< PC Read/Write protection of Sector23     */
+#define OB_PCROP_Sector_All      ((uint32_t)0x00000FFF) /*!< PC Read/Write protection of all Sectors  */
+
+#define IS_OB_PCROP(SECTOR)((((SECTOR) & (uint32_t)0xFFFFF000) == 0x00000000) && ((SECTOR) != 0x00000000))
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Option_Bytes_Read_Protection 
+  * @{
+  */
+#define OB_RDP_Level_0   ((uint8_t)0xAA)
+#define OB_RDP_Level_1   ((uint8_t)0x55)
+/*#define OB_RDP_Level_2   ((uint8_t)0xCC)*/ /*!< Warning: When enabling read protection level 2 
+                                                  it's no more possible to go back to level 1 or 0 */
+#define IS_OB_RDP(LEVEL) (((LEVEL) == OB_RDP_Level_0)||\
+                          ((LEVEL) == OB_RDP_Level_1))/*||\
+                          ((LEVEL) == OB_RDP_Level_2))*/
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Option_Bytes_IWatchdog 
+  * @{
+  */ 
+#define OB_IWDG_SW                     ((uint8_t)0x20)  /*!< Software IWDG selected */
+#define OB_IWDG_HW                     ((uint8_t)0x00)  /*!< Hardware IWDG selected */
+#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW))
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Option_Bytes_nRST_STOP 
+  * @{
+  */ 
+#define OB_STOP_NoRST                  ((uint8_t)0x40) /*!< No reset generated when entering in STOP */
+#define OB_STOP_RST                    ((uint8_t)0x00) /*!< Reset generated when entering in STOP */
+#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup FLASH_Option_Bytes_nRST_STDBY 
+  * @{
+  */ 
+#define OB_STDBY_NoRST                 ((uint8_t)0x80) /*!< No reset generated when entering in STANDBY */
+#define OB_STDBY_RST                   ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */
+#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST))
+/**
+  * @}
+  */
+  
+/** @defgroup FLASH_BOR_Reset_Level 
+  * @{
+  */  
+#define OB_BOR_LEVEL3          ((uint8_t)0x00)  /*!< Supply voltage ranges from 2.70 to 3.60 V */
+#define OB_BOR_LEVEL2          ((uint8_t)0x04)  /*!< Supply voltage ranges from 2.40 to 2.70 V */
+#define OB_BOR_LEVEL1          ((uint8_t)0x08)  /*!< Supply voltage ranges from 2.10 to 2.40 V */
+#define OB_BOR_OFF             ((uint8_t)0x0C)  /*!< Supply voltage ranges from 1.62 to 2.10 V */
+#define IS_OB_BOR(LEVEL) (((LEVEL) == OB_BOR_LEVEL1) || ((LEVEL) == OB_BOR_LEVEL2) ||\
+                          ((LEVEL) == OB_BOR_LEVEL3) || ((LEVEL) == OB_BOR_OFF))
+/**
+  * @}
+  */
+  
+/** @defgroup FLASH_Dual_Boot
+  * @{
+  */
+#define OB_Dual_BootEnabled   ((uint8_t)0x10) /*!< Dual Bank Boot Enable                             */
+#define OB_Dual_BootDisabled  ((uint8_t)0x00) /*!< Dual Bank Boot Disable, always boot on User Flash */
+#define IS_OB_BOOT(BOOT) (((BOOT) == OB_Dual_BootEnabled) || ((BOOT) == OB_Dual_BootDisabled))
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Interrupts 
+  * @{
+  */ 
+#define FLASH_IT_EOP                   ((uint32_t)0x01000000)  /*!< End of FLASH Operation Interrupt source */
+#define FLASH_IT_ERR                   ((uint32_t)0x02000000)  /*!< Error Interrupt source */
+#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFCFFFFFF) == 0x00000000) && ((IT) != 0x00000000))
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Flags 
+  * @{
+  */ 
+#define FLASH_FLAG_EOP                 ((uint32_t)0x00000001)  /*!< FLASH End of Operation flag               */
+#define FLASH_FLAG_OPERR               ((uint32_t)0x00000002)  /*!< FLASH operation Error flag                */
+#define FLASH_FLAG_WRPERR              ((uint32_t)0x00000010)  /*!< FLASH Write protected error flag          */
+#define FLASH_FLAG_PGAERR              ((uint32_t)0x00000020)  /*!< FLASH Programming Alignment error flag    */
+#define FLASH_FLAG_PGPERR              ((uint32_t)0x00000040)  /*!< FLASH Programming Parallelism error flag  */
+#define FLASH_FLAG_PGSERR              ((uint32_t)0x00000080)  /*!< FLASH Programming Sequence error flag     */
+#define FLASH_FLAG_RDERR               ((uint32_t)0x00000100)  /*!< Read Protection error flag (PCROP)        */
+#define FLASH_FLAG_BSY                 ((uint32_t)0x00010000)  /*!< FLASH Busy flag                           */ 
+#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFE0C) == 0x00000000) && ((FLAG) != 0x00000000))
+#define IS_FLASH_GET_FLAG(FLAG)  (((FLAG) == FLASH_FLAG_EOP)    || ((FLAG) == FLASH_FLAG_OPERR)  || \
+                                  ((FLAG) == FLASH_FLAG_WRPERR) || ((FLAG) == FLASH_FLAG_PGAERR) || \
+                                  ((FLAG) == FLASH_FLAG_PGPERR) || ((FLAG) == FLASH_FLAG_PGSERR) || \
+                                  ((FLAG) == FLASH_FLAG_BSY)    || ((FLAG) == FLASH_FLAG_RDERR))
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Program_Parallelism   
+  * @{
+  */
+#define FLASH_PSIZE_BYTE           ((uint32_t)0x00000000)
+#define FLASH_PSIZE_HALF_WORD      ((uint32_t)0x00000100)
+#define FLASH_PSIZE_WORD           ((uint32_t)0x00000200)
+#define FLASH_PSIZE_DOUBLE_WORD    ((uint32_t)0x00000300)
+#define CR_PSIZE_MASK              ((uint32_t)0xFFFFFCFF)
+/**
+  * @}
+  */ 
+
+/** @defgroup FLASH_Keys 
+  * @{
+  */ 
+#define RDP_KEY                  ((uint16_t)0x00A5)
+#define FLASH_KEY1               ((uint32_t)0x45670123)
+#define FLASH_KEY2               ((uint32_t)0xCDEF89AB)
+#define FLASH_OPT_KEY1           ((uint32_t)0x08192A3B)
+#define FLASH_OPT_KEY2           ((uint32_t)0x4C5D6E7F)
+/**
+  * @}
+  */ 
+
+/** 
+  * @brief   ACR register byte 0 (Bits[7:0]) base address  
+  */ 
+#define ACR_BYTE0_ADDRESS           ((uint32_t)0x40023C00) 
+/** 
+  * @brief   OPTCR register byte 0 (Bits[7:0]) base address  
+  */ 
+#define OPTCR_BYTE0_ADDRESS         ((uint32_t)0x40023C14)
+/** 
+  * @brief   OPTCR register byte 1 (Bits[15:8]) base address  
+  */ 
+#define OPTCR_BYTE1_ADDRESS         ((uint32_t)0x40023C15)
+/** 
+  * @brief   OPTCR register byte 2 (Bits[23:16]) base address  
+  */ 
+#define OPTCR_BYTE2_ADDRESS         ((uint32_t)0x40023C16)
+/** 
+  * @brief   OPTCR register byte 3 (Bits[31:24]) base address  
+  */ 
+#define OPTCR_BYTE3_ADDRESS         ((uint32_t)0x40023C17)
+
+/** 
+  * @brief   OPTCR1 register byte 0 (Bits[7:0]) base address  
+  */ 
+#define OPTCR1_BYTE2_ADDRESS         ((uint32_t)0x40023C1A)
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+ 
+/* FLASH Interface configuration functions ************************************/
+void FLASH_SetLatency(uint32_t FLASH_Latency);
+void FLASH_PrefetchBufferCmd(FunctionalState NewState);
+void FLASH_InstructionCacheCmd(FunctionalState NewState);
+void FLASH_DataCacheCmd(FunctionalState NewState);
+void FLASH_InstructionCacheReset(void);
+void FLASH_DataCacheReset(void);
+
+/* FLASH Memory Programming functions *****************************************/   
+void         FLASH_Unlock(void);
+void         FLASH_Lock(void);
+FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange);
+FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange);
+FLASH_Status FLASH_EraseAllBank1Sectors(uint8_t VoltageRange);
+FLASH_Status FLASH_EraseAllBank2Sectors(uint8_t VoltageRange);
+FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data);
+FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data);
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data);
+FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data);
+
+/* Option Bytes Programming functions *****************************************/ 
+void         FLASH_OB_Unlock(void);
+void         FLASH_OB_Lock(void);
+void         FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState);
+void         FLASH_OB_WRP1Config(uint32_t OB_WRP, FunctionalState NewState);
+void         FLASH_OB_PCROPSelectionConfig(uint8_t OB_PcROP);
+void         FLASH_OB_PCROPConfig(uint32_t OB_PCROP, FunctionalState NewState);
+void         FLASH_OB_PCROP1Config(uint32_t OB_PCROP, FunctionalState NewState);
+void         FLASH_OB_RDPConfig(uint8_t OB_RDP);
+void         FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY);
+void         FLASH_OB_BORConfig(uint8_t OB_BOR);
+void         FLASH_OB_BootConfig(uint8_t OB_BOOT);
+FLASH_Status FLASH_OB_Launch(void);
+uint8_t      FLASH_OB_GetUser(void);
+uint16_t     FLASH_OB_GetWRP(void);
+uint16_t     FLASH_OB_GetWRP1(void);
+uint16_t     FLASH_OB_GetPCROP(void);
+uint16_t     FLASH_OB_GetPCROP1(void);
+FlagStatus   FLASH_OB_GetRDP(void);
+uint8_t      FLASH_OB_GetBOR(void);
+
+/* Interrupts and flags management functions **********************************/
+void         FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState);
+FlagStatus   FLASH_GetFlagStatus(uint32_t FLASH_FLAG);
+void         FLASH_ClearFlag(uint32_t FLASH_FLAG);
+FLASH_Status FLASH_GetStatus(void);
+FLASH_Status FLASH_WaitForLastOperation(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_FLASH_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmc.h
new file mode 100644
index 0000000000000000000000000000000000000000..5f128f9bc234908b1355e083c60e0e91b6289ef2
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fmc.h
@@ -0,0 +1,1137 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_fmc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the FMC firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_FMC_H
+#define __STM32F4xx_FMC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup FMC
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/  
+
+/** 
+  * @brief  Timing parameters For NOR/SRAM Banks  
+  */
+typedef struct
+{
+  uint32_t FMC_AddressSetupTime;       /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the address setup time. 
+                                             This parameter can be a value between 0 and 15.
+                                             @note This parameter is not used with synchronous NOR Flash memories. */
+
+  uint32_t FMC_AddressHoldTime;        /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the address hold time.
+                                             This parameter can be a value between 1 and 15. 
+                                             @note This parameter is not used with synchronous NOR Flash memories.*/
+
+  uint32_t FMC_DataSetupTime;          /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the data setup time.
+                                             This parameter can be a value between 1 and 255.
+                                             @note This parameter is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */
+
+  uint32_t FMC_BusTurnAroundDuration;  /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the bus turnaround.
+                                             This parameter can be a value between 0 and 15.
+                                             @note This parameter is only used for multiplexed NOR Flash memories. */
+
+  uint32_t FMC_CLKDivision;            /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles.
+                                             This parameter can be a value between 1 and 15.
+                                             @note This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */
+
+  uint32_t FMC_DataLatency;            /*!< Defines the number of memory clock cycles to issue
+                                             to the memory before getting the first data.
+                                             The parameter value depends on the memory type as shown below:
+                                              - It must be set to 0 in case of a CRAM
+                                              - It is don't care in asynchronous NOR, SRAM or ROM accesses
+                                              - It may assume a value between 0 and 15 in NOR Flash memories
+                                                with synchronous burst mode enable */
+
+  uint32_t FMC_AccessMode;             /*!< Specifies the asynchronous access mode. 
+                                             This parameter can be a value of @ref FMC_Access_Mode */
+}FMC_NORSRAMTimingInitTypeDef;
+
+/** 
+  * @brief  FMC NOR/SRAM Init structure definition
+  */
+typedef struct
+{
+  uint32_t FMC_Bank;                /*!< Specifies the NOR/SRAM memory bank that will be used.
+                                          This parameter can be a value of @ref FMC_NORSRAM_Bank */
+
+  uint32_t FMC_DataAddressMux;      /*!< Specifies whether the address and data values are
+                                          multiplexed on the databus or not. 
+                                          This parameter can be a value of @ref FMC_Data_Address_Bus_Multiplexing */
+
+  uint32_t FMC_MemoryType;          /*!< Specifies the type of external memory attached to
+                                          the corresponding memory bank.
+                                          This parameter can be a value of @ref FMC_Memory_Type */
+
+  uint32_t FMC_MemoryDataWidth;     /*!< Specifies the external memory device width.
+                                          This parameter can be a value of @ref FMC_NORSRAM_Data_Width */
+
+  uint32_t FMC_BurstAccessMode;     /*!< Enables or disables the burst access mode for Flash memory,
+                                          valid only with synchronous burst Flash memories.
+                                          This parameter can be a value of @ref FMC_Burst_Access_Mode */                                        
+
+  uint32_t FMC_WaitSignalPolarity;  /*!< Specifies the wait signal polarity, valid only when accessing
+                                          the Flash memory in burst mode.
+                                          This parameter can be a value of @ref FMC_Wait_Signal_Polarity */
+
+  uint32_t FMC_WrapMode;            /*!< Enables or disables the Wrapped burst access mode for Flash
+                                          memory, valid only when accessing Flash memories in burst mode.
+                                          This parameter can be a value of @ref FMC_Wrap_Mode */
+
+  uint32_t FMC_WaitSignalActive;    /*!< Specifies if the wait signal is asserted by the memory one
+                                          clock cycle before the wait state or during the wait state,
+                                          valid only when accessing memories in burst mode. 
+                                          This parameter can be a value of @ref FMC_Wait_Timing */
+
+  uint32_t FMC_WriteOperation;      /*!< Enables or disables the write operation in the selected bank by the FMC. 
+                                          This parameter can be a value of @ref FMC_Write_Operation */
+
+  uint32_t FMC_WaitSignal;          /*!< Enables or disables the wait state insertion via wait
+                                          signal, valid for Flash memory access in burst mode. 
+                                          This parameter can be a value of @ref FMC_Wait_Signal */
+
+  uint32_t FMC_ExtendedMode;        /*!< Enables or disables the extended mode.
+                                          This parameter can be a value of @ref FMC_Extended_Mode */
+  
+  uint32_t FMC_AsynchronousWait;     /*!< Enables or disables wait signal during asynchronous transfers,
+                                          valid only with asynchronous Flash memories.
+                                          This parameter can be a value of @ref FMC_AsynchronousWait */  
+
+  uint32_t FMC_WriteBurst;          /*!< Enables or disables the write burst operation.
+                                          This parameter can be a value of @ref FMC_Write_Burst */ 
+
+  uint32_t FMC_ContinousClock;       /*!< Enables or disables the FMC clock output to external memory devices.
+                                          This parameter is only enabled through the FMC_BCR1 register, and don't care 
+                                          through FMC_BCR2..4 registers.
+                                          This parameter can be a value of @ref FMC_Continous_Clock */ 
+
+  
+  FMC_NORSRAMTimingInitTypeDef* FMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the  Extended Mode is not used*/  
+
+  FMC_NORSRAMTimingInitTypeDef* FMC_WriteTimingStruct;     /*!< Timing Parameters for write access if the  Extended Mode is used*/      
+}FMC_NORSRAMInitTypeDef;
+
+/** 
+  * @brief  Timing parameters For FMC NAND and PCCARD Banks
+  */
+typedef struct
+{
+  uint32_t FMC_SetupTime;      /*!< Defines the number of HCLK cycles to setup address before
+                                     the command assertion for NAND-Flash read or write access
+                                     to common/Attribute or I/O memory space (depending on
+                                     the memory space timing to be configured).
+                                     This parameter can be a value between 0 and 255.*/
+
+  uint32_t FMC_WaitSetupTime;  /*!< Defines the minimum number of HCLK cycles to assert the
+                                     command for NAND-Flash read or write access to
+                                     common/Attribute or I/O memory space (depending on the
+                                     memory space timing to be configured). 
+                                     This parameter can be a number between 0 and 255 */
+
+  uint32_t FMC_HoldSetupTime;  /*!< Defines the number of HCLK clock cycles to hold address
+                                     (and data for write access) after the command de-assertion
+                                     for NAND-Flash read or write access to common/Attribute
+                                     or I/O memory space (depending on the memory space timing
+                                     to be configured).
+                                     This parameter can be a number between 0 and 255 */
+
+  uint32_t FMC_HiZSetupTime;   /*!< Defines the number of HCLK clock cycles during which the
+                                     databus is kept in HiZ after the start of a NAND-Flash
+                                     write access to common/Attribute or I/O memory space (depending
+                                     on the memory space timing to be configured).
+                                     This parameter can be a number between 0 and 255 */
+}FMC_NAND_PCCARDTimingInitTypeDef;
+
+/** 
+  * @brief  FMC NAND Init structure definition
+  */
+typedef struct
+{
+  uint32_t FMC_Bank;              /*!< Specifies the NAND memory bank that will be used.
+                                      This parameter can be a value of @ref FMC_NAND_Bank */
+
+  uint32_t FMC_Waitfeature;      /*!< Enables or disables the Wait feature for the NAND Memory Bank.
+                                       This parameter can be any value of @ref FMC_Wait_feature */
+
+  uint32_t FMC_MemoryDataWidth;  /*!< Specifies the external memory device width.
+                                       This parameter can be any value of @ref FMC_NAND_Data_Width */
+
+  uint32_t FMC_ECC;              /*!< Enables or disables the ECC computation.
+                                       This parameter can be any value of @ref FMC_ECC */
+
+  uint32_t FMC_ECCPageSize;      /*!< Defines the page size for the extended ECC.
+                                       This parameter can be any value of @ref FMC_ECC_Page_Size */
+
+  uint32_t FMC_TCLRSetupTime;    /*!< Defines the number of HCLK cycles to configure the
+                                       delay between CLE low and RE low.
+                                       This parameter can be a value between 0 and 255. */
+
+  uint32_t FMC_TARSetupTime;     /*!< Defines the number of HCLK cycles to configure the
+                                       delay between ALE low and RE low.
+                                       This parameter can be a number between 0 and 255 */ 
+
+  FMC_NAND_PCCARDTimingInitTypeDef*  FMC_CommonSpaceTimingStruct;   /*!< FMC Common Space Timing */ 
+
+  FMC_NAND_PCCARDTimingInitTypeDef*  FMC_AttributeSpaceTimingStruct; /*!< FMC Attribute Space Timing */
+}FMC_NANDInitTypeDef;
+
+/** 
+  * @brief  FMC PCCARD Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t FMC_Waitfeature;    /*!< Enables or disables the Wait feature for the Memory Bank.
+                                    This parameter can be any value of @ref FMC_Wait_feature */
+
+  uint32_t FMC_TCLRSetupTime;  /*!< Defines the number of HCLK cycles to configure the
+                                     delay between CLE low and RE low.
+                                     This parameter can be a value between 0 and 255. */
+
+  uint32_t FMC_TARSetupTime;   /*!< Defines the number of HCLK cycles to configure the
+                                     delay between ALE low and RE low.
+                                     This parameter can be a number between 0 and 255 */ 
+
+  
+  FMC_NAND_PCCARDTimingInitTypeDef*  FMC_CommonSpaceTimingStruct; /*!< FMC Common Space Timing */
+
+  FMC_NAND_PCCARDTimingInitTypeDef*  FMC_AttributeSpaceTimingStruct;  /*!< FMC Attribute Space Timing */ 
+  
+  FMC_NAND_PCCARDTimingInitTypeDef*  FMC_IOSpaceTimingStruct; /*!< FMC IO Space Timing */  
+}FMC_PCCARDInitTypeDef;
+
+/** 
+  * @brief  Timing parameters for FMC SDRAM Banks
+  */
+  
+typedef struct
+{
+  uint32_t FMC_LoadToActiveDelay;      /*!< Defines the delay between a Load Mode Register command and 
+                                            an active or Refresh command in number of memory clock cycles.
+                                            This parameter can be a value between 1 and 16. */
+  
+  uint32_t FMC_ExitSelfRefreshDelay;   /*!< Defines the delay from releasing the self refresh command to 
+                                            issuing the Activate command in number of memory clock cycles.
+                                            This parameter can be a value between 1 and 16. */
+   
+  uint32_t FMC_SelfRefreshTime;        /*!< Defines the minimum Self Refresh period in number of memory clock 
+                                            cycles.
+                                            This parameter can be a value between 1 and 16. */
+                                            
+  uint32_t FMC_RowCycleDelay;          /*!< Defines the delay between the Refresh command and the Activate command
+                                            and the delay between two consecutive Refresh commands in number of 
+                                            memory clock cycles.
+                                            This parameter can be a value between 1 and 16. */
+                                            
+  uint32_t FMC_WriteRecoveryTime;      /*!< Defines the Write recovery Time in number of memory clock cycles.
+                                            This parameter can be a value between 1 and 16. */
+                                            
+  uint32_t FMC_RPDelay;                /*!< Defines the delay between a Precharge Command and an other command 
+                                            in number of memory clock cycles.
+                                            This parameter can be a value between 1 and 16. */
+                                            
+  uint32_t FMC_RCDDelay;               /*!< Defines the delay between the Activate Command and a Read/Write command
+                                            in number of memory clock cycles.
+                                            This parameter can be a value between 1 and 16. */
+                                            
+}FMC_SDRAMTimingInitTypeDef;
+
+/** 
+  * @brief  Command parameters for FMC SDRAM Banks
+  */
+
+
+typedef struct
+{
+  uint32_t FMC_CommandMode;            /*!< Defines the command issued to the SDRAM device.
+                                            This parameter can be a value of @ref FMC_Command_Mode. */
+                                            
+  uint32_t FMC_CommandTarget;          /*!< Defines which bank (1 or 2) the command will be issued to.
+                                            This parameter can be a value of @ref FMC_Command_Target. */
+                                            
+  uint32_t FMC_AutoRefreshNumber;      /*!< Defines the number of consecutive auto refresh command issued
+                                            in auto refresh mode.
+                                            This parameter can be a value between 1 and 16. */                                           
+                                                                                                             
+  uint32_t FMC_ModeRegisterDefinition; /*!< Defines the SDRAM Mode register content */
+  
+}FMC_SDRAMCommandTypeDef;
+
+/** 
+  * @brief  FMC SDRAM Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t FMC_Bank;                   /*!< Specifies the SDRAM memory bank that will be used.
+                                          This parameter can be a value of @ref FMC_SDRAM_Bank */
+
+  uint32_t FMC_ColumnBitsNumber;       /*!< Defines the number of bits of column address.
+                                            This parameter can be a value of @ref FMC_ColumnBits_Number. */
+                                            
+  uint32_t FMC_RowBitsNumber;          /*!< Defines the number of bits of column address..
+                                            This parameter can be a value of @ref FMC_RowBits_Number. */
+                                            
+  uint32_t FMC_SDMemoryDataWidth;        /*!< Defines the memory device width.
+                                            This parameter can be a value of @ref FMC_SDMemory_Data_Width. */
+                                            
+  uint32_t FMC_InternalBankNumber;     /*!< Defines the number of bits of column address.
+                                            This parameter can be of @ref FMC_InternalBank_Number. */
+                                            
+  uint32_t FMC_CASLatency;             /*!< Defines the SDRAM CAS latency in number of memory clock cycles.
+                                            This parameter can be a value of @ref FMC_CAS_Latency. */
+                                            
+  uint32_t FMC_WriteProtection;        /*!< Enables the SDRAM bank to be accessed in write mode.
+                                            This parameter can be a value of @ref FMC_Write_Protection. */
+                                            
+  uint32_t FMC_SDClockPeriod;          /*!< Define the SDRAM Clock Period for both SDRAM Banks and they allow to disable
+                                            the clock before changing frequency.
+                                            This parameter can be a value of @ref FMC_SDClock_Period. */
+                                            
+  uint32_t FMC_ReadBurst;              /*!< This bit enable the SDRAM controller to anticipate the next read commands 
+                                            during the CAS latency and stores data in the Read FIFO.
+                                            This parameter can be a value of @ref FMC_Read_Burst. */
+                                            
+  uint32_t FMC_ReadPipeDelay;          /*!< Define the delay in system clock cycles on read data path.
+                                            This parameter can be a value of @ref FMC_ReadPipe_Delay. */
+                                            
+  FMC_SDRAMTimingInitTypeDef* FMC_SDRAMTimingStruct;   /*!< Timing Parameters for write and read access*/                                            
+  
+}FMC_SDRAMInitTypeDef;
+
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup FMC_Exported_Constants
+  * @{
+  */ 
+
+/** @defgroup FMC_NORSRAM_Bank 
+  * @{
+  */
+#define FMC_Bank1_NORSRAM1                      ((uint32_t)0x00000000)
+#define FMC_Bank1_NORSRAM2                      ((uint32_t)0x00000002)
+#define FMC_Bank1_NORSRAM3                      ((uint32_t)0x00000004)
+#define FMC_Bank1_NORSRAM4                      ((uint32_t)0x00000006)
+
+#define IS_FMC_NORSRAM_BANK(BANK) (((BANK) == FMC_Bank1_NORSRAM1) || \
+                                   ((BANK) == FMC_Bank1_NORSRAM2) || \
+                                   ((BANK) == FMC_Bank1_NORSRAM3) || \
+                                   ((BANK) == FMC_Bank1_NORSRAM4))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_NAND_Bank 
+  * @{
+  */  
+#define FMC_Bank2_NAND                          ((uint32_t)0x00000010)
+#define FMC_Bank3_NAND                          ((uint32_t)0x00000100)
+
+#define IS_FMC_NAND_BANK(BANK) (((BANK) == FMC_Bank2_NAND) || \
+                                ((BANK) == FMC_Bank3_NAND))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_PCCARD_Bank 
+  * @{
+  */    
+#define FMC_Bank4_PCCARD                        ((uint32_t)0x00001000)
+/**
+  * @}                                                         
+  */
+
+/** @defgroup FMC_SDRAM_Bank
+  * @{
+  */
+#define FMC_Bank1_SDRAM                    ((uint32_t)0x00000000)
+#define FMC_Bank2_SDRAM                    ((uint32_t)0x00000001)
+
+#define IS_FMC_SDRAM_BANK(BANK) (((BANK) == FMC_Bank1_SDRAM) || \
+                                 ((BANK) == FMC_Bank2_SDRAM)) 
+
+/**
+  * @}
+  */                               
+
+                              
+/** @defgroup FMC_NOR_SRAM_Controller 
+  * @{
+  */
+
+/** @defgroup FMC_Data_Address_Bus_Multiplexing 
+  * @{
+  */
+
+#define FMC_DataAddressMux_Disable                ((uint32_t)0x00000000)
+#define FMC_DataAddressMux_Enable                 ((uint32_t)0x00000002)
+
+#define IS_FMC_MUX(MUX) (((MUX) == FMC_DataAddressMux_Disable) || \
+                         ((MUX) == FMC_DataAddressMux_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Memory_Type 
+  * @{
+  */
+
+#define FMC_MemoryType_SRAM                     ((uint32_t)0x00000000)
+#define FMC_MemoryType_PSRAM                    ((uint32_t)0x00000004)
+#define FMC_MemoryType_NOR                      ((uint32_t)0x00000008)
+
+#define IS_FMC_MEMORY(MEMORY) (((MEMORY) == FMC_MemoryType_SRAM) || \
+                               ((MEMORY) == FMC_MemoryType_PSRAM)|| \
+                               ((MEMORY) == FMC_MemoryType_NOR))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_NORSRAM_Data_Width 
+  * @{
+  */
+
+#define FMC_NORSRAM_MemoryDataWidth_8b                  ((uint32_t)0x00000000)
+#define FMC_NORSRAM_MemoryDataWidth_16b                 ((uint32_t)0x00000010)
+#define FMC_NORSRAM_MemoryDataWidth_32b                 ((uint32_t)0x00000020)
+
+#define IS_FMC_NORSRAM_MEMORY_WIDTH(WIDTH) (((WIDTH) == FMC_NORSRAM_MemoryDataWidth_8b)  || \
+                                            ((WIDTH) == FMC_NORSRAM_MemoryDataWidth_16b) || \
+                                            ((WIDTH) == FMC_NORSRAM_MemoryDataWidth_32b))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Burst_Access_Mode 
+  * @{
+  */
+
+#define FMC_BurstAccessMode_Disable             ((uint32_t)0x00000000) 
+#define FMC_BurstAccessMode_Enable              ((uint32_t)0x00000100)
+
+#define IS_FMC_BURSTMODE(STATE) (((STATE) == FMC_BurstAccessMode_Disable) || \
+                                  ((STATE) == FMC_BurstAccessMode_Enable))
+/**
+  * @}
+  */
+    
+/** @defgroup FMC_AsynchronousWait 
+  * @{
+  */
+#define FMC_AsynchronousWait_Disable            ((uint32_t)0x00000000)
+#define FMC_AsynchronousWait_Enable             ((uint32_t)0x00008000)
+
+#define IS_FMC_ASYNWAIT(STATE) (((STATE) == FMC_AsynchronousWait_Disable) || \
+                                 ((STATE) == FMC_AsynchronousWait_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Wait_Signal_Polarity 
+  * @{
+  */
+#define FMC_WaitSignalPolarity_Low              ((uint32_t)0x00000000)
+#define FMC_WaitSignalPolarity_High             ((uint32_t)0x00000200)
+
+#define IS_FMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FMC_WaitSignalPolarity_Low) || \
+                                         ((POLARITY) == FMC_WaitSignalPolarity_High))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Wrap_Mode 
+  * @{
+  */
+#define FMC_WrapMode_Disable                    ((uint32_t)0x00000000)
+#define FMC_WrapMode_Enable                     ((uint32_t)0x00000400) 
+
+#define IS_FMC_WRAP_MODE(MODE) (((MODE) == FMC_WrapMode_Disable) || \
+                                 ((MODE) == FMC_WrapMode_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Wait_Timing 
+  * @{
+  */
+#define FMC_WaitSignalActive_BeforeWaitState    ((uint32_t)0x00000000)
+#define FMC_WaitSignalActive_DuringWaitState    ((uint32_t)0x00000800) 
+
+#define IS_FMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FMC_WaitSignalActive_BeforeWaitState) || \
+                                            ((ACTIVE) == FMC_WaitSignalActive_DuringWaitState))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Write_Operation 
+  * @{
+  */
+#define FMC_WriteOperation_Disable                     ((uint32_t)0x00000000)
+#define FMC_WriteOperation_Enable                      ((uint32_t)0x00001000)
+
+#define IS_FMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FMC_WriteOperation_Disable) || \
+                                            ((OPERATION) == FMC_WriteOperation_Enable))                         
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Wait_Signal 
+  * @{
+  */
+#define FMC_WaitSignal_Disable                  ((uint32_t)0x00000000)
+#define FMC_WaitSignal_Enable                   ((uint32_t)0x00002000) 
+
+#define IS_FMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FMC_WaitSignal_Disable) || \
+                                      ((SIGNAL) == FMC_WaitSignal_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Extended_Mode 
+  * @{
+  */
+#define FMC_ExtendedMode_Disable                ((uint32_t)0x00000000)
+#define FMC_ExtendedMode_Enable                 ((uint32_t)0x00004000)
+
+#define IS_FMC_EXTENDED_MODE(MODE) (((MODE) == FMC_ExtendedMode_Disable) || \
+                                     ((MODE) == FMC_ExtendedMode_Enable)) 
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Write_Burst 
+  * @{
+  */
+
+#define FMC_WriteBurst_Disable                  ((uint32_t)0x00000000)
+#define FMC_WriteBurst_Enable                   ((uint32_t)0x00080000) 
+
+#define IS_FMC_WRITE_BURST(BURST) (((BURST) == FMC_WriteBurst_Disable) || \
+                                    ((BURST) == FMC_WriteBurst_Enable))
+/**
+  * @}
+  */
+  
+/** @defgroup FMC_Continous_Clock 
+  * @{
+  */
+
+#define FMC_CClock_SyncOnly                     ((uint32_t)0x00000000)
+#define FMC_CClock_SyncAsync                    ((uint32_t)0x00100000) 
+
+#define IS_FMC_CONTINOUS_CLOCK(CCLOCK) (((CCLOCK) == FMC_CClock_SyncOnly) || \
+                                        ((CCLOCK) == FMC_CClock_SyncAsync))
+/**
+  * @}
+  */  
+
+/** @defgroup FMC_Address_Setup_Time 
+  * @{
+  */
+#define IS_FMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 15)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Address_Hold_Time 
+  * @{
+  */
+#define IS_FMC_ADDRESS_HOLD_TIME(TIME) (((TIME) > 0) && ((TIME) <= 15))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Data_Setup_Time 
+  * @{
+  */
+#define IS_FMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 255))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Bus_Turn_around_Duration 
+  * @{
+  */
+#define IS_FMC_TURNAROUND_TIME(TIME) ((TIME) <= 15)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_CLK_Division 
+  * @{
+  */
+#define IS_FMC_CLK_DIV(DIV) (((DIV) > 0) && ((DIV) <= 15))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Data_Latency 
+  * @{
+  */
+#define IS_FMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 15)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Access_Mode 
+  * @{
+  */
+#define FMC_AccessMode_A                        ((uint32_t)0x00000000)
+#define FMC_AccessMode_B                        ((uint32_t)0x10000000) 
+#define FMC_AccessMode_C                        ((uint32_t)0x20000000)
+#define FMC_AccessMode_D                        ((uint32_t)0x30000000)
+
+#define IS_FMC_ACCESS_MODE(MODE) (((MODE) == FMC_AccessMode_A)  || \
+                                   ((MODE) == FMC_AccessMode_B) || \
+                                   ((MODE) == FMC_AccessMode_C) || \
+                                   ((MODE) == FMC_AccessMode_D))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+  
+/** @defgroup FMC_NAND_PCCARD_Controller 
+  * @{
+  */
+
+/** @defgroup FMC_Wait_feature 
+  * @{
+  */
+#define FMC_Waitfeature_Disable                 ((uint32_t)0x00000000)
+#define FMC_Waitfeature_Enable                  ((uint32_t)0x00000002)
+
+#define IS_FMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FMC_Waitfeature_Disable) || \
+                                       ((FEATURE) == FMC_Waitfeature_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_NAND_Data_Width 
+  * @{
+  */
+#define FMC_NAND_MemoryDataWidth_8b             ((uint32_t)0x00000000)
+#define FMC_NAND_MemoryDataWidth_16b            ((uint32_t)0x00000010)
+
+#define IS_FMC_NAND_MEMORY_WIDTH(WIDTH) (((WIDTH) == FMC_NAND_MemoryDataWidth_8b) || \
+                                         ((WIDTH) == FMC_NAND_MemoryDataWidth_16b))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_ECC 
+  * @{
+  */
+#define FMC_ECC_Disable                         ((uint32_t)0x00000000)
+#define FMC_ECC_Enable                          ((uint32_t)0x00000040)
+
+#define IS_FMC_ECC_STATE(STATE) (((STATE) == FMC_ECC_Disable) || \
+                                  ((STATE) == FMC_ECC_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_ECC_Page_Size 
+  * @{
+  */
+#define FMC_ECCPageSize_256Bytes                ((uint32_t)0x00000000)
+#define FMC_ECCPageSize_512Bytes                ((uint32_t)0x00020000)
+#define FMC_ECCPageSize_1024Bytes               ((uint32_t)0x00040000)
+#define FMC_ECCPageSize_2048Bytes               ((uint32_t)0x00060000)
+#define FMC_ECCPageSize_4096Bytes               ((uint32_t)0x00080000)
+#define FMC_ECCPageSize_8192Bytes               ((uint32_t)0x000A0000)
+
+#define IS_FMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FMC_ECCPageSize_256Bytes)   || \
+                                    ((SIZE) == FMC_ECCPageSize_512Bytes)  || \
+                                    ((SIZE) == FMC_ECCPageSize_1024Bytes) || \
+                                    ((SIZE) == FMC_ECCPageSize_2048Bytes) || \
+                                    ((SIZE) == FMC_ECCPageSize_4096Bytes) || \
+                                    ((SIZE) == FMC_ECCPageSize_8192Bytes))
+/**
+  * @}
+  */
+
+/** @defgroup FMC_TCLR_Setup_Time 
+  * @{
+  */
+#define IS_FMC_TCLR_TIME(TIME) ((TIME) <= 255)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_TAR_Setup_Time 
+  * @{
+  */
+#define IS_FMC_TAR_TIME(TIME) ((TIME) <= 255)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Setup_Time 
+  * @{
+  */
+#define IS_FMC_SETUP_TIME(TIME) ((TIME) <= 255)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Wait_Setup_Time 
+  * @{
+  */
+#define IS_FMC_WAIT_TIME(TIME) ((TIME) <= 255)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Hold_Setup_Time 
+  * @{
+  */
+#define IS_FMC_HOLD_TIME(TIME) ((TIME) <= 255)
+/**
+  * @}
+  */
+
+/** @defgroup FMC_HiZ_Setup_Time 
+  * @{
+  */
+#define IS_FMC_HIZ_TIME(TIME) ((TIME) <= 255)
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */  
+
+
+/** @defgroup FMC_NOR_SRAM_Controller 
+  * @{
+  */
+        
+/** @defgroup FMC_ColumnBits_Number 
+  * @{
+  */
+#define FMC_ColumnBits_Number_8b           ((uint32_t)0x00000000)
+#define FMC_ColumnBits_Number_9b           ((uint32_t)0x00000001)
+#define FMC_ColumnBits_Number_10b          ((uint32_t)0x00000002)
+#define FMC_ColumnBits_Number_11b          ((uint32_t)0x00000003)
+
+#define IS_FMC_COLUMNBITS_NUMBER(COLUMN) (((COLUMN) == FMC_ColumnBits_Number_8b)  || \
+                                          ((COLUMN) == FMC_ColumnBits_Number_9b)  || \
+                                          ((COLUMN) == FMC_ColumnBits_Number_10b) || \
+                                          ((COLUMN) == FMC_ColumnBits_Number_11b))
+
+/**
+  * @}
+  */
+  
+/** @defgroup FMC_RowBits_Number 
+  * @{
+  */
+#define FMC_RowBits_Number_11b             ((uint32_t)0x00000000)
+#define FMC_RowBits_Number_12b             ((uint32_t)0x00000004)
+#define FMC_RowBits_Number_13b             ((uint32_t)0x00000008)
+
+#define IS_FMC_ROWBITS_NUMBER(ROW) (((ROW) == FMC_RowBits_Number_11b) || \
+                                    ((ROW) == FMC_RowBits_Number_12b) || \
+                                    ((ROW) == FMC_RowBits_Number_13b))
+
+/**
+  * @}
+  */  
+
+/** @defgroup FMC_SDMemory_Data_Width 
+  * @{
+  */
+#define FMC_SDMemory_Width_8b                ((uint32_t)0x00000000)
+#define FMC_SDMemory_Width_16b               ((uint32_t)0x00000010)
+#define FMC_SDMemory_Width_32b               ((uint32_t)0x00000020)
+
+#define IS_FMC_SDMEMORY_WIDTH(WIDTH) (((WIDTH) == FMC_SDMemory_Width_8b)  || \
+                                      ((WIDTH) == FMC_SDMemory_Width_16b) || \
+                                      ((WIDTH) == FMC_SDMemory_Width_32b))
+
+/**
+  * @}
+  */
+  
+/** @defgroup FMC_InternalBank_Number
+  * @{
+  */
+#define FMC_InternalBank_Number_2          ((uint32_t)0x00000000)
+#define FMC_InternalBank_Number_4          ((uint32_t)0x00000040)
+
+#define IS_FMC_INTERNALBANK_NUMBER(NUMBER) (((NUMBER) == FMC_InternalBank_Number_2) || \
+                                            ((NUMBER) == FMC_InternalBank_Number_4)) 
+
+/**
+  * @}
+  */  
+  
+  
+/** @defgroup FMC_CAS_Latency 
+  * @{
+  */
+#define FMC_CAS_Latency_1                  ((uint32_t)0x00000080)
+#define FMC_CAS_Latency_2                  ((uint32_t)0x00000100)
+#define FMC_CAS_Latency_3                  ((uint32_t)0x00000180)
+
+#define IS_FMC_CAS_LATENCY(LATENCY) (((LATENCY) == FMC_CAS_Latency_1) || \
+                                     ((LATENCY) == FMC_CAS_Latency_2) || \
+                                     ((LATENCY) == FMC_CAS_Latency_3))
+
+/**
+  * @}
+  */  
+
+/** @defgroup FMC_Write_Protection
+  * @{
+  */
+#define FMC_Write_Protection_Disable       ((uint32_t)0x00000000)
+#define FMC_Write_Protection_Enable        ((uint32_t)0x00000200)
+
+#define IS_FMC_WRITE_PROTECTION(WRITE) (((WRITE) == FMC_Write_Protection_Disable) || \
+                                        ((WRITE) == FMC_Write_Protection_Enable))
+
+/**
+  * @}
+  */  
+  
+
+/** @defgroup FMC_SDClock_Period
+  * @{
+  */
+#define FMC_SDClock_Disable                ((uint32_t)0x00000000)
+#define FMC_SDClock_Period_2               ((uint32_t)0x00000800)
+#define FMC_SDClock_Period_3               ((uint32_t)0x00000C00)
+
+#define IS_FMC_SDCLOCK_PERIOD(PERIOD) (((PERIOD) == FMC_SDClock_Disable) || \
+                                       ((PERIOD) == FMC_SDClock_Period_2) || \
+                                       ((PERIOD) == FMC_SDClock_Period_3))
+
+/**
+  * @}
+  */ 
+  
+/** @defgroup FMC_Read_Burst
+  * @{
+  */
+#define FMC_Read_Burst_Disable             ((uint32_t)0x00000000)
+#define FMC_Read_Burst_Enable              ((uint32_t)0x00001000)
+
+#define IS_FMC_READ_BURST(RBURST) (((RBURST) == FMC_Read_Burst_Disable) || \
+                                   ((RBURST) == FMC_Read_Burst_Enable))
+
+/**
+  * @}
+  */
+
+/** @defgroup FMC_ReadPipe_Delay
+  * @{
+  */
+#define FMC_ReadPipe_Delay_0               ((uint32_t)0x00000000)
+#define FMC_ReadPipe_Delay_1               ((uint32_t)0x00002000)
+#define FMC_ReadPipe_Delay_2               ((uint32_t)0x00004000)
+
+#define IS_FMC_READPIPE_DELAY(DELAY) (((DELAY) == FMC_ReadPipe_Delay_0) || \
+                                      ((DELAY) == FMC_ReadPipe_Delay_1) || \
+                                      ((DELAY) == FMC_ReadPipe_Delay_2))
+
+/**
+  * @}
+  */
+  
+/** @defgroup FMC_LoadToActive_Delay
+  * @{
+  */
+#define IS_FMC_LOADTOACTIVE_DELAY(DELAY) (((DELAY) > 0) && ((DELAY) <= 16))
+/**
+  * @}
+  */
+  
+/** @defgroup FMC_ExitSelfRefresh_Delay
+  * @{
+  */
+#define IS_FMC_EXITSELFREFRESH_DELAY(DELAY) (((DELAY) > 0) && ((DELAY) <= 16))
+/**
+  * @}
+  */ 
+     
+/** @defgroup FMC_SelfRefresh_Time
+  * @{
+  */  
+#define IS_FMC_SELFREFRESH_TIME(TIME) (((TIME) > 0) && ((TIME) <= 16))
+/**
+  * @}
+  */
+  
+/** @defgroup FMC_RowCycle_Delay
+  * @{
+  */  
+#define IS_FMC_ROWCYCLE_DELAY(DELAY) (((DELAY) > 0) && ((DELAY) <= 16))
+/**
+  * @}
+  */  
+  
+/** @defgroup FMC_Write_Recovery_Time
+  * @{
+  */  
+#define IS_FMC_WRITE_RECOVERY_TIME(TIME) (((TIME) > 0) && ((TIME) <= 16))
+/**
+  * @}
+  */         
+  
+/** @defgroup FMC_RP_Delay
+  * @{
+  */  
+#define IS_FMC_RP_DELAY(DELAY) (((DELAY) > 0) && ((DELAY) <= 16))
+/**
+  * @}
+  */ 
+  
+/** @defgroup FMC_RCD_Delay 
+  * @{
+  */  
+#define IS_FMC_RCD_DELAY(DELAY) (((DELAY) > 0) && ((DELAY) <= 16))
+
+/**
+  * @}
+  */  
+  
+/** @defgroup FMC_Command_Mode
+  * @{
+  */
+#define FMC_Command_Mode_normal            ((uint32_t)0x00000000)
+#define FMC_Command_Mode_CLK_Enabled       ((uint32_t)0x00000001)
+#define FMC_Command_Mode_PALL              ((uint32_t)0x00000002)
+#define FMC_Command_Mode_AutoRefresh       ((uint32_t)0x00000003)
+#define FMC_Command_Mode_LoadMode          ((uint32_t)0x00000004)
+#define FMC_Command_Mode_Selfrefresh       ((uint32_t)0x00000005)
+#define FMC_Command_Mode_PowerDown         ((uint32_t)0x00000006)
+
+#define IS_FMC_COMMAND_MODE(COMMAND) (((COMMAND) == FMC_Command_Mode_normal)      || \
+                                      ((COMMAND) == FMC_Command_Mode_CLK_Enabled) || \
+                                      ((COMMAND) == FMC_Command_Mode_PALL)        || \
+                                      ((COMMAND) == FMC_Command_Mode_AutoRefresh) || \
+                                      ((COMMAND) == FMC_Command_Mode_LoadMode)    || \
+                                      ((COMMAND) == FMC_Command_Mode_Selfrefresh) || \
+                                      ((COMMAND) == FMC_Command_Mode_PowerDown))
+
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Command_Target
+  * @{
+  */
+#define FMC_Command_Target_bank2           ((uint32_t)0x00000008)
+#define FMC_Command_Target_bank1           ((uint32_t)0x00000010)
+#define FMC_Command_Target_bank1_2         ((uint32_t)0x00000018)
+
+#define IS_FMC_COMMAND_TARGET(TARGET) (((TARGET) == FMC_Command_Target_bank1) || \
+                                       ((TARGET) == FMC_Command_Target_bank2) || \
+                                       ((TARGET) == FMC_Command_Target_bank1_2))
+
+/**
+  * @}
+  */   
+  
+/** @defgroup FMC_AutoRefresh_Number
+  * @{
+  */  
+#define IS_FMC_AUTOREFRESH_NUMBER(NUMBER) (((NUMBER) > 0) && ((NUMBER) <= 16))
+
+/**
+  * @}
+  */
+
+/** @defgroup FMC_ModeRegister_Definition
+  * @{
+  */
+#define IS_FMC_MODE_REGISTER(CONTENT) ((CONTENT) <= 8191)
+
+/**
+  * @}
+  */
+  
+
+/** @defgroup FMC_Mode_Status 
+  * @{
+  */
+#define FMC_NormalMode_Status                     ((uint32_t)0x00000000)
+#define FMC_SelfRefreshMode_Status                FMC_SDSR_MODES1_0
+#define FMC_PowerDownMode_Status                  FMC_SDSR_MODES1_1
+
+#define IS_FMC_MODE_STATUS(STATUS) (((STATUS) == FMC_NormalMode_Status)       || \
+                                    ((STATUS) == FMC_SelfRefreshMode_Status)  || \
+                                    ((STATUS) == FMC_PowerDownMode_Status))
+
+
+/**
+  * @}
+  */      
+
+/**
+  * @}
+  */  
+
+/** @defgroup FMC_Interrupt_sources 
+  * @{
+  */
+#define FMC_IT_RisingEdge                       ((uint32_t)0x00000008)
+#define FMC_IT_Level                            ((uint32_t)0x00000010)
+#define FMC_IT_FallingEdge                      ((uint32_t)0x00000020)
+#define FMC_IT_Refresh                          ((uint32_t)0x00004000)
+
+#define IS_FMC_IT(IT) ((((IT) & (uint32_t)0xFFFFBFC7) == 0x00000000) && ((IT) != 0x00000000))
+#define IS_FMC_GET_IT(IT) (((IT) == FMC_IT_RisingEdge)  || \
+                           ((IT) == FMC_IT_Level)       || \
+                           ((IT) == FMC_IT_FallingEdge) || \
+                           ((IT) == FMC_IT_Refresh)) 
+                           
+#define IS_FMC_IT_BANK(BANK) (((BANK) == FMC_Bank2_NAND)   || \
+                              ((BANK) == FMC_Bank3_NAND)   || \
+                              ((BANK) == FMC_Bank4_PCCARD) || \
+                              ((BANK) == FMC_Bank1_SDRAM)  || \
+                              ((BANK) == FMC_Bank2_SDRAM))                           
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Flags 
+  * @{
+  */
+#define FMC_FLAG_RisingEdge                     ((uint32_t)0x00000001)
+#define FMC_FLAG_Level                          ((uint32_t)0x00000002)
+#define FMC_FLAG_FallingEdge                    ((uint32_t)0x00000004)
+#define FMC_FLAG_FEMPT                          ((uint32_t)0x00000040)
+#define FMC_FLAG_Refresh                        FMC_SDSR_RE
+#define FMC_FLAG_Busy                           FMC_SDSR_BUSY
+
+#define IS_FMC_GET_FLAG(FLAG) (((FLAG) == FMC_FLAG_RisingEdge)       || \
+                               ((FLAG) == FMC_FLAG_Level)            || \
+                               ((FLAG) == FMC_FLAG_FallingEdge)      || \
+                               ((FLAG) == FMC_FLAG_FEMPT)            || \
+                               ((FLAG) == FMC_FLAG_Refresh)          || \
+                               ((FLAG) == FMC_SDSR_BUSY))
+
+#define IS_FMC_GETFLAG_BANK(BANK) (((BANK) == FMC_Bank2_NAND)    || \
+                                   ((BANK) == FMC_Bank3_NAND)    || \
+                                   ((BANK) == FMC_Bank4_PCCARD)  || \
+                                   ((BANK) == FMC_Bank1_SDRAM)   || \
+                                   ((BANK) == FMC_Bank2_SDRAM)   || \
+                                   ((BANK) == (FMC_Bank1_SDRAM | FMC_Bank2_SDRAM)))
+                                   
+#define IS_FMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000))
+
+
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Refresh_count
+  * @{
+  */
+#define IS_FMC_REFRESH_COUNT(COUNT) ((COUNT) <= 8191)
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/* NOR/SRAM Controller functions **********************************************/
+void FMC_NORSRAMDeInit(uint32_t FMC_Bank);
+void FMC_NORSRAMInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct);
+void FMC_NORSRAMStructInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct);
+void FMC_NORSRAMCmd(uint32_t FMC_Bank, FunctionalState NewState);
+
+/* NAND Controller functions **************************************************/
+void     FMC_NANDDeInit(uint32_t FMC_Bank);
+void     FMC_NANDInit(FMC_NANDInitTypeDef* FMC_NANDInitStruct);
+void     FMC_NANDStructInit(FMC_NANDInitTypeDef* FMC_NANDInitStruct);
+void     FMC_NANDCmd(uint32_t FMC_Bank, FunctionalState NewState);
+void     FMC_NANDECCCmd(uint32_t FMC_Bank, FunctionalState NewState);
+uint32_t FMC_GetECC(uint32_t FMC_Bank);
+
+/* PCCARD Controller functions ************************************************/
+void FMC_PCCARDDeInit(void);
+void FMC_PCCARDInit(FMC_PCCARDInitTypeDef* FMC_PCCARDInitStruct);
+void FMC_PCCARDStructInit(FMC_PCCARDInitTypeDef* FMC_PCCARDInitStruct);
+void FMC_PCCARDCmd(FunctionalState NewState);
+
+/* SDRAM Controller functions ************************************************/
+void     FMC_SDRAMDeInit(uint32_t FMC_Bank);
+void     FMC_SDRAMInit(FMC_SDRAMInitTypeDef* FMC_SDRAMInitStruct);
+void     FMC_SDRAMStructInit(FMC_SDRAMInitTypeDef* FMC_SDRAMInitStruct);
+void     FMC_SDRAMCmdConfig(FMC_SDRAMCommandTypeDef* FMC_SDRAMCommandStruct);
+uint32_t FMC_GetModeStatus(uint32_t SDRAM_Bank);
+void     FMC_SetRefreshCount(uint32_t FMC_Count);
+void     FMC_SetAutoRefresh_Number(uint32_t FMC_Number);
+void     FMC_SDRAMWriteProtectionConfig(uint32_t SDRAM_Bank, FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void       FMC_ITConfig(uint32_t FMC_Bank, uint32_t FMC_IT, FunctionalState NewState);
+FlagStatus FMC_GetFlagStatus(uint32_t FMC_Bank, uint32_t FMC_FLAG);
+void       FMC_ClearFlag(uint32_t FMC_Bank, uint32_t FMC_FLAG);
+ITStatus   FMC_GetITStatus(uint32_t FMC_Bank, uint32_t FMC_IT);
+void       FMC_ClearITPendingBit(uint32_t FMC_Bank, uint32_t FMC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_FMC_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h
new file mode 100644
index 0000000000000000000000000000000000000000..204af800615b1ede3ceb119cca4bb50c6cb5a240
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_fsmc.h
@@ -0,0 +1,675 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_fsmc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the FSMC firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_FSMC_H
+#define __STM32F4xx_FSMC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup FSMC
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  Timing parameters For NOR/SRAM Banks  
+  */
+typedef struct
+{
+  uint32_t FSMC_AddressSetupTime;       /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the address setup time. 
+                                             This parameter can be a value between 0 and 0xF.
+                                             @note This parameter is not used with synchronous NOR Flash memories. */
+
+  uint32_t FSMC_AddressHoldTime;        /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the address hold time.
+                                             This parameter can be a value between 0 and 0xF. 
+                                             @note This parameter is not used with synchronous NOR Flash memories.*/
+
+  uint32_t FSMC_DataSetupTime;          /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the data setup time.
+                                             This parameter can be a value between 0 and 0xFF.
+                                             @note This parameter is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */
+
+  uint32_t FSMC_BusTurnAroundDuration;  /*!< Defines the number of HCLK cycles to configure
+                                             the duration of the bus turnaround.
+                                             This parameter can be a value between 0 and 0xF.
+                                             @note This parameter is only used for multiplexed NOR Flash memories. */
+
+  uint32_t FSMC_CLKDivision;            /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles.
+                                             This parameter can be a value between 1 and 0xF.
+                                             @note This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */
+
+  uint32_t FSMC_DataLatency;            /*!< Defines the number of memory clock cycles to issue
+                                             to the memory before getting the first data.
+                                             The parameter value depends on the memory type as shown below:
+                                              - It must be set to 0 in case of a CRAM
+                                              - It is don't care in asynchronous NOR, SRAM or ROM accesses
+                                              - It may assume a value between 0 and 0xF in NOR Flash memories
+                                                with synchronous burst mode enable */
+
+  uint32_t FSMC_AccessMode;             /*!< Specifies the asynchronous access mode. 
+                                             This parameter can be a value of @ref FSMC_Access_Mode */
+}FSMC_NORSRAMTimingInitTypeDef;
+
+/** 
+  * @brief  FSMC NOR/SRAM Init structure definition
+  */
+typedef struct
+{
+  uint32_t FSMC_Bank;                /*!< Specifies the NOR/SRAM memory bank that will be used.
+                                          This parameter can be a value of @ref FSMC_NORSRAM_Bank */
+
+  uint32_t FSMC_DataAddressMux;      /*!< Specifies whether the address and data values are
+                                          multiplexed on the data bus or not. 
+                                          This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */
+
+  uint32_t FSMC_MemoryType;          /*!< Specifies the type of external memory attached to
+                                          the corresponding memory bank.
+                                          This parameter can be a value of @ref FSMC_Memory_Type */
+
+  uint32_t FSMC_MemoryDataWidth;     /*!< Specifies the external memory device width.
+                                          This parameter can be a value of @ref FSMC_Data_Width */
+
+  uint32_t FSMC_BurstAccessMode;     /*!< Enables or disables the burst access mode for Flash memory,
+                                          valid only with synchronous burst Flash memories.
+                                          This parameter can be a value of @ref FSMC_Burst_Access_Mode */
+
+  uint32_t FSMC_AsynchronousWait;     /*!< Enables or disables wait signal during asynchronous transfers,
+                                          valid only with asynchronous Flash memories.
+                                          This parameter can be a value of @ref FSMC_AsynchronousWait */                                          
+
+  uint32_t FSMC_WaitSignalPolarity;  /*!< Specifies the wait signal polarity, valid only when accessing
+                                          the Flash memory in burst mode.
+                                          This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */
+
+  uint32_t FSMC_WrapMode;            /*!< Enables or disables the Wrapped burst access mode for Flash
+                                          memory, valid only when accessing Flash memories in burst mode.
+                                          This parameter can be a value of @ref FSMC_Wrap_Mode */
+
+  uint32_t FSMC_WaitSignalActive;    /*!< Specifies if the wait signal is asserted by the memory one
+                                          clock cycle before the wait state or during the wait state,
+                                          valid only when accessing memories in burst mode. 
+                                          This parameter can be a value of @ref FSMC_Wait_Timing */
+
+  uint32_t FSMC_WriteOperation;      /*!< Enables or disables the write operation in the selected bank by the FSMC. 
+                                          This parameter can be a value of @ref FSMC_Write_Operation */
+
+  uint32_t FSMC_WaitSignal;          /*!< Enables or disables the wait state insertion via wait
+                                          signal, valid for Flash memory access in burst mode. 
+                                          This parameter can be a value of @ref FSMC_Wait_Signal */
+
+  uint32_t FSMC_ExtendedMode;        /*!< Enables or disables the extended mode.
+                                          This parameter can be a value of @ref FSMC_Extended_Mode */
+
+  uint32_t FSMC_WriteBurst;          /*!< Enables or disables the write burst operation.
+                                          This parameter can be a value of @ref FSMC_Write_Burst */ 
+
+  FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the  Extended Mode is not used*/  
+
+  FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct;     /*!< Timing Parameters for write access if the  Extended Mode is used*/      
+}FSMC_NORSRAMInitTypeDef;
+
+/** 
+  * @brief  Timing parameters For FSMC NAND and PCCARD Banks
+  */
+typedef struct
+{
+  uint32_t FSMC_SetupTime;      /*!< Defines the number of HCLK cycles to setup address before
+                                     the command assertion for NAND Flash read or write access
+                                     to common/Attribute or I/O memory space (depending on
+                                     the memory space timing to be configured).
+                                     This parameter can be a value between 0 and 0xFF.*/
+
+  uint32_t FSMC_WaitSetupTime;  /*!< Defines the minimum number of HCLK cycles to assert the
+                                     command for NAND Flash read or write access to
+                                     common/Attribute or I/O memory space (depending on the
+                                     memory space timing to be configured). 
+                                     This parameter can be a number between 0x00 and 0xFF */
+
+  uint32_t FSMC_HoldSetupTime;  /*!< Defines the number of HCLK clock cycles to hold address
+                                     (and data for write access) after the command de-assertion
+                                     for NAND Flash read or write access to common/Attribute
+                                     or I/O memory space (depending on the memory space timing
+                                     to be configured).
+                                     This parameter can be a number between 0x00 and 0xFF */
+
+  uint32_t FSMC_HiZSetupTime;   /*!< Defines the number of HCLK clock cycles during which the
+                                     data bus is kept in HiZ after the start of a NAND Flash
+                                     write access to common/Attribute or I/O memory space (depending
+                                     on the memory space timing to be configured).
+                                     This parameter can be a number between 0x00 and 0xFF */
+}FSMC_NAND_PCCARDTimingInitTypeDef;
+
+/** 
+  * @brief  FSMC NAND Init structure definition
+  */
+typedef struct
+{
+  uint32_t FSMC_Bank;              /*!< Specifies the NAND memory bank that will be used.
+                                      This parameter can be a value of @ref FSMC_NAND_Bank */
+
+  uint32_t FSMC_Waitfeature;      /*!< Enables or disables the Wait feature for the NAND Memory Bank.
+                                       This parameter can be any value of @ref FSMC_Wait_feature */
+
+  uint32_t FSMC_MemoryDataWidth;  /*!< Specifies the external memory device width.
+                                       This parameter can be any value of @ref FSMC_Data_Width */
+
+  uint32_t FSMC_ECC;              /*!< Enables or disables the ECC computation.
+                                       This parameter can be any value of @ref FSMC_ECC */
+
+  uint32_t FSMC_ECCPageSize;      /*!< Defines the page size for the extended ECC.
+                                       This parameter can be any value of @ref FSMC_ECC_Page_Size */
+
+  uint32_t FSMC_TCLRSetupTime;    /*!< Defines the number of HCLK cycles to configure the
+                                       delay between CLE low and RE low.
+                                       This parameter can be a value between 0 and 0xFF. */
+
+  uint32_t FSMC_TARSetupTime;     /*!< Defines the number of HCLK cycles to configure the
+                                       delay between ALE low and RE low.
+                                       This parameter can be a number between 0x0 and 0xFF */ 
+
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_CommonSpaceTimingStruct;   /*!< FSMC Common Space Timing */ 
+
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */
+}FSMC_NANDInitTypeDef;
+
+/** 
+  * @brief  FSMC PCCARD Init structure definition
+  */
+
+typedef struct
+{
+  uint32_t FSMC_Waitfeature;    /*!< Enables or disables the Wait feature for the Memory Bank.
+                                    This parameter can be any value of @ref FSMC_Wait_feature */
+
+  uint32_t FSMC_TCLRSetupTime;  /*!< Defines the number of HCLK cycles to configure the
+                                     delay between CLE low and RE low.
+                                     This parameter can be a value between 0 and 0xFF. */
+
+  uint32_t FSMC_TARSetupTime;   /*!< Defines the number of HCLK cycles to configure the
+                                     delay between ALE low and RE low.
+                                     This parameter can be a number between 0x0 and 0xFF */ 
+
+  
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */
+
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_AttributeSpaceTimingStruct;  /*!< FSMC Attribute Space Timing */ 
+  
+  FSMC_NAND_PCCARDTimingInitTypeDef*  FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */  
+}FSMC_PCCARDInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup FSMC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup FSMC_NORSRAM_Bank 
+  * @{
+  */
+#define FSMC_Bank1_NORSRAM1                      ((uint32_t)0x00000000)
+#define FSMC_Bank1_NORSRAM2                      ((uint32_t)0x00000002)
+#define FSMC_Bank1_NORSRAM3                      ((uint32_t)0x00000004)
+#define FSMC_Bank1_NORSRAM4                      ((uint32_t)0x00000006)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_NAND_Bank 
+  * @{
+  */  
+#define FSMC_Bank2_NAND                          ((uint32_t)0x00000010)
+#define FSMC_Bank3_NAND                          ((uint32_t)0x00000100)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_PCCARD_Bank 
+  * @{
+  */    
+#define FSMC_Bank4_PCCARD                        ((uint32_t)0x00001000)
+/**
+  * @}
+  */
+
+#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \
+                                    ((BANK) == FSMC_Bank1_NORSRAM2) || \
+                                    ((BANK) == FSMC_Bank1_NORSRAM3) || \
+                                    ((BANK) == FSMC_Bank1_NORSRAM4))
+
+#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+                                 ((BANK) == FSMC_Bank3_NAND))
+
+#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+                                    ((BANK) == FSMC_Bank3_NAND) || \
+                                    ((BANK) == FSMC_Bank4_PCCARD))
+
+#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \
+                               ((BANK) == FSMC_Bank3_NAND) || \
+                               ((BANK) == FSMC_Bank4_PCCARD))
+
+/** @defgroup FSMC_NOR_SRAM_Controller 
+  * @{
+  */
+
+/** @defgroup FSMC_Data_Address_Bus_Multiplexing 
+  * @{
+  */
+
+#define FSMC_DataAddressMux_Disable                ((uint32_t)0x00000000)
+#define FSMC_DataAddressMux_Enable                 ((uint32_t)0x00000002)
+#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \
+                          ((MUX) == FSMC_DataAddressMux_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Memory_Type 
+  * @{
+  */
+
+#define FSMC_MemoryType_SRAM                     ((uint32_t)0x00000000)
+#define FSMC_MemoryType_PSRAM                    ((uint32_t)0x00000004)
+#define FSMC_MemoryType_NOR                      ((uint32_t)0x00000008)
+#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \
+                                ((MEMORY) == FSMC_MemoryType_PSRAM)|| \
+                                ((MEMORY) == FSMC_MemoryType_NOR))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Data_Width 
+  * @{
+  */
+
+#define FSMC_MemoryDataWidth_8b                  ((uint32_t)0x00000000)
+#define FSMC_MemoryDataWidth_16b                 ((uint32_t)0x00000010)
+#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \
+                                     ((WIDTH) == FSMC_MemoryDataWidth_16b))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Burst_Access_Mode 
+  * @{
+  */
+
+#define FSMC_BurstAccessMode_Disable             ((uint32_t)0x00000000) 
+#define FSMC_BurstAccessMode_Enable              ((uint32_t)0x00000100)
+#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \
+                                  ((STATE) == FSMC_BurstAccessMode_Enable))
+/**
+  * @}
+  */
+    
+/** @defgroup FSMC_AsynchronousWait 
+  * @{
+  */
+#define FSMC_AsynchronousWait_Disable            ((uint32_t)0x00000000)
+#define FSMC_AsynchronousWait_Enable             ((uint32_t)0x00008000)
+#define IS_FSMC_ASYNWAIT(STATE) (((STATE) == FSMC_AsynchronousWait_Disable) || \
+                                 ((STATE) == FSMC_AsynchronousWait_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Signal_Polarity 
+  * @{
+  */
+#define FSMC_WaitSignalPolarity_Low              ((uint32_t)0x00000000)
+#define FSMC_WaitSignalPolarity_High             ((uint32_t)0x00000200)
+#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \
+                                         ((POLARITY) == FSMC_WaitSignalPolarity_High))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wrap_Mode 
+  * @{
+  */
+#define FSMC_WrapMode_Disable                    ((uint32_t)0x00000000)
+#define FSMC_WrapMode_Enable                     ((uint32_t)0x00000400) 
+#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \
+                                 ((MODE) == FSMC_WrapMode_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Timing 
+  * @{
+  */
+#define FSMC_WaitSignalActive_BeforeWaitState    ((uint32_t)0x00000000)
+#define FSMC_WaitSignalActive_DuringWaitState    ((uint32_t)0x00000800) 
+#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \
+                                            ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Write_Operation 
+  * @{
+  */
+#define FSMC_WriteOperation_Disable                     ((uint32_t)0x00000000)
+#define FSMC_WriteOperation_Enable                      ((uint32_t)0x00001000)
+#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \
+                                            ((OPERATION) == FSMC_WriteOperation_Enable))                         
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Signal 
+  * @{
+  */
+#define FSMC_WaitSignal_Disable                  ((uint32_t)0x00000000)
+#define FSMC_WaitSignal_Enable                   ((uint32_t)0x00002000) 
+#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \
+                                      ((SIGNAL) == FSMC_WaitSignal_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Extended_Mode 
+  * @{
+  */
+#define FSMC_ExtendedMode_Disable                ((uint32_t)0x00000000)
+#define FSMC_ExtendedMode_Enable                 ((uint32_t)0x00004000)
+
+#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \
+                                     ((MODE) == FSMC_ExtendedMode_Enable)) 
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Write_Burst 
+  * @{
+  */
+
+#define FSMC_WriteBurst_Disable                  ((uint32_t)0x00000000)
+#define FSMC_WriteBurst_Enable                   ((uint32_t)0x00080000) 
+#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \
+                                    ((BURST) == FSMC_WriteBurst_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Address_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Address_Hold_Time 
+  * @{
+  */
+#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Data_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Bus_Turn_around_Duration 
+  * @{
+  */
+#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_CLK_Division 
+  * @{
+  */
+#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Data_Latency 
+  * @{
+  */
+#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Access_Mode 
+  * @{
+  */
+#define FSMC_AccessMode_A                        ((uint32_t)0x00000000)
+#define FSMC_AccessMode_B                        ((uint32_t)0x10000000) 
+#define FSMC_AccessMode_C                        ((uint32_t)0x20000000)
+#define FSMC_AccessMode_D                        ((uint32_t)0x30000000)
+#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \
+                                   ((MODE) == FSMC_AccessMode_B) || \
+                                   ((MODE) == FSMC_AccessMode_C) || \
+                                   ((MODE) == FSMC_AccessMode_D))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+  
+/** @defgroup FSMC_NAND_PCCARD_Controller 
+  * @{
+  */
+
+/** @defgroup FSMC_Wait_feature 
+  * @{
+  */
+#define FSMC_Waitfeature_Disable                 ((uint32_t)0x00000000)
+#define FSMC_Waitfeature_Enable                  ((uint32_t)0x00000002)
+#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \
+                                       ((FEATURE) == FSMC_Waitfeature_Enable))
+/**
+  * @}
+  */
+
+
+/** @defgroup FSMC_ECC 
+  * @{
+  */
+#define FSMC_ECC_Disable                         ((uint32_t)0x00000000)
+#define FSMC_ECC_Enable                          ((uint32_t)0x00000040)
+#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \
+                                  ((STATE) == FSMC_ECC_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_ECC_Page_Size 
+  * @{
+  */
+#define FSMC_ECCPageSize_256Bytes                ((uint32_t)0x00000000)
+#define FSMC_ECCPageSize_512Bytes                ((uint32_t)0x00020000)
+#define FSMC_ECCPageSize_1024Bytes               ((uint32_t)0x00040000)
+#define FSMC_ECCPageSize_2048Bytes               ((uint32_t)0x00060000)
+#define FSMC_ECCPageSize_4096Bytes               ((uint32_t)0x00080000)
+#define FSMC_ECCPageSize_8192Bytes               ((uint32_t)0x000A0000)
+#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_512Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \
+                                    ((SIZE) == FSMC_ECCPageSize_8192Bytes))
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_TCLR_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_TAR_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Wait_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Hold_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_HiZ_Setup_Time 
+  * @{
+  */
+#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF)
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Interrupt_sources 
+  * @{
+  */
+#define FSMC_IT_RisingEdge                       ((uint32_t)0x00000008)
+#define FSMC_IT_Level                            ((uint32_t)0x00000010)
+#define FSMC_IT_FallingEdge                      ((uint32_t)0x00000020)
+#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000))
+#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \
+                            ((IT) == FSMC_IT_Level) || \
+                            ((IT) == FSMC_IT_FallingEdge)) 
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Flags 
+  * @{
+  */
+#define FSMC_FLAG_RisingEdge                     ((uint32_t)0x00000001)
+#define FSMC_FLAG_Level                          ((uint32_t)0x00000002)
+#define FSMC_FLAG_FallingEdge                    ((uint32_t)0x00000004)
+#define FSMC_FLAG_FEMPT                          ((uint32_t)0x00000040)
+#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \
+                                ((FLAG) == FSMC_FLAG_Level) || \
+                                ((FLAG) == FSMC_FLAG_FallingEdge) || \
+                                ((FLAG) == FSMC_FLAG_FEMPT))
+
+#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/* NOR/SRAM Controller functions **********************************************/
+void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank);
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct);
+void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState);
+
+/* NAND Controller functions **************************************************/
+void FSMC_NANDDeInit(uint32_t FSMC_Bank);
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct);
+void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState);
+void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState);
+uint32_t FSMC_GetECC(uint32_t FSMC_Bank);
+
+/* PCCARD Controller functions ************************************************/
+void FSMC_PCCARDDeInit(void);
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct);
+void FSMC_PCCARDCmd(FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState);
+FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG);
+void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG);
+ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT);
+void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_FSMC_H */
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h
new file mode 100644
index 0000000000000000000000000000000000000000..d93b141971a01e5e9f75ae194f90a6a76fcf0787
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_gpio.h
@@ -0,0 +1,489 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_gpio.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the GPIO firmware
+  *          library.  
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_GPIO_H
+#define __STM32F4xx_GPIO_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup GPIO
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \
+                                    ((PERIPH) == GPIOB) || \
+                                    ((PERIPH) == GPIOC) || \
+                                    ((PERIPH) == GPIOD) || \
+                                    ((PERIPH) == GPIOE) || \
+                                    ((PERIPH) == GPIOF) || \
+                                    ((PERIPH) == GPIOG) || \
+                                    ((PERIPH) == GPIOH) || \
+                                    ((PERIPH) == GPIOI) || \
+                                    ((PERIPH) == GPIOJ) || \
+                                    ((PERIPH) == GPIOK))
+                                                                                             
+/** 
+  * @brief  GPIO Configuration Mode enumeration 
+  */   
+typedef enum
+{ 
+  GPIO_Mode_IN   = 0x00, /*!< GPIO Input Mode */
+  GPIO_Mode_OUT  = 0x01, /*!< GPIO Output Mode */
+  GPIO_Mode_AF   = 0x02, /*!< GPIO Alternate function Mode */
+  GPIO_Mode_AN   = 0x03  /*!< GPIO Analog Mode */
+}GPIOMode_TypeDef;
+#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_IN)  || ((MODE) == GPIO_Mode_OUT) || \
+                            ((MODE) == GPIO_Mode_AF)|| ((MODE) == GPIO_Mode_AN))
+
+/** 
+  * @brief  GPIO Output type enumeration 
+  */  
+typedef enum
+{ 
+  GPIO_OType_PP = 0x00,
+  GPIO_OType_OD = 0x01
+}GPIOOType_TypeDef;
+#define IS_GPIO_OTYPE(OTYPE) (((OTYPE) == GPIO_OType_PP) || ((OTYPE) == GPIO_OType_OD))
+
+
+/** 
+  * @brief  GPIO Output Maximum frequency enumeration 
+  */  
+typedef enum
+{ 
+  GPIO_Low_Speed     = 0x00, /*!< Low speed    */
+  GPIO_Medium_Speed  = 0x01, /*!< Medium speed */
+  GPIO_Fast_Speed    = 0x02, /*!< Fast speed   */
+  GPIO_High_Speed    = 0x03  /*!< High speed   */
+}GPIOSpeed_TypeDef;
+
+/* Add legacy definition */
+#define  GPIO_Speed_2MHz    GPIO_Low_Speed    
+#define  GPIO_Speed_25MHz   GPIO_Medium_Speed 
+#define  GPIO_Speed_50MHz   GPIO_Fast_Speed 
+#define  GPIO_Speed_100MHz  GPIO_High_Speed  
+  
+#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Low_Speed) || ((SPEED) == GPIO_Medium_Speed) || \
+                              ((SPEED) == GPIO_Fast_Speed)||  ((SPEED) == GPIO_High_Speed)) 
+
+/** 
+  * @brief  GPIO Configuration PullUp PullDown enumeration 
+  */ 
+typedef enum
+{ 
+  GPIO_PuPd_NOPULL = 0x00,
+  GPIO_PuPd_UP     = 0x01,
+  GPIO_PuPd_DOWN   = 0x02
+}GPIOPuPd_TypeDef;
+#define IS_GPIO_PUPD(PUPD) (((PUPD) == GPIO_PuPd_NOPULL) || ((PUPD) == GPIO_PuPd_UP) || \
+                            ((PUPD) == GPIO_PuPd_DOWN))
+
+/** 
+  * @brief  GPIO Bit SET and Bit RESET enumeration 
+  */ 
+typedef enum
+{ 
+  Bit_RESET = 0,
+  Bit_SET
+}BitAction;
+#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET))
+
+
+/** 
+  * @brief   GPIO Init structure definition  
+  */ 
+typedef struct
+{
+  uint32_t GPIO_Pin;              /*!< Specifies the GPIO pins to be configured.
+                                       This parameter can be any value of @ref GPIO_pins_define */
+
+  GPIOMode_TypeDef GPIO_Mode;     /*!< Specifies the operating mode for the selected pins.
+                                       This parameter can be a value of @ref GPIOMode_TypeDef */
+
+  GPIOSpeed_TypeDef GPIO_Speed;   /*!< Specifies the speed for the selected pins.
+                                       This parameter can be a value of @ref GPIOSpeed_TypeDef */
+
+  GPIOOType_TypeDef GPIO_OType;   /*!< Specifies the operating output type for the selected pins.
+                                       This parameter can be a value of @ref GPIOOType_TypeDef */
+
+  GPIOPuPd_TypeDef GPIO_PuPd;     /*!< Specifies the operating Pull-up/Pull down for the selected pins.
+                                       This parameter can be a value of @ref GPIOPuPd_TypeDef */
+}GPIO_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup GPIO_Exported_Constants
+  * @{
+  */ 
+
+/** @defgroup GPIO_pins_define 
+  * @{
+  */ 
+#define GPIO_Pin_0                 ((uint16_t)0x0001)  /* Pin 0 selected */
+#define GPIO_Pin_1                 ((uint16_t)0x0002)  /* Pin 1 selected */
+#define GPIO_Pin_2                 ((uint16_t)0x0004)  /* Pin 2 selected */
+#define GPIO_Pin_3                 ((uint16_t)0x0008)  /* Pin 3 selected */
+#define GPIO_Pin_4                 ((uint16_t)0x0010)  /* Pin 4 selected */
+#define GPIO_Pin_5                 ((uint16_t)0x0020)  /* Pin 5 selected */
+#define GPIO_Pin_6                 ((uint16_t)0x0040)  /* Pin 6 selected */
+#define GPIO_Pin_7                 ((uint16_t)0x0080)  /* Pin 7 selected */
+#define GPIO_Pin_8                 ((uint16_t)0x0100)  /* Pin 8 selected */
+#define GPIO_Pin_9                 ((uint16_t)0x0200)  /* Pin 9 selected */
+#define GPIO_Pin_10                ((uint16_t)0x0400)  /* Pin 10 selected */
+#define GPIO_Pin_11                ((uint16_t)0x0800)  /* Pin 11 selected */
+#define GPIO_Pin_12                ((uint16_t)0x1000)  /* Pin 12 selected */
+#define GPIO_Pin_13                ((uint16_t)0x2000)  /* Pin 13 selected */
+#define GPIO_Pin_14                ((uint16_t)0x4000)  /* Pin 14 selected */
+#define GPIO_Pin_15                ((uint16_t)0x8000)  /* Pin 15 selected */
+#define GPIO_Pin_All               ((uint16_t)0xFFFF)  /* All pins selected */
+
+#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00))
+#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \
+                              ((PIN) == GPIO_Pin_1) || \
+                              ((PIN) == GPIO_Pin_2) || \
+                              ((PIN) == GPIO_Pin_3) || \
+                              ((PIN) == GPIO_Pin_4) || \
+                              ((PIN) == GPIO_Pin_5) || \
+                              ((PIN) == GPIO_Pin_6) || \
+                              ((PIN) == GPIO_Pin_7) || \
+                              ((PIN) == GPIO_Pin_8) || \
+                              ((PIN) == GPIO_Pin_9) || \
+                              ((PIN) == GPIO_Pin_10) || \
+                              ((PIN) == GPIO_Pin_11) || \
+                              ((PIN) == GPIO_Pin_12) || \
+                              ((PIN) == GPIO_Pin_13) || \
+                              ((PIN) == GPIO_Pin_14) || \
+                              ((PIN) == GPIO_Pin_15))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup GPIO_Pin_sources 
+  * @{
+  */ 
+#define GPIO_PinSource0            ((uint8_t)0x00)
+#define GPIO_PinSource1            ((uint8_t)0x01)
+#define GPIO_PinSource2            ((uint8_t)0x02)
+#define GPIO_PinSource3            ((uint8_t)0x03)
+#define GPIO_PinSource4            ((uint8_t)0x04)
+#define GPIO_PinSource5            ((uint8_t)0x05)
+#define GPIO_PinSource6            ((uint8_t)0x06)
+#define GPIO_PinSource7            ((uint8_t)0x07)
+#define GPIO_PinSource8            ((uint8_t)0x08)
+#define GPIO_PinSource9            ((uint8_t)0x09)
+#define GPIO_PinSource10           ((uint8_t)0x0A)
+#define GPIO_PinSource11           ((uint8_t)0x0B)
+#define GPIO_PinSource12           ((uint8_t)0x0C)
+#define GPIO_PinSource13           ((uint8_t)0x0D)
+#define GPIO_PinSource14           ((uint8_t)0x0E)
+#define GPIO_PinSource15           ((uint8_t)0x0F)
+
+#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \
+                                       ((PINSOURCE) == GPIO_PinSource1) || \
+                                       ((PINSOURCE) == GPIO_PinSource2) || \
+                                       ((PINSOURCE) == GPIO_PinSource3) || \
+                                       ((PINSOURCE) == GPIO_PinSource4) || \
+                                       ((PINSOURCE) == GPIO_PinSource5) || \
+                                       ((PINSOURCE) == GPIO_PinSource6) || \
+                                       ((PINSOURCE) == GPIO_PinSource7) || \
+                                       ((PINSOURCE) == GPIO_PinSource8) || \
+                                       ((PINSOURCE) == GPIO_PinSource9) || \
+                                       ((PINSOURCE) == GPIO_PinSource10) || \
+                                       ((PINSOURCE) == GPIO_PinSource11) || \
+                                       ((PINSOURCE) == GPIO_PinSource12) || \
+                                       ((PINSOURCE) == GPIO_PinSource13) || \
+                                       ((PINSOURCE) == GPIO_PinSource14) || \
+                                       ((PINSOURCE) == GPIO_PinSource15))
+/**
+  * @}
+  */ 
+
+/** @defgroup GPIO_Alternat_function_selection_define 
+  * @{
+  */ 
+/** 
+  * @brief   AF 0 selection  
+  */ 
+#define GPIO_AF_RTC_50Hz      ((uint8_t)0x00)  /* RTC_50Hz Alternate Function mapping */
+#define GPIO_AF_MCO           ((uint8_t)0x00)  /* MCO (MCO1 and MCO2) Alternate Function mapping */
+#define GPIO_AF_TAMPER        ((uint8_t)0x00)  /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */
+#define GPIO_AF_SWJ           ((uint8_t)0x00)  /* SWJ (SWD and JTAG) Alternate Function mapping */
+#define GPIO_AF_TRACE         ((uint8_t)0x00)  /* TRACE Alternate Function mapping */
+
+/** 
+  * @brief   AF 1 selection  
+  */ 
+#define GPIO_AF_TIM1          ((uint8_t)0x01)  /* TIM1 Alternate Function mapping */
+#define GPIO_AF_TIM2          ((uint8_t)0x01)  /* TIM2 Alternate Function mapping */
+
+/** 
+  * @brief   AF 2 selection  
+  */ 
+#define GPIO_AF_TIM3          ((uint8_t)0x02)  /* TIM3 Alternate Function mapping */
+#define GPIO_AF_TIM4          ((uint8_t)0x02)  /* TIM4 Alternate Function mapping */
+#define GPIO_AF_TIM5          ((uint8_t)0x02)  /* TIM5 Alternate Function mapping */
+
+/** 
+  * @brief   AF 3 selection  
+  */ 
+#define GPIO_AF_TIM8          ((uint8_t)0x03)  /* TIM8 Alternate Function mapping */
+#define GPIO_AF_TIM9          ((uint8_t)0x03)  /* TIM9 Alternate Function mapping */
+#define GPIO_AF_TIM10         ((uint8_t)0x03)  /* TIM10 Alternate Function mapping */
+#define GPIO_AF_TIM11         ((uint8_t)0x03)  /* TIM11 Alternate Function mapping */
+
+/** 
+  * @brief   AF 4 selection  
+  */ 
+#define GPIO_AF_I2C1          ((uint8_t)0x04)  /* I2C1 Alternate Function mapping */
+#define GPIO_AF_I2C2          ((uint8_t)0x04)  /* I2C2 Alternate Function mapping */
+#define GPIO_AF_I2C3          ((uint8_t)0x04)  /* I2C3 Alternate Function mapping */
+
+/** 
+  * @brief   AF 5 selection  
+  */ 
+#define GPIO_AF_SPI1          ((uint8_t)0x05)  /* SPI1 Alternate Function mapping      */
+#define GPIO_AF_SPI2          ((uint8_t)0x05)  /* SPI2/I2S2 Alternate Function mapping */
+#define GPIO_AF_SPI4          ((uint8_t)0x05)  /* SPI4 Alternate Function mapping      */
+#define GPIO_AF_SPI5          ((uint8_t)0x05)  /* SPI5 Alternate Function mapping      */
+#define GPIO_AF_SPI6          ((uint8_t)0x05)  /* SPI6 Alternate Function mapping      */
+
+/** 
+  * @brief   AF 6 selection  
+  */ 
+#define GPIO_AF_SPI3          ((uint8_t)0x06)  /* SPI3/I2S3 Alternate Function mapping */
+
+#define GPIO_AF_SAI1          ((uint8_t)0x06)  /* SAI1 Alternate Function mapping      */
+
+/** 
+  * @brief   AF 7 selection  
+  */ 
+#define GPIO_AF_USART1        ((uint8_t)0x07)  /* USART1 Alternate Function mapping  */
+#define GPIO_AF_USART2        ((uint8_t)0x07)  /* USART2 Alternate Function mapping  */
+#define GPIO_AF_USART3        ((uint8_t)0x07)  /* USART3 Alternate Function mapping  */
+#define GPIO_AF_I2S3ext       ((uint8_t)0x07)  /* I2S3ext Alternate Function mapping */
+
+/** 
+  * @brief   AF 8 selection  
+  */ 
+#define GPIO_AF_UART4         ((uint8_t)0x08)  /* UART4 Alternate Function mapping  */
+#define GPIO_AF_UART5         ((uint8_t)0x08)  /* UART5 Alternate Function mapping  */
+#define GPIO_AF_USART6        ((uint8_t)0x08)  /* USART6 Alternate Function mapping */
+#define GPIO_AF_UART7         ((uint8_t)0x08)  /* UART7 Alternate Function mapping  */
+#define GPIO_AF_UART8         ((uint8_t)0x08)  /* UART8 Alternate Function mapping  */
+
+/** 
+  * @brief   AF 9 selection 
+  */ 
+#define GPIO_AF_CAN1          ((uint8_t)0x09)  /* CAN1 Alternate Function mapping  */
+#define GPIO_AF_CAN2          ((uint8_t)0x09)  /* CAN2 Alternate Function mapping  */
+#define GPIO_AF_TIM12         ((uint8_t)0x09)  /* TIM12 Alternate Function mapping */
+#define GPIO_AF_TIM13         ((uint8_t)0x09)  /* TIM13 Alternate Function mapping */
+#define GPIO_AF_TIM14         ((uint8_t)0x09)  /* TIM14 Alternate Function mapping */
+
+#define GPIO_AF9_I2C2          ((uint8_t)0x09)  /* I2C2 Alternate Function mapping (Only for STM32F401xx Devices) */
+#define GPIO_AF9_I2C3          ((uint8_t)0x09)  /* I2C3 Alternate Function mapping (Only for STM32F401xx Devices) */
+
+/** 
+  * @brief   AF 10 selection  
+  */ 
+#define GPIO_AF_OTG_FS         ((uint8_t)0xA)  /* OTG_FS Alternate Function mapping */
+#define GPIO_AF_OTG_HS         ((uint8_t)0xA)  /* OTG_HS Alternate Function mapping */
+
+/** 
+  * @brief   AF 11 selection  
+  */ 
+#define GPIO_AF_ETH             ((uint8_t)0x0B)  /* ETHERNET Alternate Function mapping */
+
+/** 
+  * @brief   AF 12 selection  
+  */ 
+#if defined (STM32F40_41xxx)
+#define GPIO_AF_FSMC             ((uint8_t)0xC)  /* FSMC Alternate Function mapping                     */
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define GPIO_AF_FMC              ((uint8_t)0xC)  /* FMC Alternate Function mapping                      */
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#define GPIO_AF_OTG_HS_FS        ((uint8_t)0xC)  /* OTG HS configured in FS, Alternate Function mapping */
+#define GPIO_AF_SDIO             ((uint8_t)0xC)  /* SDIO Alternate Function mapping                     */
+
+/** 
+  * @brief   AF 13 selection  
+  */ 
+#define GPIO_AF_DCMI          ((uint8_t)0x0D)  /* DCMI Alternate Function mapping */
+
+/** 
+  * @brief   AF 14 selection  
+  */
+
+#define GPIO_AF_LTDC          ((uint8_t)0x0E)  /* LCD-TFT Alternate Function mapping */
+
+/** 
+  * @brief   AF 15 selection  
+  */ 
+#define GPIO_AF_EVENTOUT      ((uint8_t)0x0F)  /* EVENTOUT Alternate Function mapping */
+
+#if defined (STM32F40_41xxx)
+#define IS_GPIO_AF(AF)   (((AF) == GPIO_AF_RTC_50Hz)  || ((AF) == GPIO_AF_TIM14)     || \
+                          ((AF) == GPIO_AF_MCO)       || ((AF) == GPIO_AF_TAMPER)    || \
+                          ((AF) == GPIO_AF_SWJ)       || ((AF) == GPIO_AF_TRACE)     || \
+                          ((AF) == GPIO_AF_TIM1)      || ((AF) == GPIO_AF_TIM2)      || \
+                          ((AF) == GPIO_AF_TIM3)      || ((AF) == GPIO_AF_TIM4)      || \
+                          ((AF) == GPIO_AF_TIM5)      || ((AF) == GPIO_AF_TIM8)      || \
+                          ((AF) == GPIO_AF_I2C1)      || ((AF) == GPIO_AF_I2C2)      || \
+                          ((AF) == GPIO_AF_I2C3)      || ((AF) == GPIO_AF_SPI1)      || \
+                          ((AF) == GPIO_AF_SPI2)      || ((AF) == GPIO_AF_TIM13)     || \
+                          ((AF) == GPIO_AF_SPI3)      || ((AF) == GPIO_AF_TIM14)     || \
+                          ((AF) == GPIO_AF_USART1)    || ((AF) == GPIO_AF_USART2)    || \
+                          ((AF) == GPIO_AF_USART3)    || ((AF) == GPIO_AF_UART4)     || \
+                          ((AF) == GPIO_AF_UART5)     || ((AF) == GPIO_AF_USART6)    || \
+                          ((AF) == GPIO_AF_CAN1)      || ((AF) == GPIO_AF_CAN2)      || \
+                          ((AF) == GPIO_AF_OTG_FS)    || ((AF) == GPIO_AF_OTG_HS)    || \
+                          ((AF) == GPIO_AF_ETH)       || ((AF) == GPIO_AF_OTG_HS_FS) || \
+                          ((AF) == GPIO_AF_SDIO)      || ((AF) == GPIO_AF_DCMI)      || \
+                          ((AF) == GPIO_AF_EVENTOUT)  || ((AF) == GPIO_AF_FSMC))
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F401xx)
+#define IS_GPIO_AF(AF)   (((AF) == GPIO_AF_RTC_50Hz)  || ((AF) == GPIO_AF_TIM14)     || \
+                          ((AF) == GPIO_AF_MCO)       || ((AF) == GPIO_AF_TAMPER)    || \
+                          ((AF) == GPIO_AF_SWJ)       || ((AF) == GPIO_AF_TRACE)     || \
+                          ((AF) == GPIO_AF_TIM1)      || ((AF) == GPIO_AF_TIM2)      || \
+                          ((AF) == GPIO_AF_TIM3)      || ((AF) == GPIO_AF_TIM4)      || \
+                          ((AF) == GPIO_AF_TIM5)      || ((AF) == GPIO_AF_TIM8)      || \
+                          ((AF) == GPIO_AF_I2C1)      || ((AF) == GPIO_AF_I2C2)      || \
+                          ((AF) == GPIO_AF_I2C3)      || ((AF) == GPIO_AF_SPI1)      || \
+                          ((AF) == GPIO_AF_SPI2)      || ((AF) == GPIO_AF_TIM13)     || \
+                          ((AF) == GPIO_AF_SPI3)      || ((AF) == GPIO_AF_TIM14)     || \
+                          ((AF) == GPIO_AF_USART1)    || ((AF) == GPIO_AF_USART2)    || \
+                          ((AF) == GPIO_AF_SDIO)      || ((AF) == GPIO_AF_USART6)    || \
+                          ((AF) == GPIO_AF_OTG_FS)    || ((AF) == GPIO_AF_OTG_HS)    || \
+                          ((AF) == GPIO_AF_EVENTOUT)  || ((AF) == GPIO_AF_SPI4))
+#endif /* STM32F401xx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define IS_GPIO_AF(AF)   (((AF) == GPIO_AF_RTC_50Hz)  || ((AF) == GPIO_AF_TIM14)     || \
+                          ((AF) == GPIO_AF_MCO)       || ((AF) == GPIO_AF_TAMPER)    || \
+                          ((AF) == GPIO_AF_SWJ)       || ((AF) == GPIO_AF_TRACE)     || \
+                          ((AF) == GPIO_AF_TIM1)      || ((AF) == GPIO_AF_TIM2)      || \
+                          ((AF) == GPIO_AF_TIM3)      || ((AF) == GPIO_AF_TIM4)      || \
+                          ((AF) == GPIO_AF_TIM5)      || ((AF) == GPIO_AF_TIM8)      || \
+                          ((AF) == GPIO_AF_I2C1)      || ((AF) == GPIO_AF_I2C2)      || \
+                          ((AF) == GPIO_AF_I2C3)      || ((AF) == GPIO_AF_SPI1)      || \
+                          ((AF) == GPIO_AF_SPI2)      || ((AF) == GPIO_AF_TIM13)     || \
+                          ((AF) == GPIO_AF_SPI3)      || ((AF) == GPIO_AF_TIM14)     || \
+                          ((AF) == GPIO_AF_USART1)    || ((AF) == GPIO_AF_USART2)    || \
+                          ((AF) == GPIO_AF_USART3)    || ((AF) == GPIO_AF_UART4)     || \
+                          ((AF) == GPIO_AF_UART5)     || ((AF) == GPIO_AF_USART6)    || \
+                          ((AF) == GPIO_AF_CAN1)      || ((AF) == GPIO_AF_CAN2)      || \
+                          ((AF) == GPIO_AF_OTG_FS)    || ((AF) == GPIO_AF_OTG_HS)    || \
+                          ((AF) == GPIO_AF_ETH)       || ((AF) == GPIO_AF_OTG_HS_FS) || \
+                          ((AF) == GPIO_AF_SDIO)      || ((AF) == GPIO_AF_DCMI)      || \
+                          ((AF) == GPIO_AF_EVENTOUT)  || ((AF) == GPIO_AF_SPI4)      || \
+                          ((AF) == GPIO_AF_SPI5)      || ((AF) == GPIO_AF_SPI6)      || \
+                          ((AF) == GPIO_AF_UART7)     || ((AF) == GPIO_AF_UART8)     || \
+                          ((AF) == GPIO_AF_FMC)       ||  ((AF) == GPIO_AF_SAI1)     || \
+                          ((AF) == GPIO_AF_LTDC))
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+                          
+/**
+  * @}
+  */ 
+
+/** @defgroup GPIO_Legacy 
+  * @{
+  */
+    
+#define GPIO_Mode_AIN           GPIO_Mode_AN
+
+#define GPIO_AF_OTG1_FS         GPIO_AF_OTG_FS
+#define GPIO_AF_OTG2_HS         GPIO_AF_OTG_HS
+#define GPIO_AF_OTG2_FS         GPIO_AF_OTG_HS_FS
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the GPIO configuration to the default reset state ****/
+void GPIO_DeInit(GPIO_TypeDef* GPIOx);
+
+/* Initialization and Configuration functions *********************************/
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct);
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct);
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+
+/* GPIO Read and Write functions **********************************************/
+uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx);
+uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx);
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal);
+void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal);
+void GPIO_ToggleBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin);
+
+/* GPIO Alternate functions configuration function ****************************/
+void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_GPIO_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h
new file mode 100644
index 0000000000000000000000000000000000000000..d3689500b0a883da15eac0a164ccb7408bf35450
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_hash.h
@@ -0,0 +1,257 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_hash.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the HASH 
+  *          firmware library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_HASH_H
+#define __STM32F4xx_HASH_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup HASH
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief   HASH Init structure definition
+  */ 
+typedef struct
+{
+  uint32_t HASH_AlgoSelection; /*!< SHA-1, SHA-224, SHA-256 or MD5. This parameter
+                                    can be a value of @ref HASH_Algo_Selection */
+  uint32_t HASH_AlgoMode;      /*!< HASH or HMAC. This parameter can be a value 
+                                    of @ref HASH_processor_Algorithm_Mode */
+  uint32_t HASH_DataType;      /*!< 32-bit data, 16-bit data, 8-bit data or 
+                                    bit string. This parameter can be a value of
+                                    @ref HASH_Data_Type */
+  uint32_t HASH_HMACKeyType;   /*!< HMAC Short key or HMAC Long Key. This parameter
+                                    can be a value of @ref HASH_HMAC_Long_key_only_for_HMAC_mode */
+}HASH_InitTypeDef;
+
+/** 
+  * @brief  HASH message digest result structure definition  
+  */ 
+typedef struct
+{
+  uint32_t Data[8];      /*!< Message digest result : 8x 32bit wors for SHA-256,
+                                                      7x 32bit wors for SHA-224,
+                                                      5x 32bit words for SHA-1 or
+                                                      4x 32bit words for MD5  */
+} HASH_MsgDigest; 
+
+/** 
+  * @brief  HASH context swapping structure definition  
+  */ 
+typedef struct
+{
+  uint32_t HASH_IMR; 
+  uint32_t HASH_STR;      
+  uint32_t HASH_CR;     
+  uint32_t HASH_CSR[54];       
+}HASH_Context;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup HASH_Exported_Constants
+  * @{
+  */ 
+
+/** @defgroup HASH_Algo_Selection 
+  * @{
+  */ 
+#define HASH_AlgoSelection_SHA1      ((uint32_t)0x0000) /*!< HASH function is SHA1   */
+#define HASH_AlgoSelection_SHA224    HASH_CR_ALGO_1     /*!< HASH function is SHA224 */
+#define HASH_AlgoSelection_SHA256    HASH_CR_ALGO       /*!< HASH function is SHA256 */
+#define HASH_AlgoSelection_MD5       HASH_CR_ALGO_0     /*!< HASH function is MD5    */
+
+#define IS_HASH_ALGOSELECTION(ALGOSELECTION) (((ALGOSELECTION) == HASH_AlgoSelection_SHA1) || \
+                                              ((ALGOSELECTION) == HASH_AlgoSelection_SHA224) || \
+                                              ((ALGOSELECTION) == HASH_AlgoSelection_SHA256) || \
+                                              ((ALGOSELECTION) == HASH_AlgoSelection_MD5))
+/**
+  * @}
+  */
+
+/** @defgroup HASH_processor_Algorithm_Mode 
+  * @{
+  */ 
+#define HASH_AlgoMode_HASH         ((uint32_t)0x00000000) /*!< Algorithm is HASH */ 
+#define HASH_AlgoMode_HMAC         HASH_CR_MODE           /*!< Algorithm is HMAC */
+
+#define IS_HASH_ALGOMODE(ALGOMODE) (((ALGOMODE) == HASH_AlgoMode_HASH) || \
+                                    ((ALGOMODE) == HASH_AlgoMode_HMAC))
+/**
+  * @}
+  */
+
+/** @defgroup HASH_Data_Type  
+  * @{
+  */  
+#define HASH_DataType_32b          ((uint32_t)0x0000) /*!< 32-bit data. No swapping                     */
+#define HASH_DataType_16b          HASH_CR_DATATYPE_0 /*!< 16-bit data. Each half word is swapped       */
+#define HASH_DataType_8b           HASH_CR_DATATYPE_1 /*!< 8-bit data. All bytes are swapped            */
+#define HASH_DataType_1b           HASH_CR_DATATYPE   /*!< 1-bit data. In the word all bits are swapped */
+
+#define IS_HASH_DATATYPE(DATATYPE) (((DATATYPE) == HASH_DataType_32b)|| \
+                                    ((DATATYPE) == HASH_DataType_16b)|| \
+                                    ((DATATYPE) == HASH_DataType_8b) || \
+                                    ((DATATYPE) == HASH_DataType_1b))
+/**
+  * @}
+  */
+
+/** @defgroup HASH_HMAC_Long_key_only_for_HMAC_mode  
+  * @{
+  */ 
+#define HASH_HMACKeyType_ShortKey      ((uint32_t)0x00000000) /*!< HMAC Key is <= 64 bytes */
+#define HASH_HMACKeyType_LongKey       HASH_CR_LKEY           /*!< HMAC Key is > 64 bytes  */
+
+#define IS_HASH_HMAC_KEYTYPE(KEYTYPE) (((KEYTYPE) == HASH_HMACKeyType_ShortKey) || \
+                                       ((KEYTYPE) == HASH_HMACKeyType_LongKey))
+/**
+  * @}
+  */
+
+/** @defgroup Number_of_valid_bits_in_last_word_of_the_message   
+  * @{
+  */  
+#define IS_HASH_VALIDBITSNUMBER(VALIDBITS) ((VALIDBITS) <= 0x1F)
+
+/**
+  * @}
+  */
+
+/** @defgroup HASH_interrupts_definition   
+  * @{
+  */  
+#define HASH_IT_DINI               HASH_IMR_DINIM  /*!< A new block can be entered into the input buffer (DIN) */
+#define HASH_IT_DCI                HASH_IMR_DCIM   /*!< Digest calculation complete                            */
+
+#define IS_HASH_IT(IT) ((((IT) & (uint32_t)0xFFFFFFFC) == 0x00000000) && ((IT) != 0x00000000))
+#define IS_HASH_GET_IT(IT) (((IT) == HASH_IT_DINI) || ((IT) == HASH_IT_DCI))
+				   
+/**
+  * @}
+  */
+
+/** @defgroup HASH_flags_definition   
+  * @{
+  */  
+#define HASH_FLAG_DINIS            HASH_SR_DINIS  /*!< 16 locations are free in the DIN : A new block can be entered into the input buffer */
+#define HASH_FLAG_DCIS             HASH_SR_DCIS   /*!< Digest calculation complete                                                         */
+#define HASH_FLAG_DMAS             HASH_SR_DMAS   /*!< DMA interface is enabled (DMAE=1) or a transfer is ongoing                          */
+#define HASH_FLAG_BUSY             HASH_SR_BUSY   /*!< The hash core is Busy : processing a block of data                                  */
+#define HASH_FLAG_DINNE            HASH_CR_DINNE  /*!< DIN not empty : The input buffer contains at least one word of data                 */
+
+#define IS_HASH_GET_FLAG(FLAG) (((FLAG) == HASH_FLAG_DINIS) || \
+                                ((FLAG) == HASH_FLAG_DCIS)  || \
+                                ((FLAG) == HASH_FLAG_DMAS)  || \
+                                ((FLAG) == HASH_FLAG_BUSY)  || \
+                                ((FLAG) == HASH_FLAG_DINNE)) 
+
+#define IS_HASH_CLEAR_FLAG(FLAG)(((FLAG) == HASH_FLAG_DINIS) || \
+                                 ((FLAG) == HASH_FLAG_DCIS))                                 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+  
+/*  Function used to set the HASH configuration to the default reset state ****/
+void HASH_DeInit(void);
+
+/* HASH Configuration function ************************************************/
+void HASH_Init(HASH_InitTypeDef* HASH_InitStruct);
+void HASH_StructInit(HASH_InitTypeDef* HASH_InitStruct);
+void HASH_Reset(void);
+
+/* HASH Message Digest generation functions ***********************************/
+void HASH_DataIn(uint32_t Data);
+uint8_t HASH_GetInFIFOWordsNbr(void);
+void HASH_SetLastWordValidBitsNbr(uint16_t ValidNumber);
+void HASH_StartDigest(void);
+void HASH_AutoStartDigest(FunctionalState NewState);
+void HASH_GetDigest(HASH_MsgDigest* HASH_MessageDigest);
+
+/* HASH Context swapping functions ********************************************/
+void HASH_SaveContext(HASH_Context* HASH_ContextSave);
+void HASH_RestoreContext(HASH_Context* HASH_ContextRestore);
+
+/* HASH DMA interface function ************************************************/
+void HASH_DMACmd(FunctionalState NewState);
+
+/* HASH Interrupts and flags management functions *****************************/
+void HASH_ITConfig(uint32_t HASH_IT, FunctionalState NewState);
+FlagStatus HASH_GetFlagStatus(uint32_t HASH_FLAG);
+void HASH_ClearFlag(uint32_t HASH_FLAG);
+ITStatus HASH_GetITStatus(uint32_t HASH_IT);
+void HASH_ClearITPendingBit(uint32_t HASH_IT);
+
+/* High Level SHA1 functions **************************************************/
+ErrorStatus HASH_SHA1(uint8_t *Input, uint32_t Ilen, uint8_t Output[20]);
+ErrorStatus HMAC_SHA1(uint8_t *Key, uint32_t Keylen,
+                      uint8_t *Input, uint32_t Ilen,
+                      uint8_t Output[20]);
+
+/* High Level MD5 functions ***************************************************/
+ErrorStatus HASH_MD5(uint8_t *Input, uint32_t Ilen, uint8_t Output[16]);
+ErrorStatus HMAC_MD5(uint8_t *Key, uint32_t Keylen,
+                     uint8_t *Input, uint32_t Ilen,
+                     uint8_t Output[16]);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_HASH_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h
new file mode 100644
index 0000000000000000000000000000000000000000..87ca212843225679d2d84db88b2cdbd701040af9
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_i2c.h
@@ -0,0 +1,711 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_i2c.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the I2C firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_I2C_H
+#define __STM32F4xx_I2C_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup I2C
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  I2C Init structure definition  
+  */
+
+typedef struct
+{
+  uint32_t I2C_ClockSpeed;          /*!< Specifies the clock frequency.
+                                         This parameter must be set to a value lower than 400kHz */
+
+  uint16_t I2C_Mode;                /*!< Specifies the I2C mode.
+                                         This parameter can be a value of @ref I2C_mode */
+
+  uint16_t I2C_DutyCycle;           /*!< Specifies the I2C fast mode duty cycle.
+                                         This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */
+
+  uint16_t I2C_OwnAddress1;         /*!< Specifies the first device own address.
+                                         This parameter can be a 7-bit or 10-bit address. */
+
+  uint16_t I2C_Ack;                 /*!< Enables or disables the acknowledgement.
+                                         This parameter can be a value of @ref I2C_acknowledgement */
+
+  uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged.
+                                         This parameter can be a value of @ref I2C_acknowledged_address */
+}I2C_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+
+/** @defgroup I2C_Exported_Constants
+  * @{
+  */
+
+#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \
+                                   ((PERIPH) == I2C2) || \
+                                   ((PERIPH) == I2C3))
+
+/** @defgroup I2C_Digital_Filter
+  * @{
+  */
+
+#define IS_I2C_DIGITAL_FILTER(FILTER)   ((FILTER) <= 0x0000000F)
+/**
+  * @}
+  */
+
+
+/** @defgroup I2C_mode 
+  * @{
+  */
+
+#define I2C_Mode_I2C                    ((uint16_t)0x0000)
+#define I2C_Mode_SMBusDevice            ((uint16_t)0x0002)  
+#define I2C_Mode_SMBusHost              ((uint16_t)0x000A)
+#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \
+                           ((MODE) == I2C_Mode_SMBusDevice) || \
+                           ((MODE) == I2C_Mode_SMBusHost))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_duty_cycle_in_fast_mode 
+  * @{
+  */
+
+#define I2C_DutyCycle_16_9              ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */
+#define I2C_DutyCycle_2                 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */
+#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \
+                                  ((CYCLE) == I2C_DutyCycle_2))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_acknowledgement
+  * @{
+  */
+
+#define I2C_Ack_Enable                  ((uint16_t)0x0400)
+#define I2C_Ack_Disable                 ((uint16_t)0x0000)
+#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \
+                                 ((STATE) == I2C_Ack_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_transfer_direction 
+  * @{
+  */
+
+#define  I2C_Direction_Transmitter      ((uint8_t)0x00)
+#define  I2C_Direction_Receiver         ((uint8_t)0x01)
+#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \
+                                     ((DIRECTION) == I2C_Direction_Receiver))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_acknowledged_address 
+  * @{
+  */
+
+#define I2C_AcknowledgedAddress_7bit    ((uint16_t)0x4000)
+#define I2C_AcknowledgedAddress_10bit   ((uint16_t)0xC000)
+#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \
+                                             ((ADDRESS) == I2C_AcknowledgedAddress_10bit))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_registers 
+  * @{
+  */
+
+#define I2C_Register_CR1                ((uint8_t)0x00)
+#define I2C_Register_CR2                ((uint8_t)0x04)
+#define I2C_Register_OAR1               ((uint8_t)0x08)
+#define I2C_Register_OAR2               ((uint8_t)0x0C)
+#define I2C_Register_DR                 ((uint8_t)0x10)
+#define I2C_Register_SR1                ((uint8_t)0x14)
+#define I2C_Register_SR2                ((uint8_t)0x18)
+#define I2C_Register_CCR                ((uint8_t)0x1C)
+#define I2C_Register_TRISE              ((uint8_t)0x20)
+#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \
+                                   ((REGISTER) == I2C_Register_CR2) || \
+                                   ((REGISTER) == I2C_Register_OAR1) || \
+                                   ((REGISTER) == I2C_Register_OAR2) || \
+                                   ((REGISTER) == I2C_Register_DR) || \
+                                   ((REGISTER) == I2C_Register_SR1) || \
+                                   ((REGISTER) == I2C_Register_SR2) || \
+                                   ((REGISTER) == I2C_Register_CCR) || \
+                                   ((REGISTER) == I2C_Register_TRISE))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_NACK_position 
+  * @{
+  */
+
+#define I2C_NACKPosition_Next           ((uint16_t)0x0800)
+#define I2C_NACKPosition_Current        ((uint16_t)0xF7FF)
+#define IS_I2C_NACK_POSITION(POSITION)  (((POSITION) == I2C_NACKPosition_Next) || \
+                                         ((POSITION) == I2C_NACKPosition_Current))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_SMBus_alert_pin_level 
+  * @{
+  */
+
+#define I2C_SMBusAlert_Low              ((uint16_t)0x2000)
+#define I2C_SMBusAlert_High             ((uint16_t)0xDFFF)
+#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \
+                                   ((ALERT) == I2C_SMBusAlert_High))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_PEC_position 
+  * @{
+  */
+
+#define I2C_PECPosition_Next            ((uint16_t)0x0800)
+#define I2C_PECPosition_Current         ((uint16_t)0xF7FF)
+#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \
+                                       ((POSITION) == I2C_PECPosition_Current))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_interrupts_definition 
+  * @{
+  */
+
+#define I2C_IT_BUF                      ((uint16_t)0x0400)
+#define I2C_IT_EVT                      ((uint16_t)0x0200)
+#define I2C_IT_ERR                      ((uint16_t)0x0100)
+#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup I2C_interrupts_definition 
+  * @{
+  */
+
+#define I2C_IT_SMBALERT                 ((uint32_t)0x01008000)
+#define I2C_IT_TIMEOUT                  ((uint32_t)0x01004000)
+#define I2C_IT_PECERR                   ((uint32_t)0x01001000)
+#define I2C_IT_OVR                      ((uint32_t)0x01000800)
+#define I2C_IT_AF                       ((uint32_t)0x01000400)
+#define I2C_IT_ARLO                     ((uint32_t)0x01000200)
+#define I2C_IT_BERR                     ((uint32_t)0x01000100)
+#define I2C_IT_TXE                      ((uint32_t)0x06000080)
+#define I2C_IT_RXNE                     ((uint32_t)0x06000040)
+#define I2C_IT_STOPF                    ((uint32_t)0x02000010)
+#define I2C_IT_ADD10                    ((uint32_t)0x02000008)
+#define I2C_IT_BTF                      ((uint32_t)0x02000004)
+#define I2C_IT_ADDR                     ((uint32_t)0x02000002)
+#define I2C_IT_SB                       ((uint32_t)0x02000001)
+
+#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00))
+
+#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \
+                           ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \
+                           ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \
+                           ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \
+                           ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \
+                           ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \
+                           ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_flags_definition 
+  * @{
+  */
+
+/** 
+  * @brief  SR2 register flags  
+  */
+
+#define I2C_FLAG_DUALF                  ((uint32_t)0x00800000)
+#define I2C_FLAG_SMBHOST                ((uint32_t)0x00400000)
+#define I2C_FLAG_SMBDEFAULT             ((uint32_t)0x00200000)
+#define I2C_FLAG_GENCALL                ((uint32_t)0x00100000)
+#define I2C_FLAG_TRA                    ((uint32_t)0x00040000)
+#define I2C_FLAG_BUSY                   ((uint32_t)0x00020000)
+#define I2C_FLAG_MSL                    ((uint32_t)0x00010000)
+
+/** 
+  * @brief  SR1 register flags  
+  */
+
+#define I2C_FLAG_SMBALERT               ((uint32_t)0x10008000)
+#define I2C_FLAG_TIMEOUT                ((uint32_t)0x10004000)
+#define I2C_FLAG_PECERR                 ((uint32_t)0x10001000)
+#define I2C_FLAG_OVR                    ((uint32_t)0x10000800)
+#define I2C_FLAG_AF                     ((uint32_t)0x10000400)
+#define I2C_FLAG_ARLO                   ((uint32_t)0x10000200)
+#define I2C_FLAG_BERR                   ((uint32_t)0x10000100)
+#define I2C_FLAG_TXE                    ((uint32_t)0x10000080)
+#define I2C_FLAG_RXNE                   ((uint32_t)0x10000040)
+#define I2C_FLAG_STOPF                  ((uint32_t)0x10000010)
+#define I2C_FLAG_ADD10                  ((uint32_t)0x10000008)
+#define I2C_FLAG_BTF                    ((uint32_t)0x10000004)
+#define I2C_FLAG_ADDR                   ((uint32_t)0x10000002)
+#define I2C_FLAG_SB                     ((uint32_t)0x10000001)
+
+#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00))
+
+#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \
+                               ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \
+                               ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \
+                               ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \
+                               ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \
+                               ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \
+                               ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \
+                               ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \
+                               ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \
+                               ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \
+                               ((FLAG) == I2C_FLAG_SB))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Events 
+  * @{
+  */
+
+/**
+ ===============================================================================
+               I2C Master Events (Events grouped in order of communication)
+ ===============================================================================
+ */
+
+/** 
+  * @brief  Communication start
+  * 
+  * After sending the START condition (I2C_GenerateSTART() function) the master 
+  * has to wait for this event. It means that the Start condition has been correctly 
+  * released on the I2C bus (the bus is free, no other devices is communicating).
+  * 
+  */
+/* --EV5 */
+#define  I2C_EVENT_MASTER_MODE_SELECT                      ((uint32_t)0x00030001)  /* BUSY, MSL and SB flag */
+
+/** 
+  * @brief  Address Acknowledge
+  * 
+  * After checking on EV5 (start condition correctly released on the bus), the 
+  * master sends the address of the slave(s) with which it will communicate 
+  * (I2C_Send7bitAddress() function, it also determines the direction of the communication: 
+  * Master transmitter or Receiver). Then the master has to wait that a slave acknowledges 
+  * his address. If an acknowledge is sent on the bus, one of the following events will 
+  * be set:
+  * 
+  *  1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED 
+  *     event is set.
+  *  
+  *  2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED 
+  *     is set
+  *  
+  *  3) In case of 10-Bit addressing mode, the master (just after generating the START 
+  *  and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData() 
+  *  function). Then master should wait on EV9. It means that the 10-bit addressing 
+  *  header has been correctly sent on the bus. Then master should send the second part of 
+  *  the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master 
+  *  should wait for event EV6. 
+  *     
+  */
+
+/* --EV6 */
+#define  I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED        ((uint32_t)0x00070082)  /* BUSY, MSL, ADDR, TXE and TRA flags */
+#define  I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED           ((uint32_t)0x00030002)  /* BUSY, MSL and ADDR flags */
+/* --EV9 */
+#define  I2C_EVENT_MASTER_MODE_ADDRESS10                   ((uint32_t)0x00030008)  /* BUSY, MSL and ADD10 flags */
+
+/** 
+  * @brief Communication events
+  * 
+  * If a communication is established (START condition generated and slave address 
+  * acknowledged) then the master has to check on one of the following events for 
+  * communication procedures:
+  *  
+  * 1) Master Receiver mode: The master has to wait on the event EV7 then to read 
+  *    the data received from the slave (I2C_ReceiveData() function).
+  * 
+  * 2) Master Transmitter mode: The master has to send data (I2C_SendData() 
+  *    function) then to wait on event EV8 or EV8_2.
+  *    These two events are similar: 
+  *     - EV8 means that the data has been written in the data register and is 
+  *       being shifted out.
+  *     - EV8_2 means that the data has been physically shifted out and output 
+  *       on the bus.
+  *     In most cases, using EV8 is sufficient for the application.
+  *     Using EV8_2 leads to a slower communication but ensure more reliable test.
+  *     EV8_2 is also more suitable than EV8 for testing on the last data transmission 
+  *     (before Stop condition generation).
+  *     
+  *  @note In case the  user software does not guarantee that this event EV7 is 
+  *        managed before the current byte end of transfer, then user may check on EV7 
+  *        and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)).
+  *        In this case the communication may be slower.
+  * 
+  */
+
+/* Master RECEIVER mode -----------------------------*/ 
+/* --EV7 */
+#define  I2C_EVENT_MASTER_BYTE_RECEIVED                    ((uint32_t)0x00030040)  /* BUSY, MSL and RXNE flags */
+
+/* Master TRANSMITTER mode --------------------------*/
+/* --EV8 */
+#define I2C_EVENT_MASTER_BYTE_TRANSMITTING                 ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */
+/* --EV8_2 */
+#define  I2C_EVENT_MASTER_BYTE_TRANSMITTED                 ((uint32_t)0x00070084)  /* TRA, BUSY, MSL, TXE and BTF flags */
+
+
+/**
+ ===============================================================================
+               I2C Slave Events (Events grouped in order of communication)
+ ===============================================================================
+ */
+
+
+/** 
+  * @brief  Communication start events
+  * 
+  * Wait on one of these events at the start of the communication. It means that 
+  * the I2C peripheral detected a Start condition on the bus (generated by master 
+  * device) followed by the peripheral address. The peripheral generates an ACK 
+  * condition on the bus (if the acknowledge feature is enabled through function 
+  * I2C_AcknowledgeConfig()) and the events listed above are set :
+  *  
+  * 1) In normal case (only one address managed by the slave), when the address 
+  *   sent by the master matches the own address of the peripheral (configured by 
+  *   I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set 
+  *   (where XXX could be TRANSMITTER or RECEIVER).
+  *    
+  * 2) In case the address sent by the master matches the second address of the 
+  *   peripheral (configured by the function I2C_OwnAddress2Config() and enabled 
+  *   by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED 
+  *   (where XXX could be TRANSMITTER or RECEIVER) are set.
+  *   
+  * 3) In case the address sent by the master is General Call (address 0x00) and 
+  *   if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd()) 
+  *   the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED.   
+  * 
+  */
+
+/* --EV1  (all the events below are variants of EV1) */   
+/* 1) Case of One Single Address managed by the slave */
+#define  I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED          ((uint32_t)0x00020002) /* BUSY and ADDR flags */
+#define  I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED       ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */
+
+/* 2) Case of Dual address managed by the slave */
+#define  I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED    ((uint32_t)0x00820000)  /* DUALF and BUSY flags */
+#define  I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080)  /* DUALF, TRA, BUSY and TXE flags */
+
+/* 3) Case of General Call enabled for the slave */
+#define  I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED        ((uint32_t)0x00120000)  /* GENCALL and BUSY flags */
+
+/** 
+  * @brief  Communication events
+  * 
+  * Wait on one of these events when EV1 has already been checked and: 
+  * 
+  * - Slave RECEIVER mode:
+  *     - EV2: When the application is expecting a data byte to be received. 
+  *     - EV4: When the application is expecting the end of the communication: master 
+  *       sends a stop condition and data transmission is stopped.
+  *    
+  * - Slave Transmitter mode:
+  *    - EV3: When a byte has been transmitted by the slave and the application is expecting 
+  *      the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and
+  *      I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be 
+  *      used when the user software doesn't guarantee the EV3 is managed before the
+  *      current byte end of transfer.
+  *    - EV3_2: When the master sends a NACK in order to tell slave that data transmission 
+  *      shall end (before sending the STOP condition). In this case slave has to stop sending 
+  *      data bytes and expect a Stop condition on the bus.
+  *      
+  *  @note In case the  user software does not guarantee that the event EV2 is 
+  *        managed before the current byte end of transfer, then user may check on EV2 
+  *        and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)).
+  *        In this case the communication may be slower.
+  *
+  */
+
+/* Slave RECEIVER mode --------------------------*/ 
+/* --EV2 */
+#define  I2C_EVENT_SLAVE_BYTE_RECEIVED                     ((uint32_t)0x00020040)  /* BUSY and RXNE flags */
+/* --EV4  */
+#define  I2C_EVENT_SLAVE_STOP_DETECTED                     ((uint32_t)0x00000010)  /* STOPF flag */
+
+/* Slave TRANSMITTER mode -----------------------*/
+/* --EV3 */
+#define  I2C_EVENT_SLAVE_BYTE_TRANSMITTED                  ((uint32_t)0x00060084)  /* TRA, BUSY, TXE and BTF flags */
+#define  I2C_EVENT_SLAVE_BYTE_TRANSMITTING                 ((uint32_t)0x00060080)  /* TRA, BUSY and TXE flags */
+/* --EV3_2 */
+#define  I2C_EVENT_SLAVE_ACK_FAILURE                       ((uint32_t)0x00000400)  /* AF flag */
+
+/*
+ ===============================================================================
+                          End of Events Description
+ ===============================================================================
+ */
+
+#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \
+                             ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \
+                             ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \
+                             ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \
+                             ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \
+                             ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE))
+/**
+  * @}
+  */
+
+/** @defgroup I2C_own_address1 
+  * @{
+  */
+
+#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF)
+/**
+  * @}
+  */
+
+/** @defgroup I2C_clock_speed 
+  * @{
+  */
+
+#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the I2C configuration to the default reset state *****/
+void I2C_DeInit(I2C_TypeDef* I2Cx);
+
+/* Initialization and Configuration functions *********************************/
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct);
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct);
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DigitalFilterConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DigitalFilter);
+void I2C_AnalogFilterCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction);
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address);
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle);
+void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition);
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert);
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+
+/* Data transfers functions ***************************************************/ 
+void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data);
+uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx);
+
+/* PEC management functions ***************************************************/ 
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition);
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState);
+uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx);
+
+/* DMA transfers management functions *****************************************/
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState);
+
+/* Interrupts, events and flags management functions **************************/
+uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register);
+void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState);
+
+/* 
+ ===============================================================================
+                          I2C State Monitoring Functions
+ ===============================================================================
+  This I2C driver provides three different ways for I2C state monitoring
+  depending on the application requirements and constraints:
+         
+   
+     1. Basic state monitoring (Using I2C_CheckEvent() function)
+     -----------------------------------------------------------
+        It compares the status registers (SR1 and SR2) content to a given event
+        (can be the combination of one or more flags).
+        It returns SUCCESS if the current status includes the given flags 
+        and returns ERROR if one or more flags are missing in the current status.
+
+          - When to use
+             - This function is suitable for most applications as well as for startup 
+               activity since the events are fully described in the product reference 
+               manual (RM0090).
+             - It is also suitable for users who need to define their own events.
+
+          - Limitations
+             - If an error occurs (ie. error flags are set besides to the monitored 
+               flags), the I2C_CheckEvent() function may return SUCCESS despite 
+               the communication hold or corrupted real state. 
+               In this case, it is advised to use error interrupts to monitor 
+               the error events and handle them in the interrupt IRQ handler.
+         
+     Note 
+         For error management, it is advised to use the following functions:
+           - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR).
+           - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs.
+             Where x is the peripheral instance (I2C1, I2C2 ...)
+           - I2C_GetFlagStatus() or I2C_GetITStatus()  to be called into the 
+             I2Cx_ER_IRQHandler() function in order to determine which error occurred.
+           - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() 
+             and/or I2C_GenerateStop() in order to clear the error flag and source 
+             and return to correct  communication status.
+             
+ 
+     2. Advanced state monitoring (Using the function I2C_GetLastEvent())
+     -------------------------------------------------------------------- 
+        Using the function I2C_GetLastEvent() which returns the image of both status 
+        registers in a single word (uint32_t) (Status Register 2 value is shifted left 
+        by 16 bits and concatenated to Status Register 1).
+
+          - When to use
+             - This function is suitable for the same applications above but it 
+               allows to overcome the mentioned limitation of I2C_GetFlagStatus() 
+               function.
+             - The returned value could be compared to events already defined in 
+               this file or to custom values defined by user.
+               This function is suitable when multiple flags are monitored at the 
+               same time.
+             - At the opposite of I2C_CheckEvent() function, this function allows 
+               user to choose when an event is accepted (when all events flags are 
+               set and no other flags are set or just when the needed flags are set 
+               like I2C_CheckEvent() function.
+
+          - Limitations
+             - User may need to define his own events.
+             - Same remark concerning the error management is applicable for this 
+               function if user decides to check only regular communication flags 
+               (and ignores error flags).
+      
+ 
+     3. Flag-based state monitoring (Using the function I2C_GetFlagStatus())
+     -----------------------------------------------------------------------
+     
+      Using the function I2C_GetFlagStatus() which simply returns the status of 
+      one single flag (ie. I2C_FLAG_RXNE ...). 
+
+          - When to use
+             - This function could be used for specific applications or in debug 
+               phase.
+             - It is suitable when only one flag checking is needed (most I2C 
+               events are monitored through multiple flags).
+          - Limitations: 
+             - When calling this function, the Status register is accessed. 
+               Some flags are cleared when the status register is accessed. 
+               So checking the status of one Flag, may clear other ones.
+             - Function may need to be called twice or more in order to monitor 
+               one single event.           
+ */
+
+/*
+ ===============================================================================
+                          1. Basic state monitoring
+ ===============================================================================
+ */
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT);
+/*
+ ===============================================================================
+                          2. Advanced state monitoring
+ ===============================================================================
+ */
+uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx);
+/*
+ ===============================================================================
+                          3. Flag-based state monitoring
+ ===============================================================================
+ */
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
+
+
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG);
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_I2C_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h
new file mode 100644
index 0000000000000000000000000000000000000000..37e5d6e38a80cee3ce67ebade8a8e3fa54b7060f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_iwdg.h
@@ -0,0 +1,131 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_iwdg.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the IWDG 
+  *          firmware library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_IWDG_H
+#define __STM32F4xx_IWDG_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup IWDG
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup IWDG_Exported_Constants
+  * @{
+  */
+  
+/** @defgroup IWDG_WriteAccess
+  * @{
+  */
+#define IWDG_WriteAccess_Enable     ((uint16_t)0x5555)
+#define IWDG_WriteAccess_Disable    ((uint16_t)0x0000)
+#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \
+                                      ((ACCESS) == IWDG_WriteAccess_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_prescaler 
+  * @{
+  */
+#define IWDG_Prescaler_4            ((uint8_t)0x00)
+#define IWDG_Prescaler_8            ((uint8_t)0x01)
+#define IWDG_Prescaler_16           ((uint8_t)0x02)
+#define IWDG_Prescaler_32           ((uint8_t)0x03)
+#define IWDG_Prescaler_64           ((uint8_t)0x04)
+#define IWDG_Prescaler_128          ((uint8_t)0x05)
+#define IWDG_Prescaler_256          ((uint8_t)0x06)
+#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4)  || \
+                                      ((PRESCALER) == IWDG_Prescaler_8)  || \
+                                      ((PRESCALER) == IWDG_Prescaler_16) || \
+                                      ((PRESCALER) == IWDG_Prescaler_32) || \
+                                      ((PRESCALER) == IWDG_Prescaler_64) || \
+                                      ((PRESCALER) == IWDG_Prescaler_128)|| \
+                                      ((PRESCALER) == IWDG_Prescaler_256))
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Flag 
+  * @{
+  */
+#define IWDG_FLAG_PVU               ((uint16_t)0x0001)
+#define IWDG_FLAG_RVU               ((uint16_t)0x0002)
+#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU))
+#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF)
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+/* Prescaler and Counter configuration functions ******************************/
+void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess);
+void IWDG_SetPrescaler(uint8_t IWDG_Prescaler);
+void IWDG_SetReload(uint16_t Reload);
+void IWDG_ReloadCounter(void);
+
+/* IWDG activation function ***************************************************/
+void IWDG_Enable(void);
+
+/* Flag management function ***************************************************/
+FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_IWDG_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_ltdc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_ltdc.h
new file mode 100644
index 0000000000000000000000000000000000000000..0a6f460f993b586d73686033528cd1fd3abee2ad
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_ltdc.h
@@ -0,0 +1,525 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_ltdc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the LTDC firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_LTDC_H
+#define __STM32F4xx_LTDC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup LTDC
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+ 
+/** 
+  * @brief  LTDC Init structure definition  
+  */
+
+typedef struct
+{
+  uint32_t LTDC_HSPolarity;                 /*!< configures the horizontal synchronization polarity.
+                                                 This parameter can be one value of @ref LTDC_HSPolarity */
+
+  uint32_t LTDC_VSPolarity;                 /*!< configures the vertical synchronization polarity.
+                                                 This parameter can be one value of @ref LTDC_VSPolarity */
+
+  uint32_t LTDC_DEPolarity;                 /*!< configures the data enable polarity. This parameter can
+                                                 be one of value of @ref LTDC_DEPolarity */
+
+  uint32_t LTDC_PCPolarity;                 /*!< configures the pixel clock polarity. This parameter can
+                                                 be one of value of @ref LTDC_PCPolarity */
+
+  uint32_t LTDC_HorizontalSync;             /*!< configures the number of Horizontal synchronization 
+                                                 width. This parameter must range from 0x000 to 0xFFF. */
+
+  uint32_t LTDC_VerticalSync;               /*!< configures the number of Vertical synchronization 
+                                                 heigh. This parameter must range from 0x000 to 0x7FF. */
+
+  uint32_t LTDC_AccumulatedHBP;             /*!< configures the accumulated horizontal back porch width.
+                                                 This parameter must range from LTDC_HorizontalSync to 0xFFF. */
+
+  uint32_t LTDC_AccumulatedVBP;             /*!< configures the accumulated vertical back porch heigh.
+                                                 This parameter must range from LTDC_VerticalSync to 0x7FF. */
+            
+  uint32_t LTDC_AccumulatedActiveW;         /*!< configures the accumulated active width. This parameter 
+                                                 must range from LTDC_AccumulatedHBP to 0xFFF. */
+
+  uint32_t LTDC_AccumulatedActiveH;         /*!< configures the accumulated active heigh. This parameter 
+                                                 must range from LTDC_AccumulatedVBP to 0x7FF. */
+
+  uint32_t LTDC_TotalWidth;                 /*!< configures the total width. This parameter 
+                                                 must range from LTDC_AccumulatedActiveW to 0xFFF. */
+
+  uint32_t LTDC_TotalHeigh;                 /*!< configures the total heigh. This parameter 
+                                                 must range from LTDC_AccumulatedActiveH to 0x7FF. */
+            
+  uint32_t LTDC_BackgroundRedValue;         /*!< configures the background red value.
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_BackgroundGreenValue;       /*!< configures the background green value.
+                                                 This parameter must range from 0x00 to 0xFF. */ 
+
+   uint32_t LTDC_BackgroundBlueValue;       /*!< configures the background blue value.
+                                                 This parameter must range from 0x00 to 0xFF. */
+} LTDC_InitTypeDef;
+
+/** 
+  * @brief  LTDC Layer structure definition  
+  */
+
+typedef struct
+{
+  uint32_t LTDC_HorizontalStart;            /*!< Configures the Window Horizontal Start Position.
+                                                 This parameter must range from 0x000 to 0xFFF. */
+            
+  uint32_t LTDC_HorizontalStop;             /*!< Configures the Window Horizontal Stop Position.
+                                                 This parameter must range from 0x0000 to 0xFFFF. */
+  
+  uint32_t LTDC_VerticalStart;              /*!< Configures the Window vertical Start Position.
+                                                 This parameter must range from 0x000 to 0xFFF. */
+
+  uint32_t LTDC_VerticalStop;               /*!< Configures the Window vaertical Stop Position.
+                                                 This parameter must range from 0x0000 to 0xFFFF. */
+  
+  uint32_t LTDC_PixelFormat;                /*!< Specifies the pixel format. This parameter can be 
+                                                 one of value of @ref LTDC_Pixelformat */
+
+  uint32_t LTDC_ConstantAlpha;              /*!< Specifies the constant alpha used for blending.
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_DefaultColorBlue;           /*!< Configures the default blue value.
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_DefaultColorGreen;          /*!< Configures the default green value.
+                                                 This parameter must range from 0x00 to 0xFF. */
+            
+  uint32_t LTDC_DefaultColorRed;            /*!< Configures the default red value.
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_DefaultColorAlpha;          /*!< Configures the default alpha value.
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_BlendingFactor_1;           /*!< Select the blending factor 1. This parameter 
+                                                 can be one of value of @ref LTDC_BlendingFactor1 */
+
+  uint32_t LTDC_BlendingFactor_2;           /*!< Select the blending factor 2. This parameter 
+                                                 can be one of value of @ref LTDC_BlendingFactor2 */
+            
+  uint32_t LTDC_CFBStartAdress;             /*!< Configures the color frame buffer address */
+
+  uint32_t LTDC_CFBLineLength;              /*!< Configures the color frame buffer line length. 
+                                                 This parameter must range from 0x0000 to 0x1FFF. */
+
+  uint32_t LTDC_CFBPitch;                   /*!< Configures the color frame buffer pitch in bytes.
+                                                 This parameter must range from 0x0000 to 0x1FFF. */
+                                                 
+  uint32_t LTDC_CFBLineNumber;              /*!< Specifies the number of line in frame buffer. 
+                                                 This parameter must range from 0x000 to 0x7FF. */
+} LTDC_Layer_InitTypeDef;
+
+/** 
+  * @brief  LTDC Position structure definition  
+  */
+
+typedef struct
+{
+  uint32_t LTDC_POSX;                         /*!<  Current X Position */
+  uint32_t LTDC_POSY;                         /*!<  Current Y Position */
+} LTDC_PosTypeDef;
+
+typedef struct
+{
+  uint32_t LTDC_BlueWidth;                        /*!< Blue width */
+  uint32_t LTDC_GreenWidth;                       /*!< Green width */
+  uint32_t LTDC_RedWidth;                         /*!< Red width */
+} LTDC_RGBTypeDef;
+
+typedef struct
+{
+  uint32_t LTDC_ColorKeyBlue;               /*!< Configures the color key blue value. 
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_ColorKeyGreen;              /*!< Configures the color key green value. 
+                                                 This parameter must range from 0x00 to 0xFF. */
+            
+  uint32_t LTDC_ColorKeyRed;                /*!< Configures the color key red value. 
+                                                 This parameter must range from 0x00 to 0xFF. */
+} LTDC_ColorKeying_InitTypeDef;
+
+typedef struct
+{
+  uint32_t LTDC_CLUTAdress;                 /*!< Configures the CLUT address.
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_BlueValue;                  /*!< Configures the blue value. 
+                                                 This parameter must range from 0x00 to 0xFF. */
+                                                 
+  uint32_t LTDC_GreenValue;                 /*!< Configures the green value. 
+                                                 This parameter must range from 0x00 to 0xFF. */
+
+  uint32_t LTDC_RedValue;                   /*!< Configures the red value.
+                                                 This parameter must range from 0x00 to 0xFF. */
+} LTDC_CLUT_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup LTDC_Exported_Constants
+  * @}
+  */
+  
+/** @defgroup LTDC_SYNC 
+  * @{
+  */
+
+#define LTDC_HorizontalSYNC               ((uint32_t)0x00000FFF)
+#define LTDC_VerticalSYNC                 ((uint32_t)0x000007FF)
+
+#define IS_LTDC_HSYNC(HSYNC) ((HSYNC) <= LTDC_HorizontalSYNC)
+#define IS_LTDC_VSYNC(VSYNC) ((VSYNC) <= LTDC_VerticalSYNC)
+#define IS_LTDC_AHBP(AHBP)  ((AHBP) <= LTDC_HorizontalSYNC)
+#define IS_LTDC_AVBP(AVBP) ((AVBP) <= LTDC_VerticalSYNC)
+#define IS_LTDC_AAW(AAW)   ((AAW) <= LTDC_HorizontalSYNC)
+#define IS_LTDC_AAH(AAH) ((AAH) <= LTDC_VerticalSYNC)
+#define IS_LTDC_TOTALW(TOTALW) ((TOTALW) <= LTDC_HorizontalSYNC)
+#define IS_LTDC_TOTALH(TOTALH) ((TOTALH) <= LTDC_VerticalSYNC)
+
+/**
+  * @}
+  */
+  
+/** @defgroup LTDC_HSPolarity 
+  * @{
+  */
+#define LTDC_HSPolarity_AL                ((uint32_t)0x00000000)                /*!< Horizontal Synchronization is active low. */
+#define LTDC_HSPolarity_AH                LTDC_GCR_HSPOL                        /*!< Horizontal Synchronization is active high. */
+
+#define IS_LTDC_HSPOL(HSPOL) (((HSPOL) == LTDC_HSPolarity_AL) || \
+                              ((HSPOL) == LTDC_HSPolarity_AH))  
+
+/**
+  * @}
+  */
+  
+/** @defgroup LTDC_VSPolarity 
+  * @{
+  */
+#define LTDC_VSPolarity_AL                ((uint32_t)0x00000000)                /*!< Vertical Synchronization is active low. */
+#define LTDC_VSPolarity_AH                LTDC_GCR_VSPOL                        /*!< Vertical Synchronization is active high. */
+
+#define IS_LTDC_VSPOL(VSPOL) (((VSPOL) == LTDC_VSPolarity_AL) || \
+                              ((VSPOL) == LTDC_VSPolarity_AH))  
+
+/**
+  * @}
+  */
+  
+/** @defgroup LTDC_DEPolarity 
+  * @{
+  */
+#define LTDC_DEPolarity_AL                ((uint32_t)0x00000000)                /*!< Data Enable, is active low. */
+#define LTDC_DEPolarity_AH                LTDC_GCR_DEPOL                        /*!< Data Enable, is active high. */
+
+#define IS_LTDC_DEPOL(DEPOL) (((DEPOL) ==  LTDC_VSPolarity_AL) || \
+                              ((DEPOL) ==  LTDC_DEPolarity_AH))
+
+/**
+  * @}
+  */
+
+/** @defgroup LTDC_PCPolarity 
+  * @{
+  */
+#define LTDC_PCPolarity_IPC               ((uint32_t)0x00000000)                /*!< input pixel clock. */
+#define LTDC_PCPolarity_IIPC              LTDC_GCR_PCPOL                        /*!< inverted input pixel clock. */
+
+#define IS_LTDC_PCPOL(PCPOL) (((PCPOL) ==  LTDC_PCPolarity_IPC) || \
+                              ((PCPOL) ==  LTDC_PCPolarity_IIPC))
+
+/**
+  * @}
+  */
+
+/** @defgroup LTDC_Reload 
+  * @{
+  */
+#define LTDC_IMReload                     LTDC_SRCR_IMR                         /*!< Immediately Reload. */
+#define LTDC_VBReload                     LTDC_SRCR_VBR                         /*!< Vertical Blanking Reload. */
+
+#define IS_LTDC_RELOAD(RELOAD) (((RELOAD) == LTDC_IMReload) || \
+                                ((RELOAD) == LTDC_VBReload))
+
+/**
+  * @}
+  */
+  
+/** @defgroup LTDC_Back_Color
+  * @{
+  */ 
+
+#define LTDC_Back_Color                   ((uint32_t)0x000000FF)
+
+#define IS_LTDC_BackBlueValue(BBLUE)    ((BBLUE) <= LTDC_Back_Color)
+#define IS_LTDC_BackGreenValue(BGREEN)  ((BGREEN) <= LTDC_Back_Color)
+#define IS_LTDC_BackRedValue(BRED)      ((BRED) <= LTDC_Back_Color) 
+
+/**
+  * @}
+  */
+      
+/** @defgroup LTDC_Position 
+  * @{
+  */
+
+#define LTDC_POS_CY                       LTDC_CPSR_CYPOS
+#define LTDC_POS_CX                       LTDC_CPSR_CXPOS
+
+#define IS_LTDC_GET_POS(POS) (((POS) <= LTDC_POS_CY))
+
+
+/**
+  * @}
+  */
+      
+/** @defgroup LTDC_LIPosition 
+  * @{
+  */
+
+#define IS_LTDC_LIPOS(LIPOS) ((LIPOS) <= 0x7FF)
+
+/**
+  * @}
+  */
+      
+/** @defgroup LTDC_CurrentStatus 
+  * @{
+  */
+
+#define LTDC_CD_VDES                     LTDC_CDSR_VDES
+#define LTDC_CD_HDES                     LTDC_CDSR_HDES
+#define LTDC_CD_VSYNC                    LTDC_CDSR_VSYNCS
+#define LTDC_CD_HSYNC                    LTDC_CDSR_HSYNCS
+
+
+#define IS_LTDC_GET_CD(CD) (((CD) == LTDC_CD_VDES) || ((CD) == LTDC_CD_HDES) || \
+                              ((CD) == LTDC_CD_VSYNC) || ((CD) == LTDC_CD_HSYNC))
+
+
+/**
+  * @}
+  */  
+
+/** @defgroup LTDC_Interrupts 
+  * @{
+  */                           
+
+#define LTDC_IT_LI                      LTDC_IER_LIE
+#define LTDC_IT_FU                      LTDC_IER_FUIE
+#define LTDC_IT_TERR                    LTDC_IER_TERRIE
+#define LTDC_IT_RR                      LTDC_IER_RRIE
+
+#define IS_LTDC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFF0) == 0x00) && ((IT) != 0x00))
+
+/**
+  * @}
+  */
+      
+/** @defgroup LTDC_Flag 
+  * @{
+  */
+
+#define LTDC_FLAG_LI                     LTDC_ISR_LIF
+#define LTDC_FLAG_FU                     LTDC_ISR_FUIF
+#define LTDC_FLAG_TERR                   LTDC_ISR_TERRIF
+#define LTDC_FLAG_RR                     LTDC_ISR_RRIF
+
+
+#define IS_LTDC_FLAG(FLAG) (((FLAG) == LTDC_FLAG_LI) || ((FLAG) == LTDC_FLAG_FU) || \
+                               ((FLAG) == LTDC_FLAG_TERR) || ((FLAG) == LTDC_FLAG_RR))
+
+/**
+  * @}
+  */
+      
+/** @defgroup LTDC_Pixelformat 
+  * @{
+  */
+#define LTDC_Pixelformat_ARGB8888                  ((uint32_t)0x00000000)
+#define LTDC_Pixelformat_RGB888                    ((uint32_t)0x00000001)
+#define LTDC_Pixelformat_RGB565                    ((uint32_t)0x00000002)
+#define LTDC_Pixelformat_ARGB1555                  ((uint32_t)0x00000003)
+#define LTDC_Pixelformat_ARGB4444                  ((uint32_t)0x00000004)
+#define LTDC_Pixelformat_L8                        ((uint32_t)0x00000005)
+#define LTDC_Pixelformat_AL44                      ((uint32_t)0x00000006)
+#define LTDC_Pixelformat_AL88                      ((uint32_t)0x00000007)
+
+#define IS_LTDC_Pixelformat(Pixelformat) (((Pixelformat) == LTDC_Pixelformat_ARGB8888) || ((Pixelformat) == LTDC_Pixelformat_RGB888)   || \
+                        ((Pixelformat) == LTDC_Pixelformat_RGB565)   || ((Pixelformat) == LTDC_Pixelformat_ARGB1555) || \
+                        ((Pixelformat) == LTDC_Pixelformat_ARGB4444) || ((Pixelformat) == LTDC_Pixelformat_L8)       || \
+                        ((Pixelformat) == LTDC_Pixelformat_AL44)     || ((Pixelformat) == LTDC_Pixelformat_AL88))
+
+/**
+  * @}
+  */
+      
+/** @defgroup LTDC_BlendingFactor1 
+  * @{
+  */
+
+#define LTDC_BlendingFactor1_CA                       ((uint32_t)0x00000400)
+#define LTDC_BlendingFactor1_PAxCA                    ((uint32_t)0x00000600)
+
+#define IS_LTDC_BlendingFactor1(BlendingFactor1) (((BlendingFactor1) == LTDC_BlendingFactor1_CA) || ((BlendingFactor1) == LTDC_BlendingFactor1_PAxCA))
+
+/**
+  * @}
+  */
+      
+/** @defgroup LTDC_BlendingFactor2
+  * @{
+  */
+
+#define LTDC_BlendingFactor2_CA                       ((uint32_t)0x00000005)
+#define LTDC_BlendingFactor2_PAxCA                    ((uint32_t)0x00000007)
+
+#define IS_LTDC_BlendingFactor2(BlendingFactor2) (((BlendingFactor2) == LTDC_BlendingFactor2_CA) || ((BlendingFactor2) == LTDC_BlendingFactor2_PAxCA))
+
+
+/**
+  * @}
+  */
+      
+     
+/** @defgroup LTDC_LAYER_Config
+  * @{
+  */
+
+#define LTDC_STOPPosition                 ((uint32_t)0x0000FFFF)
+#define LTDC_STARTPosition                ((uint32_t)0x00000FFF)
+
+#define LTDC_DefaultColorConfig           ((uint32_t)0x000000FF)
+#define LTDC_ColorFrameBuffer             ((uint32_t)0x00001FFF)
+#define LTDC_LineNumber                   ((uint32_t)0x000007FF)
+
+#define IS_LTDC_HCONFIGST(HCONFIGST) ((HCONFIGST) <= LTDC_STARTPosition)
+#define IS_LTDC_HCONFIGSP(HCONFIGSP) ((HCONFIGSP) <= LTDC_STOPPosition)
+#define IS_LTDC_VCONFIGST(VCONFIGST)  ((VCONFIGST) <= LTDC_STARTPosition)
+#define IS_LTDC_VCONFIGSP(VCONFIGSP) ((VCONFIGSP) <= LTDC_STOPPosition)
+
+#define IS_LTDC_DEFAULTCOLOR(DEFAULTCOLOR) ((DEFAULTCOLOR) <= LTDC_DefaultColorConfig)
+
+#define IS_LTDC_CFBP(CFBP) ((CFBP) <= LTDC_ColorFrameBuffer)
+#define IS_LTDC_CFBLL(CFBLL) ((CFBLL) <= LTDC_ColorFrameBuffer)
+
+#define IS_LTDC_CFBLNBR(CFBLNBR) ((CFBLNBR) <= LTDC_LineNumber)
+
+
+
+/**
+  * @}
+  */
+          
+/** @defgroup LTDC_colorkeying_Config
+  * @{
+  */
+
+#define LTDC_colorkeyingConfig            ((uint32_t)0x000000FF)
+
+#define IS_LTDC_CKEYING(CKEYING) ((CKEYING) <= LTDC_colorkeyingConfig)
+
+
+/**
+  * @}
+  */
+          
+/** @defgroup LTDC_CLUT_Config
+  * @{
+  */
+
+#define LTDC_CLUTWR                       ((uint32_t)0x000000FF)
+
+#define IS_LTDC_CLUTWR(CLUTWR)  ((CLUTWR) <= LTDC_CLUTWR)
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+/*  Function used to set the LTDC configuration to the default reset state *****/
+void LTDC_DeInit(void);
+
+/* Initialization and Configuration functions *********************************/
+void LTDC_Init(LTDC_InitTypeDef* LTDC_InitStruct);
+void LTDC_StructInit(LTDC_InitTypeDef* LTDC_InitStruct);
+void LTDC_Cmd(FunctionalState NewState);
+void LTDC_DitherCmd(FunctionalState NewState);
+LTDC_RGBTypeDef LTDC_GetRGBWidth(void);
+void LTDC_RGBStructInit(LTDC_RGBTypeDef* LTDC_RGB_InitStruct);
+void LTDC_LIPConfig(uint32_t LTDC_LIPositionConfig);
+void LTDC_ReloadConfig(uint32_t LTDC_Reload);
+void LTDC_LayerInit(LTDC_Layer_TypeDef* LTDC_Layerx, LTDC_Layer_InitTypeDef* LTDC_Layer_InitStruct);
+void LTDC_LayerStructInit(LTDC_Layer_InitTypeDef * LTDC_Layer_InitStruct);
+void LTDC_LayerCmd(LTDC_Layer_TypeDef* LTDC_Layerx, FunctionalState NewState);
+LTDC_PosTypeDef LTDC_GetPosStatus(void);
+void LTDC_PosStructInit(LTDC_PosTypeDef* LTDC_Pos_InitStruct);
+FlagStatus LTDC_GetCDStatus(uint32_t LTDC_CD);
+void LTDC_ColorKeyingConfig(LTDC_Layer_TypeDef* LTDC_Layerx, LTDC_ColorKeying_InitTypeDef* LTDC_colorkeying_InitStruct, FunctionalState NewState);
+void LTDC_ColorKeyingStructInit(LTDC_ColorKeying_InitTypeDef* LTDC_colorkeying_InitStruct);
+void LTDC_CLUTCmd(LTDC_Layer_TypeDef* LTDC_Layerx, FunctionalState NewState);
+void LTDC_CLUTInit(LTDC_Layer_TypeDef* LTDC_Layerx, LTDC_CLUT_InitTypeDef* LTDC_CLUT_InitStruct);
+void LTDC_CLUTStructInit(LTDC_CLUT_InitTypeDef* LTDC_CLUT_InitStruct);
+void LTDC_LayerPosition(LTDC_Layer_TypeDef* LTDC_Layerx, uint16_t OffsetX, uint16_t OffsetY);
+void LTDC_LayerAlpha(LTDC_Layer_TypeDef* LTDC_Layerx, uint8_t ConstantAlpha);
+void LTDC_LayerAddress(LTDC_Layer_TypeDef* LTDC_Layerx, uint32_t Address);
+void LTDC_LayerSize(LTDC_Layer_TypeDef* LTDC_Layerx, uint32_t Width, uint32_t Height);
+void LTDC_LayerPixelFormat(LTDC_Layer_TypeDef* LTDC_Layerx, uint32_t PixelFormat);
+
+/* Interrupts and flags management functions **********************************/
+void LTDC_ITConfig(uint32_t LTDC_IT, FunctionalState NewState);
+FlagStatus LTDC_GetFlagStatus(uint32_t LTDC_FLAG);
+void LTDC_ClearFlag(uint32_t LTDC_FLAG);
+ITStatus LTDC_GetITStatus(uint32_t LTDC_IT);
+void LTDC_ClearITPendingBit(uint32_t LTDC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_LTDC_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_misc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_misc.h
new file mode 100644
index 0000000000000000000000000000000000000000..2d08fdd63b042a38b65150cc0db4d15cbab68787
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_misc.h
@@ -0,0 +1,178 @@
+/**
+  ******************************************************************************
+  * @file    misc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the miscellaneous
+  *          firmware library functions (add-on to CMSIS functions).
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __MISC_H
+#define __MISC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup MISC
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  NVIC Init Structure definition  
+  */
+
+typedef struct
+{
+  uint8_t NVIC_IRQChannel;                    /*!< Specifies the IRQ channel to be enabled or disabled.
+                                                   This parameter can be an enumerator of @ref IRQn_Type 
+                                                   enumeration (For the complete STM32 Devices IRQ Channels
+                                                   list, please refer to stm32f4xx.h file) */
+
+  uint8_t NVIC_IRQChannelPreemptionPriority;  /*!< Specifies the pre-emption priority for the IRQ channel
+                                                   specified in NVIC_IRQChannel. This parameter can be a value
+                                                   between 0 and 15 as described in the table @ref MISC_NVIC_Priority_Table
+                                                   A lower priority value indicates a higher priority */
+
+  uint8_t NVIC_IRQChannelSubPriority;         /*!< Specifies the subpriority level for the IRQ channel specified
+                                                   in NVIC_IRQChannel. This parameter can be a value
+                                                   between 0 and 15 as described in the table @ref MISC_NVIC_Priority_Table
+                                                   A lower priority value indicates a higher priority */
+
+  FunctionalState NVIC_IRQChannelCmd;         /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel
+                                                   will be enabled or disabled. 
+                                                   This parameter can be set either to ENABLE or DISABLE */   
+} NVIC_InitTypeDef;
+ 
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup MISC_Exported_Constants
+  * @{
+  */
+
+/** @defgroup MISC_Vector_Table_Base 
+  * @{
+  */
+
+#define NVIC_VectTab_RAM             ((uint32_t)0x20000000)
+#define NVIC_VectTab_FLASH           ((uint32_t)0x08000000)
+#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \
+                                  ((VECTTAB) == NVIC_VectTab_FLASH))
+/**
+  * @}
+  */
+
+/** @defgroup MISC_System_Low_Power 
+  * @{
+  */
+
+#define NVIC_LP_SEVONPEND            ((uint8_t)0x10)
+#define NVIC_LP_SLEEPDEEP            ((uint8_t)0x04)
+#define NVIC_LP_SLEEPONEXIT          ((uint8_t)0x02)
+#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \
+                        ((LP) == NVIC_LP_SLEEPDEEP) || \
+                        ((LP) == NVIC_LP_SLEEPONEXIT))
+/**
+  * @}
+  */
+
+/** @defgroup MISC_Preemption_Priority_Group 
+  * @{
+  */
+
+#define NVIC_PriorityGroup_0         ((uint32_t)0x700) /*!< 0 bits for pre-emption priority
+                                                            4 bits for subpriority */
+#define NVIC_PriorityGroup_1         ((uint32_t)0x600) /*!< 1 bits for pre-emption priority
+                                                            3 bits for subpriority */
+#define NVIC_PriorityGroup_2         ((uint32_t)0x500) /*!< 2 bits for pre-emption priority
+                                                            2 bits for subpriority */
+#define NVIC_PriorityGroup_3         ((uint32_t)0x400) /*!< 3 bits for pre-emption priority
+                                                            1 bits for subpriority */
+#define NVIC_PriorityGroup_4         ((uint32_t)0x300) /*!< 4 bits for pre-emption priority
+                                                            0 bits for subpriority */
+
+#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \
+                                       ((GROUP) == NVIC_PriorityGroup_1) || \
+                                       ((GROUP) == NVIC_PriorityGroup_2) || \
+                                       ((GROUP) == NVIC_PriorityGroup_3) || \
+                                       ((GROUP) == NVIC_PriorityGroup_4))
+
+#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY)  ((PRIORITY) < 0x10)
+
+#define IS_NVIC_SUB_PRIORITY(PRIORITY)  ((PRIORITY) < 0x10)
+
+#define IS_NVIC_OFFSET(OFFSET)  ((OFFSET) < 0x000FFFFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup MISC_SysTick_clock_source 
+  * @{
+  */
+
+#define SysTick_CLKSource_HCLK_Div8    ((uint32_t)0xFFFFFFFB)
+#define SysTick_CLKSource_HCLK         ((uint32_t)0x00000004)
+#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
+                                       ((SOURCE) == SysTick_CLKSource_HCLK_Div8))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+
+void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup);
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct);
+void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset);
+void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState);
+void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MISC_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h
new file mode 100644
index 0000000000000000000000000000000000000000..4ce588db6ddf50f33986f7d442ab558568db5a8d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_pwr.h
@@ -0,0 +1,210 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_pwr.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the PWR firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_PWR_H
+#define __STM32F4xx_PWR_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup PWR
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup PWR_Exported_Constants
+  * @{
+  */ 
+
+/** @defgroup PWR_PVD_detection_level 
+  * @{
+  */ 
+#define PWR_PVDLevel_0                  PWR_CR_PLS_LEV0
+#define PWR_PVDLevel_1                  PWR_CR_PLS_LEV1
+#define PWR_PVDLevel_2                  PWR_CR_PLS_LEV2
+#define PWR_PVDLevel_3                  PWR_CR_PLS_LEV3
+#define PWR_PVDLevel_4                  PWR_CR_PLS_LEV4
+#define PWR_PVDLevel_5                  PWR_CR_PLS_LEV5
+#define PWR_PVDLevel_6                  PWR_CR_PLS_LEV6
+#define PWR_PVDLevel_7                  PWR_CR_PLS_LEV7
+
+#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_0) || ((LEVEL) == PWR_PVDLevel_1)|| \
+                                 ((LEVEL) == PWR_PVDLevel_2) || ((LEVEL) == PWR_PVDLevel_3)|| \
+                                 ((LEVEL) == PWR_PVDLevel_4) || ((LEVEL) == PWR_PVDLevel_5)|| \
+                                 ((LEVEL) == PWR_PVDLevel_6) || ((LEVEL) == PWR_PVDLevel_7))
+/**
+  * @}
+  */
+
+  
+/** @defgroup PWR_Regulator_state_in_STOP_mode 
+  * @{
+  */
+#define PWR_MainRegulator_ON                        ((uint32_t)0x00000000)
+#define PWR_LowPowerRegulator_ON                    PWR_CR_LPDS
+
+/* --- PWR_Legacy ---*/
+#define PWR_Regulator_ON                            PWR_MainRegulator_ON
+#define PWR_Regulator_LowPower                      PWR_LowPowerRegulator_ON
+
+#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_MainRegulator_ON) || \
+                                     ((REGULATOR) == PWR_LowPowerRegulator_ON))
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Regulator_state_in_UnderDrive_mode 
+  * @{
+  */
+#define PWR_MainRegulator_UnderDrive_ON               PWR_CR_MRUDS
+#define PWR_LowPowerRegulator_UnderDrive_ON           ((uint32_t)(PWR_CR_LPDS | PWR_CR_LPUDS))
+
+#define IS_PWR_REGULATOR_UNDERDRIVE(REGULATOR) (((REGULATOR) == PWR_MainRegulator_UnderDrive_ON) || \
+                                                ((REGULATOR) == PWR_LowPowerRegulator_UnderDrive_ON))
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_STOP_mode_entry 
+  * @{
+  */
+#define PWR_STOPEntry_WFI               ((uint8_t)0x01)
+#define PWR_STOPEntry_WFE               ((uint8_t)0x02)
+#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE))
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Regulator_Voltage_Scale 
+  * @{
+  */
+#define PWR_Regulator_Voltage_Scale1    ((uint32_t)0x0000C000)
+#define PWR_Regulator_Voltage_Scale2    ((uint32_t)0x00008000)
+#define PWR_Regulator_Voltage_Scale3    ((uint32_t)0x00004000)
+#define IS_PWR_REGULATOR_VOLTAGE(VOLTAGE) (((VOLTAGE) == PWR_Regulator_Voltage_Scale1) || \
+                                           ((VOLTAGE) == PWR_Regulator_Voltage_Scale2) || \
+                                           ((VOLTAGE) == PWR_Regulator_Voltage_Scale3))
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Flag 
+  * @{
+  */
+#define PWR_FLAG_WU                     PWR_CSR_WUF
+#define PWR_FLAG_SB                     PWR_CSR_SBF
+#define PWR_FLAG_PVDO                   PWR_CSR_PVDO
+#define PWR_FLAG_BRR                    PWR_CSR_BRR
+#define PWR_FLAG_VOSRDY                 PWR_CSR_VOSRDY
+#define PWR_FLAG_ODRDY                  PWR_CSR_ODRDY
+#define PWR_FLAG_ODSWRDY                PWR_CSR_ODSWRDY
+#define PWR_FLAG_UDRDY                  PWR_CSR_UDSWRDY
+
+/* --- FLAG Legacy ---*/
+#define PWR_FLAG_REGRDY                  PWR_FLAG_VOSRDY               
+
+#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \
+                               ((FLAG) == PWR_FLAG_PVDO) || ((FLAG) == PWR_FLAG_BRR) || \
+                               ((FLAG) == PWR_FLAG_VOSRDY) || ((FLAG) == PWR_FLAG_ODRDY) || \
+                               ((FLAG) == PWR_FLAG_ODSWRDY) || ((FLAG) == PWR_FLAG_UDRDY))
+
+
+#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \
+                                 ((FLAG) == PWR_FLAG_UDRDY))
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/* Function used to set the PWR configuration to the default reset state ******/ 
+void PWR_DeInit(void);
+
+/* Backup Domain Access function **********************************************/ 
+void PWR_BackupAccessCmd(FunctionalState NewState);
+
+/* PVD configuration functions ************************************************/ 
+void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel);
+void PWR_PVDCmd(FunctionalState NewState);
+
+/* WakeUp pins configuration functions ****************************************/ 
+void PWR_WakeUpPinCmd(FunctionalState NewState);
+
+/* Main and Backup Regulators configuration functions *************************/ 
+void PWR_BackupRegulatorCmd(FunctionalState NewState);
+void PWR_MainRegulatorModeConfig(uint32_t PWR_Regulator_Voltage);
+void PWR_OverDriveCmd(FunctionalState NewState);
+void PWR_OverDriveSWCmd(FunctionalState NewState);
+void PWR_UnderDriveCmd(FunctionalState NewState);
+
+/* FLASH Power Down configuration functions ***********************************/ 
+void PWR_FlashPowerDownCmd(FunctionalState NewState);
+
+/* Low Power modes configuration functions ************************************/ 
+void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry);
+void PWR_EnterUnderDriveSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry);
+void PWR_EnterSTANDBYMode(void);
+
+/* Flags management functions *************************************************/ 
+FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG);
+void PWR_ClearFlag(uint32_t PWR_FLAG);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_PWR_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h
new file mode 100644
index 0000000000000000000000000000000000000000..6abb551602c62caffcb8a2c6c1af84e0e84a92f7
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rcc.h
@@ -0,0 +1,615 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_rcc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the RCC firmware library.  
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_RCC_H
+#define __STM32F4xx_RCC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup RCC
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+typedef struct
+{
+  uint32_t SYSCLK_Frequency; /*!<  SYSCLK clock frequency expressed in Hz */
+  uint32_t HCLK_Frequency;   /*!<  HCLK clock frequency expressed in Hz   */
+  uint32_t PCLK1_Frequency;  /*!<  PCLK1 clock frequency expressed in Hz  */
+  uint32_t PCLK2_Frequency;  /*!<  PCLK2 clock frequency expressed in Hz  */
+}RCC_ClocksTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup RCC_Exported_Constants
+  * @{
+  */
+  
+/** @defgroup RCC_HSE_configuration 
+  * @{
+  */
+#define RCC_HSE_OFF                      ((uint8_t)0x00)
+#define RCC_HSE_ON                       ((uint8_t)0x01)
+#define RCC_HSE_Bypass                   ((uint8_t)0x05)
+#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \
+                         ((HSE) == RCC_HSE_Bypass))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_PLL_Clock_Source 
+  * @{
+  */
+#define RCC_PLLSource_HSI                ((uint32_t)0x00000000)
+#define RCC_PLLSource_HSE                ((uint32_t)0x00400000)
+#define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI) || \
+                                   ((SOURCE) == RCC_PLLSource_HSE))
+#define IS_RCC_PLLM_VALUE(VALUE) ((VALUE) <= 63)
+#define IS_RCC_PLLN_VALUE(VALUE) ((192 <= (VALUE)) && ((VALUE) <= 432))
+#define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2) || ((VALUE) == 4) || ((VALUE) == 6) || ((VALUE) == 8))
+#define IS_RCC_PLLQ_VALUE(VALUE) ((4 <= (VALUE)) && ((VALUE) <= 15))
+ 
+#define IS_RCC_PLLI2SN_VALUE(VALUE) ((192 <= (VALUE)) && ((VALUE) <= 432))
+#define IS_RCC_PLLI2SR_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 7))  
+
+#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 15))
+#define IS_RCC_PLLSAIN_VALUE(VALUE) ((192 <= (VALUE)) && ((VALUE) <= 432))
+#define IS_RCC_PLLSAIQ_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 15))
+#define IS_RCC_PLLSAIR_VALUE(VALUE) ((2 <= (VALUE)) && ((VALUE) <= 7))  
+
+#define IS_RCC_PLLSAI_DIVQ_VALUE(VALUE) ((1 <= (VALUE)) && ((VALUE) <= 32))
+#define IS_RCC_PLLI2S_DIVQ_VALUE(VALUE) ((1 <= (VALUE)) && ((VALUE) <= 32))
+
+#define RCC_PLLSAIDivR_Div2                ((uint32_t)0x00000000)
+#define RCC_PLLSAIDivR_Div4                ((uint32_t)0x00010000)
+#define RCC_PLLSAIDivR_Div8                ((uint32_t)0x00020000)
+#define RCC_PLLSAIDivR_Div16               ((uint32_t)0x00030000)
+#define IS_RCC_PLLSAI_DIVR_VALUE(VALUE) (((VALUE) == RCC_PLLSAIDivR_Div2) ||\
+                                        ((VALUE) == RCC_PLLSAIDivR_Div4)  ||\
+                                        ((VALUE) == RCC_PLLSAIDivR_Div8)  ||\
+                                        ((VALUE) == RCC_PLLSAIDivR_Div16))
+ 
+/**                                                                     
+  * @}
+  */ 
+  
+/** @defgroup RCC_System_Clock_Source 
+  * @{
+  */
+#define RCC_SYSCLKSource_HSI             ((uint32_t)0x00000000)
+#define RCC_SYSCLKSource_HSE             ((uint32_t)0x00000001)
+#define RCC_SYSCLKSource_PLLCLK          ((uint32_t)0x00000002)
+#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \
+                                      ((SOURCE) == RCC_SYSCLKSource_HSE) || \
+                                      ((SOURCE) == RCC_SYSCLKSource_PLLCLK))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_AHB_Clock_Source
+  * @{
+  */
+#define RCC_SYSCLK_Div1                  ((uint32_t)0x00000000)
+#define RCC_SYSCLK_Div2                  ((uint32_t)0x00000080)
+#define RCC_SYSCLK_Div4                  ((uint32_t)0x00000090)
+#define RCC_SYSCLK_Div8                  ((uint32_t)0x000000A0)
+#define RCC_SYSCLK_Div16                 ((uint32_t)0x000000B0)
+#define RCC_SYSCLK_Div64                 ((uint32_t)0x000000C0)
+#define RCC_SYSCLK_Div128                ((uint32_t)0x000000D0)
+#define RCC_SYSCLK_Div256                ((uint32_t)0x000000E0)
+#define RCC_SYSCLK_Div512                ((uint32_t)0x000000F0)
+#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \
+                           ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \
+                           ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \
+                           ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \
+                           ((HCLK) == RCC_SYSCLK_Div512))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_APB1_APB2_Clock_Source
+  * @{
+  */
+#define RCC_HCLK_Div1                    ((uint32_t)0x00000000)
+#define RCC_HCLK_Div2                    ((uint32_t)0x00001000)
+#define RCC_HCLK_Div4                    ((uint32_t)0x00001400)
+#define RCC_HCLK_Div8                    ((uint32_t)0x00001800)
+#define RCC_HCLK_Div16                   ((uint32_t)0x00001C00)
+#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \
+                           ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \
+                           ((PCLK) == RCC_HCLK_Div16))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_Interrupt_Source 
+  * @{
+  */
+#define RCC_IT_LSIRDY                    ((uint8_t)0x01)
+#define RCC_IT_LSERDY                    ((uint8_t)0x02)
+#define RCC_IT_HSIRDY                    ((uint8_t)0x04)
+#define RCC_IT_HSERDY                    ((uint8_t)0x08)
+#define RCC_IT_PLLRDY                    ((uint8_t)0x10)
+#define RCC_IT_PLLI2SRDY                 ((uint8_t)0x20) 
+#define RCC_IT_PLLSAIRDY                 ((uint8_t)0x40)
+#define RCC_IT_CSS                       ((uint8_t)0x80)
+
+#define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00))
+#define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \
+                           ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \
+                           ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \
+                           ((IT) == RCC_IT_PLLSAIRDY) || ((IT) == RCC_IT_PLLI2SRDY))
+#define IS_RCC_CLEAR_IT(IT)((IT) != 0x00)
+
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_LSE_Configuration 
+  * @{
+  */
+#define RCC_LSE_OFF                      ((uint8_t)0x00)
+#define RCC_LSE_ON                       ((uint8_t)0x01)
+#define RCC_LSE_Bypass                   ((uint8_t)0x04)
+#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \
+                         ((LSE) == RCC_LSE_Bypass))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_RTC_Clock_Source
+  * @{
+  */
+#define RCC_RTCCLKSource_LSE             ((uint32_t)0x00000100)
+#define RCC_RTCCLKSource_LSI             ((uint32_t)0x00000200)
+#define RCC_RTCCLKSource_HSE_Div2        ((uint32_t)0x00020300)
+#define RCC_RTCCLKSource_HSE_Div3        ((uint32_t)0x00030300)
+#define RCC_RTCCLKSource_HSE_Div4        ((uint32_t)0x00040300)
+#define RCC_RTCCLKSource_HSE_Div5        ((uint32_t)0x00050300)
+#define RCC_RTCCLKSource_HSE_Div6        ((uint32_t)0x00060300)
+#define RCC_RTCCLKSource_HSE_Div7        ((uint32_t)0x00070300)
+#define RCC_RTCCLKSource_HSE_Div8        ((uint32_t)0x00080300)
+#define RCC_RTCCLKSource_HSE_Div9        ((uint32_t)0x00090300)
+#define RCC_RTCCLKSource_HSE_Div10       ((uint32_t)0x000A0300)
+#define RCC_RTCCLKSource_HSE_Div11       ((uint32_t)0x000B0300)
+#define RCC_RTCCLKSource_HSE_Div12       ((uint32_t)0x000C0300)
+#define RCC_RTCCLKSource_HSE_Div13       ((uint32_t)0x000D0300)
+#define RCC_RTCCLKSource_HSE_Div14       ((uint32_t)0x000E0300)
+#define RCC_RTCCLKSource_HSE_Div15       ((uint32_t)0x000F0300)
+#define RCC_RTCCLKSource_HSE_Div16       ((uint32_t)0x00100300)
+#define RCC_RTCCLKSource_HSE_Div17       ((uint32_t)0x00110300)
+#define RCC_RTCCLKSource_HSE_Div18       ((uint32_t)0x00120300)
+#define RCC_RTCCLKSource_HSE_Div19       ((uint32_t)0x00130300)
+#define RCC_RTCCLKSource_HSE_Div20       ((uint32_t)0x00140300)
+#define RCC_RTCCLKSource_HSE_Div21       ((uint32_t)0x00150300)
+#define RCC_RTCCLKSource_HSE_Div22       ((uint32_t)0x00160300)
+#define RCC_RTCCLKSource_HSE_Div23       ((uint32_t)0x00170300)
+#define RCC_RTCCLKSource_HSE_Div24       ((uint32_t)0x00180300)
+#define RCC_RTCCLKSource_HSE_Div25       ((uint32_t)0x00190300)
+#define RCC_RTCCLKSource_HSE_Div26       ((uint32_t)0x001A0300)
+#define RCC_RTCCLKSource_HSE_Div27       ((uint32_t)0x001B0300)
+#define RCC_RTCCLKSource_HSE_Div28       ((uint32_t)0x001C0300)
+#define RCC_RTCCLKSource_HSE_Div29       ((uint32_t)0x001D0300)
+#define RCC_RTCCLKSource_HSE_Div30       ((uint32_t)0x001E0300)
+#define RCC_RTCCLKSource_HSE_Div31       ((uint32_t)0x001F0300)
+#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_LSI) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div2) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div3) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div4) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div5) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div6) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div7) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div8) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div9) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div10) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div11) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div12) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div13) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div14) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div15) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div16) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div17) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div18) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div19) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div20) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div21) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div22) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div23) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div24) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div25) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div26) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div27) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div28) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div29) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div30) || \
+                                      ((SOURCE) == RCC_RTCCLKSource_HSE_Div31))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_I2S_Clock_Source
+  * @{
+  */
+#define RCC_I2S2CLKSource_PLLI2S             ((uint8_t)0x00)
+#define RCC_I2S2CLKSource_Ext                ((uint8_t)0x01)
+
+#define IS_RCC_I2SCLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_PLLI2S) || ((SOURCE) == RCC_I2S2CLKSource_Ext))                                
+/**
+  * @}
+  */ 
+
+/** @defgroup RCC_SAI_BlockA_Clock_Source
+  * @{
+  */
+#define RCC_SAIACLKSource_PLLSAI             ((uint32_t)0x00000000)
+#define RCC_SAIACLKSource_PLLI2S             ((uint32_t)0x00100000)
+#define RCC_SAIACLKSource_Ext                ((uint32_t)0x00200000)
+
+#define IS_RCC_SAIACLK_SOURCE(SOURCE) (((SOURCE) == RCC_SAIACLKSource_PLLI2S) ||\
+                                       ((SOURCE) == RCC_SAIACLKSource_PLLSAI) ||\
+                                       ((SOURCE) == RCC_SAIACLKSource_Ext))
+/**
+  * @}
+  */ 
+
+/** @defgroup RCC_SAI_BlockB_Clock_Source
+  * @{
+  */
+#define RCC_SAIBCLKSource_PLLSAI             ((uint32_t)0x00000000)
+#define RCC_SAIBCLKSource_PLLI2S             ((uint32_t)0x00400000)
+#define RCC_SAIBCLKSource_Ext                ((uint32_t)0x00800000)
+
+#define IS_RCC_SAIBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SAIBCLKSource_PLLI2S) ||\
+                                       ((SOURCE) == RCC_SAIBCLKSource_PLLSAI) ||\
+                                       ((SOURCE) == RCC_SAIBCLKSource_Ext))
+/**
+  * @}
+  */ 
+
+/** @defgroup RCC_TIM_PRescaler_Selection
+  * @{
+  */
+#define RCC_TIMPrescDesactivated             ((uint8_t)0x00)
+#define RCC_TIMPrescActivated                ((uint8_t)0x01)
+
+#define IS_RCC_TIMCLK_PRESCALER(VALUE) (((VALUE) == RCC_TIMPrescDesactivated) || ((VALUE) == RCC_TIMPrescActivated))
+/**
+  * @}
+  */
+  
+/** @defgroup RCC_AHB1_Peripherals 
+  * @{
+  */ 
+#define RCC_AHB1Periph_GPIOA             ((uint32_t)0x00000001)
+#define RCC_AHB1Periph_GPIOB             ((uint32_t)0x00000002)
+#define RCC_AHB1Periph_GPIOC             ((uint32_t)0x00000004)
+#define RCC_AHB1Periph_GPIOD             ((uint32_t)0x00000008)
+#define RCC_AHB1Periph_GPIOE             ((uint32_t)0x00000010)
+#define RCC_AHB1Periph_GPIOF             ((uint32_t)0x00000020)
+#define RCC_AHB1Periph_GPIOG             ((uint32_t)0x00000040)
+#define RCC_AHB1Periph_GPIOH             ((uint32_t)0x00000080)
+#define RCC_AHB1Periph_GPIOI             ((uint32_t)0x00000100) 
+#define RCC_AHB1Periph_GPIOJ             ((uint32_t)0x00000200)
+#define RCC_AHB1Periph_GPIOK             ((uint32_t)0x00000400)
+#define RCC_AHB1Periph_CRC               ((uint32_t)0x00001000)
+#define RCC_AHB1Periph_FLITF             ((uint32_t)0x00008000)
+#define RCC_AHB1Periph_SRAM1             ((uint32_t)0x00010000)
+#define RCC_AHB1Periph_SRAM2             ((uint32_t)0x00020000)
+#define RCC_AHB1Periph_BKPSRAM           ((uint32_t)0x00040000)
+#define RCC_AHB1Periph_SRAM3             ((uint32_t)0x00080000)
+#define RCC_AHB1Periph_CCMDATARAMEN      ((uint32_t)0x00100000)
+#define RCC_AHB1Periph_DMA1              ((uint32_t)0x00200000)
+#define RCC_AHB1Periph_DMA2              ((uint32_t)0x00400000)
+#define RCC_AHB1Periph_DMA2D             ((uint32_t)0x00800000)
+#define RCC_AHB1Periph_ETH_MAC           ((uint32_t)0x02000000)
+#define RCC_AHB1Periph_ETH_MAC_Tx        ((uint32_t)0x04000000)
+#define RCC_AHB1Periph_ETH_MAC_Rx        ((uint32_t)0x08000000)
+#define RCC_AHB1Periph_ETH_MAC_PTP       ((uint32_t)0x10000000)
+#define RCC_AHB1Periph_OTG_HS            ((uint32_t)0x20000000)
+#define RCC_AHB1Periph_OTG_HS_ULPI       ((uint32_t)0x40000000)
+
+#define IS_RCC_AHB1_CLOCK_PERIPH(PERIPH) ((((PERIPH) & 0x810BE800) == 0x00) && ((PERIPH) != 0x00))
+#define IS_RCC_AHB1_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xDD1FE800) == 0x00) && ((PERIPH) != 0x00))
+#define IS_RCC_AHB1_LPMODE_PERIPH(PERIPH) ((((PERIPH) & 0x81106800) == 0x00) && ((PERIPH) != 0x00))
+
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_AHB2_Peripherals 
+  * @{
+  */  
+#define RCC_AHB2Periph_DCMI              ((uint32_t)0x00000001)
+#define RCC_AHB2Periph_CRYP              ((uint32_t)0x00000010)
+#define RCC_AHB2Periph_HASH              ((uint32_t)0x00000020)
+#define RCC_AHB2Periph_RNG               ((uint32_t)0x00000040)
+#define RCC_AHB2Periph_OTG_FS            ((uint32_t)0x00000080)
+#define IS_RCC_AHB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFF0E) == 0x00) && ((PERIPH) != 0x00))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_AHB3_Peripherals 
+  * @{
+  */ 
+#if defined (STM32F40_41xxx)
+#define RCC_AHB3Periph_FSMC                ((uint32_t)0x00000001)
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx) 
+#define RCC_AHB3Periph_FMC                ((uint32_t)0x00000001)
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#define IS_RCC_AHB3_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFFFE) == 0x00) && ((PERIPH) != 0x00))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_APB1_Peripherals 
+  * @{
+  */ 
+#define RCC_APB1Periph_TIM2              ((uint32_t)0x00000001)
+#define RCC_APB1Periph_TIM3              ((uint32_t)0x00000002)
+#define RCC_APB1Periph_TIM4              ((uint32_t)0x00000004)
+#define RCC_APB1Periph_TIM5              ((uint32_t)0x00000008)
+#define RCC_APB1Periph_TIM6              ((uint32_t)0x00000010)
+#define RCC_APB1Periph_TIM7              ((uint32_t)0x00000020)
+#define RCC_APB1Periph_TIM12             ((uint32_t)0x00000040)
+#define RCC_APB1Periph_TIM13             ((uint32_t)0x00000080)
+#define RCC_APB1Periph_TIM14             ((uint32_t)0x00000100)
+#define RCC_APB1Periph_WWDG              ((uint32_t)0x00000800)
+#define RCC_APB1Periph_SPI2              ((uint32_t)0x00004000)
+#define RCC_APB1Periph_SPI3              ((uint32_t)0x00008000)
+#define RCC_APB1Periph_USART2            ((uint32_t)0x00020000)
+#define RCC_APB1Periph_USART3            ((uint32_t)0x00040000)
+#define RCC_APB1Periph_UART4             ((uint32_t)0x00080000)
+#define RCC_APB1Periph_UART5             ((uint32_t)0x00100000)
+#define RCC_APB1Periph_I2C1              ((uint32_t)0x00200000)
+#define RCC_APB1Periph_I2C2              ((uint32_t)0x00400000)
+#define RCC_APB1Periph_I2C3              ((uint32_t)0x00800000)
+#define RCC_APB1Periph_CAN1              ((uint32_t)0x02000000)
+#define RCC_APB1Periph_CAN2              ((uint32_t)0x04000000)
+#define RCC_APB1Periph_PWR               ((uint32_t)0x10000000)
+#define RCC_APB1Periph_DAC               ((uint32_t)0x20000000)
+#define RCC_APB1Periph_UART7             ((uint32_t)0x40000000)
+#define RCC_APB1Periph_UART8             ((uint32_t)0x80000000)
+#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x09013600) == 0x00) && ((PERIPH) != 0x00))
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_APB2_Peripherals 
+  * @{
+  */ 
+#define RCC_APB2Periph_TIM1              ((uint32_t)0x00000001)
+#define RCC_APB2Periph_TIM8              ((uint32_t)0x00000002)
+#define RCC_APB2Periph_USART1            ((uint32_t)0x00000010)
+#define RCC_APB2Periph_USART6            ((uint32_t)0x00000020)
+#define RCC_APB2Periph_ADC               ((uint32_t)0x00000100)
+#define RCC_APB2Periph_ADC1              ((uint32_t)0x00000100)
+#define RCC_APB2Periph_ADC2              ((uint32_t)0x00000200)
+#define RCC_APB2Periph_ADC3              ((uint32_t)0x00000400)
+#define RCC_APB2Periph_SDIO              ((uint32_t)0x00000800)
+#define RCC_APB2Periph_SPI1              ((uint32_t)0x00001000)
+#define RCC_APB2Periph_SPI4              ((uint32_t)0x00002000)
+#define RCC_APB2Periph_SYSCFG            ((uint32_t)0x00004000)
+#define RCC_APB2Periph_TIM9              ((uint32_t)0x00010000)
+#define RCC_APB2Periph_TIM10             ((uint32_t)0x00020000)
+#define RCC_APB2Periph_TIM11             ((uint32_t)0x00040000)
+#define RCC_APB2Periph_SPI5              ((uint32_t)0x00100000)
+#define RCC_APB2Periph_SPI6              ((uint32_t)0x00200000)
+#define RCC_APB2Periph_SAI1              ((uint32_t)0x00400000)
+#define RCC_APB2Periph_LTDC              ((uint32_t)0x04000000)
+
+#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFB8880CC) == 0x00) && ((PERIPH) != 0x00))
+#define IS_RCC_APB2_RESET_PERIPH(PERIPH) ((((PERIPH) & 0xFB8886CC) == 0x00) && ((PERIPH) != 0x00))
+
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_MCO1_Clock_Source_Prescaler
+  * @{
+  */
+#define RCC_MCO1Source_HSI               ((uint32_t)0x00000000)
+#define RCC_MCO1Source_LSE               ((uint32_t)0x00200000)
+#define RCC_MCO1Source_HSE               ((uint32_t)0x00400000)
+#define RCC_MCO1Source_PLLCLK            ((uint32_t)0x00600000)
+#define RCC_MCO1Div_1                    ((uint32_t)0x00000000)
+#define RCC_MCO1Div_2                    ((uint32_t)0x04000000)
+#define RCC_MCO1Div_3                    ((uint32_t)0x05000000)
+#define RCC_MCO1Div_4                    ((uint32_t)0x06000000)
+#define RCC_MCO1Div_5                    ((uint32_t)0x07000000)
+#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1Source_HSI) || ((SOURCE) == RCC_MCO1Source_LSE) || \
+                                   ((SOURCE) == RCC_MCO1Source_HSE) || ((SOURCE) == RCC_MCO1Source_PLLCLK))
+                                   
+#define IS_RCC_MCO1DIV(DIV) (((DIV) == RCC_MCO1Div_1) || ((DIV) == RCC_MCO1Div_2) || \
+                             ((DIV) == RCC_MCO1Div_3) || ((DIV) == RCC_MCO1Div_4) || \
+                             ((DIV) == RCC_MCO1Div_5)) 
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_MCO2_Clock_Source_Prescaler
+  * @{
+  */
+#define RCC_MCO2Source_SYSCLK            ((uint32_t)0x00000000)
+#define RCC_MCO2Source_PLLI2SCLK         ((uint32_t)0x40000000)
+#define RCC_MCO2Source_HSE               ((uint32_t)0x80000000)
+#define RCC_MCO2Source_PLLCLK            ((uint32_t)0xC0000000)
+#define RCC_MCO2Div_1                    ((uint32_t)0x00000000)
+#define RCC_MCO2Div_2                    ((uint32_t)0x20000000)
+#define RCC_MCO2Div_3                    ((uint32_t)0x28000000)
+#define RCC_MCO2Div_4                    ((uint32_t)0x30000000)
+#define RCC_MCO2Div_5                    ((uint32_t)0x38000000)
+#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2Source_SYSCLK) || ((SOURCE) == RCC_MCO2Source_PLLI2SCLK)|| \
+                                   ((SOURCE) == RCC_MCO2Source_HSE) || ((SOURCE) == RCC_MCO2Source_PLLCLK))
+                                   
+#define IS_RCC_MCO2DIV(DIV) (((DIV) == RCC_MCO2Div_1) || ((DIV) == RCC_MCO2Div_2) || \
+                             ((DIV) == RCC_MCO2Div_3) || ((DIV) == RCC_MCO2Div_4) || \
+                             ((DIV) == RCC_MCO2Div_5))                             
+/**
+  * @}
+  */ 
+  
+/** @defgroup RCC_Flag 
+  * @{
+  */
+#define RCC_FLAG_HSIRDY                  ((uint8_t)0x21)
+#define RCC_FLAG_HSERDY                  ((uint8_t)0x31)
+#define RCC_FLAG_PLLRDY                  ((uint8_t)0x39)
+#define RCC_FLAG_PLLI2SRDY               ((uint8_t)0x3B)
+#define RCC_FLAG_PLLSAIRDY               ((uint8_t)0x3D)
+#define RCC_FLAG_LSERDY                  ((uint8_t)0x41)
+#define RCC_FLAG_LSIRDY                  ((uint8_t)0x61)
+#define RCC_FLAG_BORRST                  ((uint8_t)0x79)
+#define RCC_FLAG_PINRST                  ((uint8_t)0x7A)
+#define RCC_FLAG_PORRST                  ((uint8_t)0x7B)
+#define RCC_FLAG_SFTRST                  ((uint8_t)0x7C)
+#define RCC_FLAG_IWDGRST                 ((uint8_t)0x7D)
+#define RCC_FLAG_WWDGRST                 ((uint8_t)0x7E)
+#define RCC_FLAG_LPWRRST                 ((uint8_t)0x7F)
+
+#define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY)   || ((FLAG) == RCC_FLAG_HSERDY) || \
+                           ((FLAG) == RCC_FLAG_PLLRDY)   || ((FLAG) == RCC_FLAG_LSERDY) || \
+                           ((FLAG) == RCC_FLAG_LSIRDY)   || ((FLAG) == RCC_FLAG_BORRST) || \
+                           ((FLAG) == RCC_FLAG_PINRST)   || ((FLAG) == RCC_FLAG_PORRST) || \
+                           ((FLAG) == RCC_FLAG_SFTRST)   || ((FLAG) == RCC_FLAG_IWDGRST)|| \
+                           ((FLAG) == RCC_FLAG_WWDGRST)  || ((FLAG) == RCC_FLAG_LPWRRST)|| \
+                           ((FLAG) == RCC_FLAG_PLLI2SRDY)|| ((FLAG) == RCC_FLAG_PLLSAIRDY))
+
+#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F)
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/* Function used to set the RCC clock configuration to the default reset state */
+void RCC_DeInit(void);
+
+/* Internal/external clocks, PLL, CSS and MCO configuration functions *********/
+void        RCC_HSEConfig(uint8_t RCC_HSE);
+ErrorStatus RCC_WaitForHSEStartUp(void);
+void        RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue);
+void        RCC_HSICmd(FunctionalState NewState);
+void        RCC_LSEConfig(uint8_t RCC_LSE);
+void        RCC_LSICmd(FunctionalState NewState);
+void        RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ);
+void        RCC_PLLCmd(FunctionalState NewState);
+
+#if defined (STM32F40_41xxx) || defined (STM32F401xx)
+void        RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR);
+#endif /* STM32F40_41xxx || STM32F401xx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+void        RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SQ, uint32_t PLLI2SR);
+#endif /* STM32F41_43xxx */
+
+void        RCC_PLLI2SCmd(FunctionalState NewState);
+void        RCC_PLLSAIConfig(uint32_t PLLSAIN, uint32_t PLLSAIQ, uint32_t PLLSAIR);
+void        RCC_PLLSAICmd(FunctionalState NewState);
+void        RCC_ClockSecuritySystemCmd(FunctionalState NewState);
+void        RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div);
+void        RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div);
+
+/* System, AHB and APB busses clocks configuration functions ******************/
+void        RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource);
+uint8_t     RCC_GetSYSCLKSource(void);
+void        RCC_HCLKConfig(uint32_t RCC_SYSCLK);
+void        RCC_PCLK1Config(uint32_t RCC_HCLK);
+void        RCC_PCLK2Config(uint32_t RCC_HCLK);
+void        RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks);
+
+/* Peripheral clocks configuration functions **********************************/
+void        RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource);
+void        RCC_RTCCLKCmd(FunctionalState NewState);
+void        RCC_BackupResetCmd(FunctionalState NewState);
+void        RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource); 
+void        RCC_SAIPLLI2SClkDivConfig(uint32_t RCC_PLLI2SDivQ);
+void        RCC_SAIPLLSAIClkDivConfig(uint32_t RCC_PLLSAIDivQ);
+void        RCC_SAIBlockACLKConfig(uint32_t RCC_SAIBlockACLKSource);
+void        RCC_SAIBlockBCLKConfig(uint32_t RCC_SAIBlockBCLKSource);
+void        RCC_LTDCCLKDivConfig(uint32_t RCC_PLLSAIDivR);
+void        RCC_TIMCLKPresConfig(uint32_t RCC_TIMCLKPrescaler);
+
+void        RCC_AHB1PeriphClockCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState);
+void        RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState);
+void        RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState);
+void        RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
+void        RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
+
+void        RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState);
+void        RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState);
+void        RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState);
+void        RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
+void        RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
+
+void        RCC_AHB1PeriphClockLPModeCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState);
+void        RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState);
+void        RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState);
+void        RCC_APB1PeriphClockLPModeCmd(uint32_t RCC_APB1Periph, FunctionalState NewState);
+void        RCC_APB2PeriphClockLPModeCmd(uint32_t RCC_APB2Periph, FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void        RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState);
+FlagStatus  RCC_GetFlagStatus(uint8_t RCC_FLAG);
+void        RCC_ClearFlag(void);
+ITStatus    RCC_GetITStatus(uint8_t RCC_IT);
+void        RCC_ClearITPendingBit(uint8_t RCC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_RCC_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h
new file mode 100644
index 0000000000000000000000000000000000000000..874c9bab554c3c083e4b47644cc6967ee21b13a9
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rng.h
@@ -0,0 +1,120 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_rng.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the Random 
+  *          Number Generator(RNG) firmware library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_RNG_H
+#define __STM32F4xx_RNG_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup RNG
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/ 
+
+/** @defgroup RNG_Exported_Constants
+  * @{
+  */
+  
+/** @defgroup RNG_flags_definition  
+  * @{
+  */ 
+#define RNG_FLAG_DRDY               ((uint8_t)0x0001) /*!< Data ready */
+#define RNG_FLAG_CECS               ((uint8_t)0x0002) /*!< Clock error current status */
+#define RNG_FLAG_SECS               ((uint8_t)0x0004) /*!< Seed error current status */
+
+#define IS_RNG_GET_FLAG(RNG_FLAG) (((RNG_FLAG) == RNG_FLAG_DRDY) || \
+                                   ((RNG_FLAG) == RNG_FLAG_CECS) || \
+                                   ((RNG_FLAG) == RNG_FLAG_SECS))
+#define IS_RNG_CLEAR_FLAG(RNG_FLAG) (((RNG_FLAG) == RNG_FLAG_CECS) || \
+                                    ((RNG_FLAG) == RNG_FLAG_SECS))
+/**
+  * @}
+  */ 
+
+/** @defgroup RNG_interrupts_definition   
+  * @{
+  */  
+#define RNG_IT_CEI                  ((uint8_t)0x20) /*!< Clock error interrupt */
+#define RNG_IT_SEI                  ((uint8_t)0x40) /*!< Seed error interrupt */
+
+#define IS_RNG_IT(IT) ((((IT) & (uint8_t)0x9F) == 0x00) && ((IT) != 0x00))
+#define IS_RNG_GET_IT(RNG_IT) (((RNG_IT) == RNG_IT_CEI) || ((RNG_IT) == RNG_IT_SEI))
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the RNG configuration to the default reset state *****/ 
+void RNG_DeInit(void);
+
+/* Configuration function *****************************************************/
+void RNG_Cmd(FunctionalState NewState);
+
+/* Get 32 bit Random number function ******************************************/
+uint32_t RNG_GetRandomNumber(void);
+
+/* Interrupts and flags management functions **********************************/
+void RNG_ITConfig(FunctionalState NewState);
+FlagStatus RNG_GetFlagStatus(uint8_t RNG_FLAG);
+void RNG_ClearFlag(uint8_t RNG_FLAG);
+ITStatus RNG_GetITStatus(uint8_t RNG_IT);
+void RNG_ClearITPendingBit(uint8_t RNG_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_RNG_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h
new file mode 100644
index 0000000000000000000000000000000000000000..a46227e531f2e184384d94c88e39e9c1ad0877f9
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_rtc.h
@@ -0,0 +1,881 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_rtc.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the RTC firmware
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ****************************************************************************** 
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_RTC_H
+#define __STM32F4xx_RTC_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup RTC
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  RTC Init structures definition  
+  */ 
+typedef struct
+{
+  uint32_t RTC_HourFormat;   /*!< Specifies the RTC Hour Format.
+                             This parameter can be a value of @ref RTC_Hour_Formats */
+  
+  uint32_t RTC_AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value.
+                             This parameter must be set to a value lower than 0x7F */
+  
+  uint32_t RTC_SynchPrediv;  /*!< Specifies the RTC Synchronous Predivider value.
+                             This parameter must be set to a value lower than 0x7FFF */
+}RTC_InitTypeDef;
+
+/** 
+  * @brief  RTC Time structure definition  
+  */
+typedef struct
+{
+  uint8_t RTC_Hours;    /*!< Specifies the RTC Time Hour.
+                        This parameter must be set to a value in the 0-12 range
+                        if the RTC_HourFormat_12 is selected or 0-23 range if
+                        the RTC_HourFormat_24 is selected. */
+
+  uint8_t RTC_Minutes;  /*!< Specifies the RTC Time Minutes.
+                        This parameter must be set to a value in the 0-59 range. */
+  
+  uint8_t RTC_Seconds;  /*!< Specifies the RTC Time Seconds.
+                        This parameter must be set to a value in the 0-59 range. */
+
+  uint8_t RTC_H12;      /*!< Specifies the RTC AM/PM Time.
+                        This parameter can be a value of @ref RTC_AM_PM_Definitions */
+}RTC_TimeTypeDef; 
+
+/** 
+  * @brief  RTC Date structure definition  
+  */
+typedef struct
+{
+  uint8_t RTC_WeekDay; /*!< Specifies the RTC Date WeekDay.
+                        This parameter can be a value of @ref RTC_WeekDay_Definitions */
+  
+  uint8_t RTC_Month;   /*!< Specifies the RTC Date Month (in BCD format).
+                        This parameter can be a value of @ref RTC_Month_Date_Definitions */
+
+  uint8_t RTC_Date;     /*!< Specifies the RTC Date.
+                        This parameter must be set to a value in the 1-31 range. */
+  
+  uint8_t RTC_Year;     /*!< Specifies the RTC Date Year.
+                        This parameter must be set to a value in the 0-99 range. */
+}RTC_DateTypeDef;
+
+/** 
+  * @brief  RTC Alarm structure definition  
+  */
+typedef struct
+{
+  RTC_TimeTypeDef RTC_AlarmTime;     /*!< Specifies the RTC Alarm Time members. */
+
+  uint32_t RTC_AlarmMask;            /*!< Specifies the RTC Alarm Masks.
+                                     This parameter can be a value of @ref RTC_AlarmMask_Definitions */
+
+  uint32_t RTC_AlarmDateWeekDaySel;  /*!< Specifies the RTC Alarm is on Date or WeekDay.
+                                     This parameter can be a value of @ref RTC_AlarmDateWeekDay_Definitions */
+  
+  uint8_t RTC_AlarmDateWeekDay;      /*!< Specifies the RTC Alarm Date/WeekDay.
+                                     If the Alarm Date is selected, this parameter
+                                     must be set to a value in the 1-31 range.
+                                     If the Alarm WeekDay is selected, this 
+                                     parameter can be a value of @ref RTC_WeekDay_Definitions */
+}RTC_AlarmTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup RTC_Exported_Constants
+  * @{
+  */ 
+
+
+/** @defgroup RTC_Hour_Formats 
+  * @{
+  */ 
+#define RTC_HourFormat_24              ((uint32_t)0x00000000)
+#define RTC_HourFormat_12              ((uint32_t)0x00000040)
+#define IS_RTC_HOUR_FORMAT(FORMAT)     (((FORMAT) == RTC_HourFormat_12) || \
+                                        ((FORMAT) == RTC_HourFormat_24))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Asynchronous_Predivider 
+  * @{
+  */ 
+#define IS_RTC_ASYNCH_PREDIV(PREDIV)   ((PREDIV) <= 0x7F)
+ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup RTC_Synchronous_Predivider 
+  * @{
+  */ 
+#define IS_RTC_SYNCH_PREDIV(PREDIV)    ((PREDIV) <= 0x7FFF)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Time_Definitions 
+  * @{
+  */ 
+#define IS_RTC_HOUR12(HOUR)            (((HOUR) > 0) && ((HOUR) <= 12))
+#define IS_RTC_HOUR24(HOUR)            ((HOUR) <= 23)
+#define IS_RTC_MINUTES(MINUTES)        ((MINUTES) <= 59)
+#define IS_RTC_SECONDS(SECONDS)        ((SECONDS) <= 59)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_AM_PM_Definitions 
+  * @{
+  */ 
+#define RTC_H12_AM                     ((uint8_t)0x00)
+#define RTC_H12_PM                     ((uint8_t)0x40)
+#define IS_RTC_H12(PM) (((PM) == RTC_H12_AM) || ((PM) == RTC_H12_PM))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Year_Date_Definitions 
+  * @{
+  */ 
+#define IS_RTC_YEAR(YEAR)              ((YEAR) <= 99)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Month_Date_Definitions 
+  * @{
+  */ 
+
+/* Coded in BCD format */
+#define RTC_Month_January              ((uint8_t)0x01)
+#define RTC_Month_February             ((uint8_t)0x02)
+#define RTC_Month_March                ((uint8_t)0x03)
+#define RTC_Month_April                ((uint8_t)0x04)
+#define RTC_Month_May                  ((uint8_t)0x05)
+#define RTC_Month_June                 ((uint8_t)0x06)
+#define RTC_Month_July                 ((uint8_t)0x07)
+#define RTC_Month_August               ((uint8_t)0x08)
+#define RTC_Month_September            ((uint8_t)0x09)
+#define RTC_Month_October              ((uint8_t)0x10)
+#define RTC_Month_November             ((uint8_t)0x11)
+#define RTC_Month_December             ((uint8_t)0x12)
+#define IS_RTC_MONTH(MONTH)            (((MONTH) >= 1) && ((MONTH) <= 12))
+#define IS_RTC_DATE(DATE)              (((DATE) >= 1) && ((DATE) <= 31))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_WeekDay_Definitions 
+  * @{
+  */ 
+  
+#define RTC_Weekday_Monday             ((uint8_t)0x01)
+#define RTC_Weekday_Tuesday            ((uint8_t)0x02)
+#define RTC_Weekday_Wednesday          ((uint8_t)0x03)
+#define RTC_Weekday_Thursday           ((uint8_t)0x04)
+#define RTC_Weekday_Friday             ((uint8_t)0x05)
+#define RTC_Weekday_Saturday           ((uint8_t)0x06)
+#define RTC_Weekday_Sunday             ((uint8_t)0x07)
+#define IS_RTC_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_Weekday_Monday) || \
+                                 ((WEEKDAY) == RTC_Weekday_Tuesday) || \
+                                 ((WEEKDAY) == RTC_Weekday_Wednesday) || \
+                                 ((WEEKDAY) == RTC_Weekday_Thursday) || \
+                                 ((WEEKDAY) == RTC_Weekday_Friday) || \
+                                 ((WEEKDAY) == RTC_Weekday_Saturday) || \
+                                 ((WEEKDAY) == RTC_Weekday_Sunday))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup RTC_Alarm_Definitions
+  * @{
+  */ 
+#define IS_RTC_ALARM_DATE_WEEKDAY_DATE(DATE) (((DATE) > 0) && ((DATE) <= 31))
+#define IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_Weekday_Monday) || \
+                                                    ((WEEKDAY) == RTC_Weekday_Tuesday) || \
+                                                    ((WEEKDAY) == RTC_Weekday_Wednesday) || \
+                                                    ((WEEKDAY) == RTC_Weekday_Thursday) || \
+                                                    ((WEEKDAY) == RTC_Weekday_Friday) || \
+                                                    ((WEEKDAY) == RTC_Weekday_Saturday) || \
+                                                    ((WEEKDAY) == RTC_Weekday_Sunday))
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup RTC_AlarmDateWeekDay_Definitions 
+  * @{
+  */ 
+#define RTC_AlarmDateWeekDaySel_Date      ((uint32_t)0x00000000)
+#define RTC_AlarmDateWeekDaySel_WeekDay   ((uint32_t)0x40000000)
+
+#define IS_RTC_ALARM_DATE_WEEKDAY_SEL(SEL) (((SEL) == RTC_AlarmDateWeekDaySel_Date) || \
+                                            ((SEL) == RTC_AlarmDateWeekDaySel_WeekDay))
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup RTC_AlarmMask_Definitions 
+  * @{
+  */ 
+#define RTC_AlarmMask_None                ((uint32_t)0x00000000)
+#define RTC_AlarmMask_DateWeekDay         ((uint32_t)0x80000000)
+#define RTC_AlarmMask_Hours               ((uint32_t)0x00800000)
+#define RTC_AlarmMask_Minutes             ((uint32_t)0x00008000)
+#define RTC_AlarmMask_Seconds             ((uint32_t)0x00000080)
+#define RTC_AlarmMask_All                 ((uint32_t)0x80808080)
+#define IS_ALARM_MASK(MASK)  (((MASK) & 0x7F7F7F7F) == (uint32_t)RESET)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Alarms_Definitions 
+  * @{
+  */ 
+#define RTC_Alarm_A                       ((uint32_t)0x00000100)
+#define RTC_Alarm_B                       ((uint32_t)0x00000200)
+#define IS_RTC_ALARM(ALARM)     (((ALARM) == RTC_Alarm_A) || ((ALARM) == RTC_Alarm_B))
+#define IS_RTC_CMD_ALARM(ALARM) (((ALARM) & (RTC_Alarm_A | RTC_Alarm_B)) != (uint32_t)RESET)
+
+/**
+  * @}
+  */ 
+
+  /** @defgroup RTC_Alarm_Sub_Seconds_Masks_Definitions
+  * @{
+  */ 
+#define RTC_AlarmSubSecondMask_All         ((uint32_t)0x00000000) /*!< All Alarm SS fields are masked. 
+                                                                       There is no comparison on sub seconds 
+                                                                       for Alarm */
+#define RTC_AlarmSubSecondMask_SS14_1      ((uint32_t)0x01000000) /*!< SS[14:1] are don't care in Alarm 
+                                                                       comparison. Only SS[0] is compared. */
+#define RTC_AlarmSubSecondMask_SS14_2      ((uint32_t)0x02000000) /*!< SS[14:2] are don't care in Alarm 
+                                                                       comparison. Only SS[1:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_3      ((uint32_t)0x03000000) /*!< SS[14:3] are don't care in Alarm 
+                                                                       comparison. Only SS[2:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_4      ((uint32_t)0x04000000) /*!< SS[14:4] are don't care in Alarm 
+                                                                       comparison. Only SS[3:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_5      ((uint32_t)0x05000000) /*!< SS[14:5] are don't care in Alarm 
+                                                                       comparison. Only SS[4:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_6      ((uint32_t)0x06000000) /*!< SS[14:6] are don't care in Alarm 
+                                                                       comparison. Only SS[5:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_7      ((uint32_t)0x07000000) /*!< SS[14:7] are don't care in Alarm 
+                                                                       comparison. Only SS[6:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_8      ((uint32_t)0x08000000) /*!< SS[14:8] are don't care in Alarm 
+                                                                       comparison. Only SS[7:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_9      ((uint32_t)0x09000000) /*!< SS[14:9] are don't care in Alarm 
+                                                                       comparison. Only SS[8:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_10     ((uint32_t)0x0A000000) /*!< SS[14:10] are don't care in Alarm 
+                                                                       comparison. Only SS[9:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_11     ((uint32_t)0x0B000000) /*!< SS[14:11] are don't care in Alarm 
+                                                                       comparison. Only SS[10:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_12     ((uint32_t)0x0C000000) /*!< SS[14:12] are don't care in Alarm 
+                                                                       comparison.Only SS[11:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14_13     ((uint32_t)0x0D000000) /*!< SS[14:13] are don't care in Alarm 
+                                                                       comparison. Only SS[12:0] are compared */
+#define RTC_AlarmSubSecondMask_SS14        ((uint32_t)0x0E000000) /*!< SS[14] is don't care in Alarm 
+                                                                       comparison.Only SS[13:0] are compared */
+#define RTC_AlarmSubSecondMask_None        ((uint32_t)0x0F000000) /*!< SS[14:0] are compared and must match 
+                                                                       to activate alarm. */
+#define IS_RTC_ALARM_SUB_SECOND_MASK(MASK)   (((MASK) == RTC_AlarmSubSecondMask_All) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_1) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_2) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_3) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_4) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_5) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_6) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_7) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_8) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_9) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_10) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_11) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_12) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14_13) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_SS14) || \
+                                              ((MASK) == RTC_AlarmSubSecondMask_None))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Alarm_Sub_Seconds_Value
+  * @{
+  */ 
+
+#define IS_RTC_ALARM_SUB_SECOND_VALUE(VALUE) ((VALUE) <= 0x00007FFF)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Wakeup_Timer_Definitions 
+  * @{
+  */ 
+#define RTC_WakeUpClock_RTCCLK_Div16        ((uint32_t)0x00000000)
+#define RTC_WakeUpClock_RTCCLK_Div8         ((uint32_t)0x00000001)
+#define RTC_WakeUpClock_RTCCLK_Div4         ((uint32_t)0x00000002)
+#define RTC_WakeUpClock_RTCCLK_Div2         ((uint32_t)0x00000003)
+#define RTC_WakeUpClock_CK_SPRE_16bits      ((uint32_t)0x00000004)
+#define RTC_WakeUpClock_CK_SPRE_17bits      ((uint32_t)0x00000006)
+#define IS_RTC_WAKEUP_CLOCK(CLOCK) (((CLOCK) == RTC_WakeUpClock_RTCCLK_Div16) || \
+                                    ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div8) || \
+                                    ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div4) || \
+                                    ((CLOCK) == RTC_WakeUpClock_RTCCLK_Div2) || \
+                                    ((CLOCK) == RTC_WakeUpClock_CK_SPRE_16bits) || \
+                                    ((CLOCK) == RTC_WakeUpClock_CK_SPRE_17bits))
+#define IS_RTC_WAKEUP_COUNTER(COUNTER)  ((COUNTER) <= 0xFFFF)
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Time_Stamp_Edges_definitions 
+  * @{
+  */ 
+#define RTC_TimeStampEdge_Rising          ((uint32_t)0x00000000)
+#define RTC_TimeStampEdge_Falling         ((uint32_t)0x00000008)
+#define IS_RTC_TIMESTAMP_EDGE(EDGE) (((EDGE) == RTC_TimeStampEdge_Rising) || \
+                                     ((EDGE) == RTC_TimeStampEdge_Falling))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Output_selection_Definitions 
+  * @{
+  */ 
+#define RTC_Output_Disable             ((uint32_t)0x00000000)
+#define RTC_Output_AlarmA              ((uint32_t)0x00200000)
+#define RTC_Output_AlarmB              ((uint32_t)0x00400000)
+#define RTC_Output_WakeUp              ((uint32_t)0x00600000)
+ 
+#define IS_RTC_OUTPUT(OUTPUT) (((OUTPUT) == RTC_Output_Disable) || \
+                               ((OUTPUT) == RTC_Output_AlarmA) || \
+                               ((OUTPUT) == RTC_Output_AlarmB) || \
+                               ((OUTPUT) == RTC_Output_WakeUp))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Output_Polarity_Definitions 
+  * @{
+  */ 
+#define RTC_OutputPolarity_High           ((uint32_t)0x00000000)
+#define RTC_OutputPolarity_Low            ((uint32_t)0x00100000)
+#define IS_RTC_OUTPUT_POL(POL) (((POL) == RTC_OutputPolarity_High) || \
+                                ((POL) == RTC_OutputPolarity_Low))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup RTC_Digital_Calibration_Definitions 
+  * @{
+  */ 
+#define RTC_CalibSign_Positive            ((uint32_t)0x00000000) 
+#define RTC_CalibSign_Negative            ((uint32_t)0x00000080)
+#define IS_RTC_CALIB_SIGN(SIGN) (((SIGN) == RTC_CalibSign_Positive) || \
+                                 ((SIGN) == RTC_CalibSign_Negative))
+#define IS_RTC_CALIB_VALUE(VALUE) ((VALUE) < 0x20)
+
+/**
+  * @}
+  */ 
+
+ /** @defgroup RTC_Calib_Output_selection_Definitions 
+  * @{
+  */ 
+#define RTC_CalibOutput_512Hz            ((uint32_t)0x00000000) 
+#define RTC_CalibOutput_1Hz              ((uint32_t)0x00080000)
+#define IS_RTC_CALIB_OUTPUT(OUTPUT)  (((OUTPUT) == RTC_CalibOutput_512Hz) || \
+                                      ((OUTPUT) == RTC_CalibOutput_1Hz))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Smooth_calib_period_Definitions 
+  * @{
+  */ 
+#define RTC_SmoothCalibPeriod_32sec   ((uint32_t)0x00000000) /*!<  if RTCCLK = 32768 Hz, Smooth calibation
+                                                             period is 32s,  else 2exp20 RTCCLK seconds */
+#define RTC_SmoothCalibPeriod_16sec   ((uint32_t)0x00002000) /*!<  if RTCCLK = 32768 Hz, Smooth calibation 
+                                                             period is 16s, else 2exp19 RTCCLK seconds */
+#define RTC_SmoothCalibPeriod_8sec    ((uint32_t)0x00004000) /*!<  if RTCCLK = 32768 Hz, Smooth calibation 
+                                                             period is 8s, else 2exp18 RTCCLK seconds */
+#define IS_RTC_SMOOTH_CALIB_PERIOD(PERIOD) (((PERIOD) == RTC_SmoothCalibPeriod_32sec) || \
+                                             ((PERIOD) == RTC_SmoothCalibPeriod_16sec) || \
+                                             ((PERIOD) == RTC_SmoothCalibPeriod_8sec))
+                                          
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Smooth_calib_Plus_pulses_Definitions 
+  * @{
+  */ 
+#define RTC_SmoothCalibPlusPulses_Set    ((uint32_t)0x00008000) /*!<  The number of RTCCLK pulses added  
+                                                                during a X -second window = Y - CALM[8:0]. 
+                                                                 with Y = 512, 256, 128 when X = 32, 16, 8 */
+#define RTC_SmoothCalibPlusPulses_Reset  ((uint32_t)0x00000000) /*!<  The number of RTCCLK pulses subbstited
+                                                                 during a 32-second window =   CALM[8:0]. */
+#define IS_RTC_SMOOTH_CALIB_PLUS(PLUS) (((PLUS) == RTC_SmoothCalibPlusPulses_Set) || \
+                                         ((PLUS) == RTC_SmoothCalibPlusPulses_Reset))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Smooth_calib_Minus_pulses_Definitions 
+  * @{
+  */ 
+#define  IS_RTC_SMOOTH_CALIB_MINUS(VALUE) ((VALUE) <= 0x000001FF)
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_DayLightSaving_Definitions 
+  * @{
+  */ 
+#define RTC_DayLightSaving_SUB1H   ((uint32_t)0x00020000)
+#define RTC_DayLightSaving_ADD1H   ((uint32_t)0x00010000)
+#define IS_RTC_DAYLIGHT_SAVING(SAVE) (((SAVE) == RTC_DayLightSaving_SUB1H) || \
+                                      ((SAVE) == RTC_DayLightSaving_ADD1H))
+
+#define RTC_StoreOperation_Reset        ((uint32_t)0x00000000)
+#define RTC_StoreOperation_Set          ((uint32_t)0x00040000)
+#define IS_RTC_STORE_OPERATION(OPERATION) (((OPERATION) == RTC_StoreOperation_Reset) || \
+                                           ((OPERATION) == RTC_StoreOperation_Set))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Tamper_Trigger_Definitions 
+  * @{
+  */ 
+#define RTC_TamperTrigger_RisingEdge            ((uint32_t)0x00000000)
+#define RTC_TamperTrigger_FallingEdge           ((uint32_t)0x00000001)
+#define RTC_TamperTrigger_LowLevel              ((uint32_t)0x00000000)
+#define RTC_TamperTrigger_HighLevel             ((uint32_t)0x00000001)
+#define IS_RTC_TAMPER_TRIGGER(TRIGGER) (((TRIGGER) == RTC_TamperTrigger_RisingEdge) || \
+                                        ((TRIGGER) == RTC_TamperTrigger_FallingEdge) || \
+                                        ((TRIGGER) == RTC_TamperTrigger_LowLevel) || \
+                                        ((TRIGGER) == RTC_TamperTrigger_HighLevel)) 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Tamper_Filter_Definitions 
+  * @{
+  */ 
+#define RTC_TamperFilter_Disable   ((uint32_t)0x00000000) /*!< Tamper filter is disabled */
+
+#define RTC_TamperFilter_2Sample   ((uint32_t)0x00000800) /*!< Tamper is activated after 2 
+                                                          consecutive samples at the active level */
+#define RTC_TamperFilter_4Sample   ((uint32_t)0x00001000) /*!< Tamper is activated after 4 
+                                                          consecutive samples at the active level */
+#define RTC_TamperFilter_8Sample   ((uint32_t)0x00001800) /*!< Tamper is activated after 8 
+                                                          consecutive samples at the active leve. */
+#define IS_RTC_TAMPER_FILTER(FILTER) (((FILTER) == RTC_TamperFilter_Disable) || \
+                                      ((FILTER) == RTC_TamperFilter_2Sample) || \
+                                      ((FILTER) == RTC_TamperFilter_4Sample) || \
+                                      ((FILTER) == RTC_TamperFilter_8Sample))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Tamper_Sampling_Frequencies_Definitions 
+  * @{
+  */ 
+#define RTC_TamperSamplingFreq_RTCCLK_Div32768  ((uint32_t)0x00000000) /*!< Each of the tamper inputs are sampled
+                                                                           with a frequency =  RTCCLK / 32768 */
+#define RTC_TamperSamplingFreq_RTCCLK_Div16384  ((uint32_t)0x000000100) /*!< Each of the tamper inputs are sampled
+                                                                            with a frequency =  RTCCLK / 16384 */
+#define RTC_TamperSamplingFreq_RTCCLK_Div8192   ((uint32_t)0x00000200) /*!< Each of the tamper inputs are sampled
+                                                                           with a frequency =  RTCCLK / 8192  */
+#define RTC_TamperSamplingFreq_RTCCLK_Div4096   ((uint32_t)0x00000300) /*!< Each of the tamper inputs are sampled
+                                                                           with a frequency =  RTCCLK / 4096  */
+#define RTC_TamperSamplingFreq_RTCCLK_Div2048   ((uint32_t)0x00000400) /*!< Each of the tamper inputs are sampled
+                                                                           with a frequency =  RTCCLK / 2048  */
+#define RTC_TamperSamplingFreq_RTCCLK_Div1024   ((uint32_t)0x00000500) /*!< Each of the tamper inputs are sampled
+                                                                           with a frequency =  RTCCLK / 1024  */
+#define RTC_TamperSamplingFreq_RTCCLK_Div512    ((uint32_t)0x00000600) /*!< Each of the tamper inputs are sampled
+                                                                           with a frequency =  RTCCLK / 512   */
+#define RTC_TamperSamplingFreq_RTCCLK_Div256    ((uint32_t)0x00000700) /*!< Each of the tamper inputs are sampled
+                                                                           with a frequency =  RTCCLK / 256   */
+#define IS_RTC_TAMPER_SAMPLING_FREQ(FREQ) (((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div32768) || \
+                                           ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div16384) || \
+                                           ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div8192) || \
+                                           ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div4096) || \
+                                           ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div2048) || \
+                                           ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div1024) || \
+                                           ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div512) || \
+                                           ((FREQ) ==RTC_TamperSamplingFreq_RTCCLK_Div256))
+
+/**
+  * @}
+  */
+
+  /** @defgroup RTC_Tamper_Pin_Precharge_Duration_Definitions 
+  * @{
+  */ 
+#define RTC_TamperPrechargeDuration_1RTCCLK ((uint32_t)0x00000000)  /*!< Tamper pins are pre-charged before 
+                                                                         sampling during 1 RTCCLK cycle */
+#define RTC_TamperPrechargeDuration_2RTCCLK ((uint32_t)0x00002000)  /*!< Tamper pins are pre-charged before 
+                                                                         sampling during 2 RTCCLK cycles */
+#define RTC_TamperPrechargeDuration_4RTCCLK ((uint32_t)0x00004000)  /*!< Tamper pins are pre-charged before 
+                                                                         sampling during 4 RTCCLK cycles */
+#define RTC_TamperPrechargeDuration_8RTCCLK ((uint32_t)0x00006000)  /*!< Tamper pins are pre-charged before 
+                                                                         sampling during 8 RTCCLK cycles */
+
+#define IS_RTC_TAMPER_PRECHARGE_DURATION(DURATION) (((DURATION) == RTC_TamperPrechargeDuration_1RTCCLK) || \
+                                                    ((DURATION) == RTC_TamperPrechargeDuration_2RTCCLK) || \
+                                                    ((DURATION) == RTC_TamperPrechargeDuration_4RTCCLK) || \
+                                                    ((DURATION) == RTC_TamperPrechargeDuration_8RTCCLK))
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Tamper_Pins_Definitions 
+  * @{
+  */ 
+#define RTC_Tamper_1                    RTC_TAFCR_TAMP1E
+#define IS_RTC_TAMPER(TAMPER) (((TAMPER) == RTC_Tamper_1))
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Tamper_Pin_Selection 
+  * @{
+  */ 
+#define RTC_TamperPin_PC13                 ((uint32_t)0x00000000)
+#define RTC_TamperPin_PI8                  ((uint32_t)0x00010000)
+#define IS_RTC_TAMPER_PIN(PIN) (((PIN) == RTC_TamperPin_PC13) || \
+                                ((PIN) == RTC_TamperPin_PI8))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_TimeStamp_Pin_Selection 
+  * @{
+  */ 
+#define RTC_TimeStampPin_PC13              ((uint32_t)0x00000000)
+#define RTC_TimeStampPin_PI8               ((uint32_t)0x00020000)
+#define IS_RTC_TIMESTAMP_PIN(PIN) (((PIN) == RTC_TimeStampPin_PC13) || \
+                                   ((PIN) == RTC_TimeStampPin_PI8))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Output_Type_ALARM_OUT 
+  * @{
+  */ 
+#define RTC_OutputType_OpenDrain           ((uint32_t)0x00000000)
+#define RTC_OutputType_PushPull            ((uint32_t)0x00040000)
+#define IS_RTC_OUTPUT_TYPE(TYPE) (((TYPE) == RTC_OutputType_OpenDrain) || \
+                                  ((TYPE) == RTC_OutputType_PushPull))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Add_1_Second_Parameter_Definitions
+  * @{
+  */ 
+#define RTC_ShiftAdd1S_Reset      ((uint32_t)0x00000000)
+#define RTC_ShiftAdd1S_Set        ((uint32_t)0x80000000)
+#define IS_RTC_SHIFT_ADD1S(SEL) (((SEL) == RTC_ShiftAdd1S_Reset) || \
+                                 ((SEL) == RTC_ShiftAdd1S_Set))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Substract_Fraction_Of_Second_Value
+  * @{
+  */ 
+#define IS_RTC_SHIFT_SUBFS(FS) ((FS) <= 0x00007FFF)
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Backup_Registers_Definitions 
+  * @{
+  */
+
+#define RTC_BKP_DR0                       ((uint32_t)0x00000000)
+#define RTC_BKP_DR1                       ((uint32_t)0x00000001)
+#define RTC_BKP_DR2                       ((uint32_t)0x00000002)
+#define RTC_BKP_DR3                       ((uint32_t)0x00000003)
+#define RTC_BKP_DR4                       ((uint32_t)0x00000004)
+#define RTC_BKP_DR5                       ((uint32_t)0x00000005)
+#define RTC_BKP_DR6                       ((uint32_t)0x00000006)
+#define RTC_BKP_DR7                       ((uint32_t)0x00000007)
+#define RTC_BKP_DR8                       ((uint32_t)0x00000008)
+#define RTC_BKP_DR9                       ((uint32_t)0x00000009)
+#define RTC_BKP_DR10                      ((uint32_t)0x0000000A)
+#define RTC_BKP_DR11                      ((uint32_t)0x0000000B)
+#define RTC_BKP_DR12                      ((uint32_t)0x0000000C)
+#define RTC_BKP_DR13                      ((uint32_t)0x0000000D)
+#define RTC_BKP_DR14                      ((uint32_t)0x0000000E)
+#define RTC_BKP_DR15                      ((uint32_t)0x0000000F)
+#define RTC_BKP_DR16                      ((uint32_t)0x00000010)
+#define RTC_BKP_DR17                      ((uint32_t)0x00000011)
+#define RTC_BKP_DR18                      ((uint32_t)0x00000012)
+#define RTC_BKP_DR19                      ((uint32_t)0x00000013)
+#define IS_RTC_BKP(BKP)                   (((BKP) == RTC_BKP_DR0) || \
+                                           ((BKP) == RTC_BKP_DR1) || \
+                                           ((BKP) == RTC_BKP_DR2) || \
+                                           ((BKP) == RTC_BKP_DR3) || \
+                                           ((BKP) == RTC_BKP_DR4) || \
+                                           ((BKP) == RTC_BKP_DR5) || \
+                                           ((BKP) == RTC_BKP_DR6) || \
+                                           ((BKP) == RTC_BKP_DR7) || \
+                                           ((BKP) == RTC_BKP_DR8) || \
+                                           ((BKP) == RTC_BKP_DR9) || \
+                                           ((BKP) == RTC_BKP_DR10) || \
+                                           ((BKP) == RTC_BKP_DR11) || \
+                                           ((BKP) == RTC_BKP_DR12) || \
+                                           ((BKP) == RTC_BKP_DR13) || \
+                                           ((BKP) == RTC_BKP_DR14) || \
+                                           ((BKP) == RTC_BKP_DR15) || \
+                                           ((BKP) == RTC_BKP_DR16) || \
+                                           ((BKP) == RTC_BKP_DR17) || \
+                                           ((BKP) == RTC_BKP_DR18) || \
+                                           ((BKP) == RTC_BKP_DR19))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Input_parameter_format_definitions 
+  * @{
+  */ 
+#define RTC_Format_BIN                    ((uint32_t)0x000000000)
+#define RTC_Format_BCD                    ((uint32_t)0x000000001)
+#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == RTC_Format_BIN) || ((FORMAT) == RTC_Format_BCD))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Flags_Definitions 
+  * @{
+  */ 
+#define RTC_FLAG_RECALPF                  ((uint32_t)0x00010000)
+#define RTC_FLAG_TAMP1F                   ((uint32_t)0x00002000)
+#define RTC_FLAG_TSOVF                    ((uint32_t)0x00001000)
+#define RTC_FLAG_TSF                      ((uint32_t)0x00000800)
+#define RTC_FLAG_WUTF                     ((uint32_t)0x00000400)
+#define RTC_FLAG_ALRBF                    ((uint32_t)0x00000200)
+#define RTC_FLAG_ALRAF                    ((uint32_t)0x00000100)
+#define RTC_FLAG_INITF                    ((uint32_t)0x00000040)
+#define RTC_FLAG_RSF                      ((uint32_t)0x00000020)
+#define RTC_FLAG_INITS                    ((uint32_t)0x00000010)
+#define RTC_FLAG_SHPF                     ((uint32_t)0x00000008)
+#define RTC_FLAG_WUTWF                    ((uint32_t)0x00000004)
+#define RTC_FLAG_ALRBWF                   ((uint32_t)0x00000002)
+#define RTC_FLAG_ALRAWF                   ((uint32_t)0x00000001)
+#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_TSOVF) || ((FLAG) == RTC_FLAG_TSF) || \
+                               ((FLAG) == RTC_FLAG_WUTF) || ((FLAG) == RTC_FLAG_ALRBF) || \
+                               ((FLAG) == RTC_FLAG_ALRAF) || ((FLAG) == RTC_FLAG_INITF) || \
+                               ((FLAG) == RTC_FLAG_RSF) || ((FLAG) == RTC_FLAG_WUTWF) || \
+                               ((FLAG) == RTC_FLAG_ALRBWF) || ((FLAG) == RTC_FLAG_ALRAWF) || \
+                               ((FLAG) == RTC_FLAG_TAMP1F) || ((FLAG) == RTC_FLAG_RECALPF) || \
+                                ((FLAG) == RTC_FLAG_SHPF))
+#define IS_RTC_CLEAR_FLAG(FLAG) (((FLAG) != (uint32_t)RESET) && (((FLAG) & 0xFFFF00DF) == (uint32_t)RESET))
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Interrupts_Definitions 
+  * @{
+  */ 
+#define RTC_IT_TS                         ((uint32_t)0x00008000)
+#define RTC_IT_WUT                        ((uint32_t)0x00004000)
+#define RTC_IT_ALRB                       ((uint32_t)0x00002000)
+#define RTC_IT_ALRA                       ((uint32_t)0x00001000)
+#define RTC_IT_TAMP                       ((uint32_t)0x00000004) /* Used only to Enable the Tamper Interrupt */
+#define RTC_IT_TAMP1                      ((uint32_t)0x00020000)
+
+#define IS_RTC_CONFIG_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFFF0FFB) == (uint32_t)RESET))
+#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_TS) || ((IT) == RTC_IT_WUT) || \
+                           ((IT) == RTC_IT_ALRB) || ((IT) == RTC_IT_ALRA) || \
+                           ((IT) == RTC_IT_TAMP1))
+#define IS_RTC_CLEAR_IT(IT) (((IT) != (uint32_t)RESET) && (((IT) & 0xFFFD0FFF) == (uint32_t)RESET))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup RTC_Legacy 
+  * @{
+  */ 
+#define RTC_DigitalCalibConfig  RTC_CoarseCalibConfig
+#define RTC_DigitalCalibCmd     RTC_CoarseCalibCmd
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the RTC configuration to the default reset state *****/
+ErrorStatus RTC_DeInit(void);
+
+/* Initialization and Configuration functions *********************************/
+ErrorStatus RTC_Init(RTC_InitTypeDef* RTC_InitStruct);
+void RTC_StructInit(RTC_InitTypeDef* RTC_InitStruct);
+void RTC_WriteProtectionCmd(FunctionalState NewState);
+ErrorStatus RTC_EnterInitMode(void);
+void RTC_ExitInitMode(void);
+ErrorStatus RTC_WaitForSynchro(void);
+ErrorStatus RTC_RefClockCmd(FunctionalState NewState);
+void RTC_BypassShadowCmd(FunctionalState NewState);
+
+/* Time and Date configuration functions **************************************/
+ErrorStatus RTC_SetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct);
+void RTC_TimeStructInit(RTC_TimeTypeDef* RTC_TimeStruct);
+void RTC_GetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct);
+uint32_t RTC_GetSubSecond(void);
+ErrorStatus RTC_SetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct);
+void RTC_DateStructInit(RTC_DateTypeDef* RTC_DateStruct);
+void RTC_GetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct);
+
+/* Alarms (Alarm A and Alarm B) configuration functions  **********************/
+void RTC_SetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct);
+void RTC_AlarmStructInit(RTC_AlarmTypeDef* RTC_AlarmStruct);
+void RTC_GetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct);
+ErrorStatus RTC_AlarmCmd(uint32_t RTC_Alarm, FunctionalState NewState);
+void RTC_AlarmSubSecondConfig(uint32_t RTC_Alarm, uint32_t RTC_AlarmSubSecondValue, uint32_t RTC_AlarmSubSecondMask);
+uint32_t RTC_GetAlarmSubSecond(uint32_t RTC_Alarm);
+
+/* WakeUp Timer configuration functions ***************************************/
+void RTC_WakeUpClockConfig(uint32_t RTC_WakeUpClock);
+void RTC_SetWakeUpCounter(uint32_t RTC_WakeUpCounter);
+uint32_t RTC_GetWakeUpCounter(void);
+ErrorStatus RTC_WakeUpCmd(FunctionalState NewState);
+
+/* Daylight Saving configuration functions ************************************/
+void RTC_DayLightSavingConfig(uint32_t RTC_DayLightSaving, uint32_t RTC_StoreOperation);
+uint32_t RTC_GetStoreOperation(void);
+
+/* Output pin Configuration function ******************************************/
+void RTC_OutputConfig(uint32_t RTC_Output, uint32_t RTC_OutputPolarity);
+
+/* Digital Calibration configuration functions *********************************/
+ErrorStatus RTC_CoarseCalibConfig(uint32_t RTC_CalibSign, uint32_t Value);
+ErrorStatus RTC_CoarseCalibCmd(FunctionalState NewState);
+void RTC_CalibOutputCmd(FunctionalState NewState);
+void RTC_CalibOutputConfig(uint32_t RTC_CalibOutput);
+ErrorStatus RTC_SmoothCalibConfig(uint32_t RTC_SmoothCalibPeriod, 
+                                  uint32_t RTC_SmoothCalibPlusPulses,
+                                  uint32_t RTC_SmouthCalibMinusPulsesValue);
+
+/* TimeStamp configuration functions ******************************************/
+void RTC_TimeStampCmd(uint32_t RTC_TimeStampEdge, FunctionalState NewState);
+void RTC_GetTimeStamp(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_StampTimeStruct,
+                                      RTC_DateTypeDef* RTC_StampDateStruct);
+uint32_t RTC_GetTimeStampSubSecond(void);
+
+/* Tampers configuration functions ********************************************/
+void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger);
+void RTC_TamperCmd(uint32_t RTC_Tamper, FunctionalState NewState);
+void RTC_TamperFilterConfig(uint32_t RTC_TamperFilter);
+void RTC_TamperSamplingFreqConfig(uint32_t RTC_TamperSamplingFreq);
+void RTC_TamperPinsPrechargeDuration(uint32_t RTC_TamperPrechargeDuration);
+void RTC_TimeStampOnTamperDetectionCmd(FunctionalState NewState);
+void RTC_TamperPullUpCmd(FunctionalState NewState);
+
+/* Backup Data Registers configuration functions ******************************/
+void RTC_WriteBackupRegister(uint32_t RTC_BKP_DR, uint32_t Data);
+uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR);
+
+/* RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration
+   functions ******************************************************************/
+void RTC_TamperPinSelection(uint32_t RTC_TamperPin);
+void RTC_TimeStampPinSelection(uint32_t RTC_TimeStampPin);
+void RTC_OutputTypeConfig(uint32_t RTC_OutputType);
+
+/* RTC_Shift_control_synchonisation_functions *********************************/
+ErrorStatus RTC_SynchroShiftConfig(uint32_t RTC_ShiftAdd1S, uint32_t RTC_ShiftSubFS);
+
+/* Interrupts and flags management functions **********************************/
+void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState);
+FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG);
+void RTC_ClearFlag(uint32_t RTC_FLAG);
+ITStatus RTC_GetITStatus(uint32_t RTC_IT);
+void RTC_ClearITPendingBit(uint32_t RTC_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_RTC_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sai.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sai.h
new file mode 100644
index 0000000000000000000000000000000000000000..8708646e7903e2d7a172afc5f99829d6427eb1f8
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sai.h
@@ -0,0 +1,611 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_sai.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the SAI 
+  *          firmware library.  
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_SAI_H
+#define __STM32F4xx_SAI_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup SAI
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  SAI Block Init structure definition  
+  */
+
+typedef struct
+{
+  uint32_t SAI_AudioMode;           /*!< Specifies the SAI Block Audio Mode.
+                                         This parameter can be a value of @ref SAI_Block_Mode */
+
+  uint32_t SAI_Protocol;             /*!< Specifies the SAI Block Protocol.
+                                         This parameter can be a value of @ref SAI_Block_Protocol */
+
+  uint32_t SAI_DataSize;            /*!< Specifies the SAI Block data size.
+                                         This parameter can be a value of @ref SAI_Block_Data_Size 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_FirstBit;            /*!< Specifies whether data transfers start from MSB or LSB bit.
+                                         This parameter can be a value of @ref SAI_Block_MSB_LSB_transmission 
+                                         @note this value has no meaning when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_ClockStrobing;       /*!< Specifies the SAI Block clock strobing edge sensitivity.
+                                         This parameter can be a value of @ref SAI_Block_Clock_Strobing */
+
+  uint32_t SAI_Synchro;             /*!< Specifies SAI Block synchronization
+                                         This parameter can be a value of @ref SAI_Block_Synchronization */
+ 
+  uint32_t SAI_OUTDRIV;             /*!< Specifies when SAI Block outputs are driven.
+                                         This parameter can be a value of @ref SAI_Block_Output_Drive
+                                         @note this value has to be set before enabling the audio block  
+                                               but after the audio block configuration. */
+
+  uint32_t SAI_NoDivider;            /*!< Specifies whether Master Clock will be divided or not.
+                                         This parameter can be a value of @ref SAI_Block_NoDivider */
+
+  uint32_t SAI_MasterDivider;       /*!< Specifies SAI Block Master Clock Divider. 
+                                         @note the Master Clock Frequency is calculated accordingly to the  
+                                               following formula : MCLK_x = SAI_CK_x/(MCKDIV[3:0]*2)*/
+                                               
+  uint32_t SAI_FIFOThreshold;      /*!< Specifies SAI Block FIFO Threshold.
+                                         This parameter can be a value of @ref SAI_Block_Fifo_Threshold */                                                                                             
+}SAI_InitTypeDef;
+
+/** 
+  * @brief  SAI Block Frame Init structure definition  
+  */
+
+typedef struct
+{
+
+  uint32_t SAI_FrameLength;         /*!< Specifies the Frame Length, the number of SCK clocks 
+                                         for each audio frame.
+                                         This parameter must be a number between 8 and 256.
+                                         @note If master Clock MCLK_x pin is declared as an output, the frame length
+                                               should be Aligned to a number equal to power of 2 in order to keep 
+                                              in an audio frame, an integer number of MCLK pulses by bit Clock.                                                 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+                                   
+  uint32_t SAI_ActiveFrameLength;   /*!< Specifies the Frame synchronization active level length.
+                                         This Parameter specifies the length in number of bit clock (SCK + 1)  
+                                         of the active level of FS signal in audio frame.
+                                         This parameter must be a number between 1 and 128. 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_FSDefinition;        /*!< Specifies the Frame Synchronization definition.
+                                         This parameter can be a value of @ref SAI_Block_FS_Definition 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_FSPolarity;          /*!< Specifies the Frame Synchronization Polarity.
+                                         This parameter can be a value of @ref SAI_Block_FS_Polarity 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_FSOffset;            /*!< Specifies the Frame Synchronization Offset.
+                                         This parameter can be a value of @ref SAI_Block_FS_Offset 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+}SAI_FrameInitTypeDef;
+
+/**
+  * @brief   SAI Block Slot Init Structure definition
+  */    
+
+typedef struct
+{
+  uint32_t SAI_FirstBitOffset;      /*!< Specifies the position of first data transfer bit in the slot.
+                                         This parameter must be a number between 0 and 24. 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_SlotSize;            /*!< Specifies the Slot Size.
+                                         This parameter can be a value of @ref SAI_Block_Slot_Size 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_SlotNumber;          /*!< Specifies the number of slot in the audio frame.
+                                         This parameter must be a number between 1 and 16. 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/
+
+  uint32_t SAI_SlotActive;          /*!< Specifies the slots in audio frame that will be activated.
+                                         This parameter can be a value of @ ref SAI_Block_Slot_Active 
+                                         @note this value is ignored when AC'97 or SPDIF protocols are selected.*/ 
+}SAI_SlotInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup SAI_Exported_Constants
+  * @{
+  */
+
+#define IS_SAI_PERIPH(PERIPH) ((PERIPH) == SAI1)
+
+#define IS_SAI_BLOCK_PERIPH(PERIPH) (((PERIPH) == SAI1_Block_A) || \
+                                     ((PERIPH) == SAI1_Block_B))
+
+
+/** @defgroup SAI_Block_Mode 
+  * @{
+  */
+#define SAI_Mode_MasterTx               ((uint32_t)0x00000000)
+#define SAI_Mode_MasterRx               ((uint32_t)0x00000001)  
+#define SAI_Mode_SlaveTx                ((uint32_t)0x00000002)
+#define SAI_Mode_SlaveRx                ((uint32_t)0x00000003)
+#define IS_SAI_BLOCK_MODE(MODE) (((MODE) == SAI_Mode_MasterTx) || \
+                                 ((MODE) == SAI_Mode_MasterRx) || \
+                                 ((MODE) == SAI_Mode_SlaveTx)  || \
+                                 ((MODE) == SAI_Mode_SlaveRx))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Protocol 
+  * @{
+  */
+
+#define SAI_Free_Protocol                 ((uint32_t)0x00000000)
+#define SAI_SPDIF_Protocol                ((uint32_t)SAI_xCR1_PRTCFG_0)
+#define SAI_AC97_Protocol                 ((uint32_t)SAI_xCR1_PRTCFG_1)
+#define IS_SAI_BLOCK_PROTOCOL(PROTOCOL) (((PROTOCOL) == SAI_Free_Protocol)  || \
+                                         ((PROTOCOL) == SAI_SPDIF_Protocol) || \
+                                         ((PROTOCOL) == SAI_AC97_Protocol))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Data_Size 
+  * @{
+  */
+
+#define SAI_DataSize_8b                   ((uint32_t)0x00000040)
+#define SAI_DataSize_10b                  ((uint32_t)0x00000060)
+#define SAI_DataSize_16b                  ((uint32_t)0x00000080)
+#define SAI_DataSize_20b                  ((uint32_t)0x000000A0)
+#define SAI_DataSize_24b                  ((uint32_t)0x000000C0)
+#define SAI_DataSize_32b                  ((uint32_t)0x000000E0)
+#define IS_SAI_BLOCK_DATASIZE(DATASIZE) (((DATASIZE) == SAI_DataSize_8b)  || \
+                                         ((DATASIZE) == SAI_DataSize_10b) || \
+                                         ((DATASIZE) == SAI_DataSize_16b) || \
+                                         ((DATASIZE) == SAI_DataSize_20b) || \
+                                         ((DATASIZE) == SAI_DataSize_24b) || \
+                                         ((DATASIZE) == SAI_DataSize_32b))
+/**
+  * @}
+  */ 
+
+/** @defgroup SAI_Block_MSB_LSB_transmission 
+  * @{
+  */
+
+#define SAI_FirstBit_MSB                  ((uint32_t)0x00000000)
+#define SAI_FirstBit_LSB                  ((uint32_t)SAI_xCR1_LSBFIRST)
+#define IS_SAI_BLOCK_FIRST_BIT(BIT) (((BIT) == SAI_FirstBit_MSB) || \
+                                     ((BIT) == SAI_FirstBit_LSB))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Clock_Strobing 
+  * @{
+  */
+
+#define SAI_ClockStrobing_FallingEdge     ((uint32_t)0x00000000)
+#define SAI_ClockStrobing_RisingEdge      ((uint32_t)SAI_xCR1_CKSTR)
+#define IS_SAI_BLOCK_CLOCK_STROBING(CLOCK) (((CLOCK) == SAI_ClockStrobing_FallingEdge) || \
+                                            ((CLOCK) == SAI_ClockStrobing_RisingEdge))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Synchronization 
+  * @{
+  */
+
+#define SAI_Asynchronous                   ((uint32_t)0x00000000)
+#define SAI_Synchronous                    ((uint32_t)SAI_xCR1_SYNCEN_0)
+#define IS_SAI_BLOCK_SYNCHRO(SYNCHRO) (((SYNCHRO) == SAI_Synchronous) || \
+                                       ((SYNCHRO) == SAI_Asynchronous))
+/**
+  * @}
+  */ 
+
+/** @defgroup SAI_Block_Output_Drive 
+  * @{
+  */
+
+#define SAI_OutputDrive_Disabled          ((uint32_t)0x00000000)
+#define SAI_OutputDrive_Enabled           ((uint32_t)SAI_xCR1_OUTDRIV)
+#define IS_SAI_BLOCK_OUTPUT_DRIVE(DRIVE) (((DRIVE) == SAI_OutputDrive_Disabled) || \
+                                          ((DRIVE) == SAI_OutputDrive_Enabled))
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup SAI_Block_NoDivider 
+  * @{
+  */
+
+#define SAI_MasterDivider_Enabled         ((uint32_t)0x00000000)
+#define SAI_MasterDivider_Disabled        ((uint32_t)SAI_xCR1_NODIV)
+#define IS_SAI_BLOCK_NODIVIDER(NODIVIDER) (((NODIVIDER) == SAI_MasterDivider_Enabled) || \
+                                           ((NODIVIDER) == SAI_MasterDivider_Disabled))
+/**
+  * @}
+  */
+  
+
+/** @defgroup SAI_Block_Master_Divider 
+  * @{
+  */
+#define IS_SAI_BLOCK_MASTER_DIVIDER(DIVIDER) ((DIVIDER) <= 15)
+
+/**
+  * @}
+  */
+  
+/** @defgroup SAI_Block_Frame_Length 
+  * @{
+  */
+#define IS_SAI_BLOCK_FRAME_LENGTH(LENGTH) ((8 <= (LENGTH)) && ((LENGTH) <= 256))
+
+/**
+  * @}
+  */
+    
+/** @defgroup SAI_Block_Active_FrameLength 
+  * @{
+  */
+#define IS_SAI_BLOCK_ACTIVE_FRAME(LENGTH) ((1 <= (LENGTH)) && ((LENGTH) <= 128))
+
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_FS_Definition 
+  * @{
+  */
+
+#define SAI_FS_StartFrame                 ((uint32_t)0x00000000)
+#define I2S_FS_ChannelIdentification      ((uint32_t)SAI_xFRCR_FSDEF)
+#define IS_SAI_BLOCK_FS_DEFINITION(DEFINITION) (((DEFINITION) == SAI_FS_StartFrame) || \
+                                                ((DEFINITION) == I2S_FS_ChannelIdentification))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_FS_Polarity 
+  * @{
+  */
+
+#define SAI_FS_ActiveLow                  ((uint32_t)0x00000000)
+#define SAI_FS_ActiveHigh                 ((uint32_t)SAI_xFRCR_FSPO)
+#define IS_SAI_BLOCK_FS_POLARITY(POLARITY) (((POLARITY) == SAI_FS_ActiveLow) || \
+                                            ((POLARITY) == SAI_FS_ActiveHigh))
+/**
+  * @}
+  */
+            
+/** @defgroup SAI_Block_FS_Offset 
+  * @{
+  */
+  
+#define SAI_FS_FirstBit                   ((uint32_t)0x00000000)
+#define SAI_FS_BeforeFirstBit             ((uint32_t)SAI_xFRCR_FSOFF)
+#define IS_SAI_BLOCK_FS_OFFSET(OFFSET) (((OFFSET) == SAI_FS_FirstBit) || \
+                                        ((OFFSET) == SAI_FS_BeforeFirstBit))
+/**
+  * @}
+  */
+  
+/** @defgroup SAI_Block_Slot_FirstBit_Offset
+  * @{
+  */
+#define IS_SAI_BLOCK_FIRSTBIT_OFFSET(OFFSET) ((OFFSET) <= 24)
+
+/**
+  * @}
+  */
+
+  /** @defgroup SAI_Block_Slot_Size
+  * @{
+  */
+#define SAI_SlotSize_DataSize             ((uint32_t)0x00000000)  
+#define SAI_SlotSize_16b                  ((uint32_t)SAI_xSLOTR_SLOTSZ_0)
+#define SAI_SlotSize_32b                  ((uint32_t)SAI_xSLOTR_SLOTSZ_1)
+#define IS_SAI_BLOCK_SLOT_SIZE(SIZE) (((SIZE) == SAI_SlotSize_DataSize) || \
+                                      ((SIZE) == SAI_SlotSize_16b)      || \
+                                      ((SIZE) == SAI_SlotSize_32b))
+
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Slot_Number
+  * @{
+  */
+#define IS_SAI_BLOCK_SLOT_NUMBER(NUMBER) ((1 <= (NUMBER)) && ((NUMBER) <= 16))
+
+/**
+  * @}
+  */
+  
+/** @defgroup SAI_Block_Slot_Active
+  * @{
+  */
+#define SAI_Slot_NotActive           ((uint32_t)0x00000000)  
+#define SAI_SlotActive_0             ((uint32_t)0x00010000)  
+#define SAI_SlotActive_1             ((uint32_t)0x00020000)
+#define SAI_SlotActive_2             ((uint32_t)0x00040000)
+#define SAI_SlotActive_3             ((uint32_t)0x00080000)
+#define SAI_SlotActive_4             ((uint32_t)0x00100000)
+#define SAI_SlotActive_5             ((uint32_t)0x00200000)
+#define SAI_SlotActive_6             ((uint32_t)0x00400000)
+#define SAI_SlotActive_7             ((uint32_t)0x00800000)
+#define SAI_SlotActive_8             ((uint32_t)0x01000000)
+#define SAI_SlotActive_9             ((uint32_t)0x02000000)
+#define SAI_SlotActive_10            ((uint32_t)0x04000000)
+#define SAI_SlotActive_11            ((uint32_t)0x08000000)
+#define SAI_SlotActive_12            ((uint32_t)0x10000000)
+#define SAI_SlotActive_13            ((uint32_t)0x20000000)
+#define SAI_SlotActive_14            ((uint32_t)0x40000000)
+#define SAI_SlotActive_15            ((uint32_t)0x80000000)
+#define SAI_SlotActive_ALL           ((uint32_t)0xFFFF0000)
+
+#define IS_SAI_SLOT_ACTIVE(ACTIVE) ((ACTIVE) != 0)
+
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Mono_Streo_Mode
+  * @{
+  */
+
+#define SAI_MonoMode                      ((uint32_t)SAI_xCR1_MONO)
+#define SAI_StreoMode                     ((uint32_t)0x00000000)
+#define IS_SAI_BLOCK_MONO_STREO_MODE(MODE) (((MODE) == SAI_MonoMode) ||\
+                                            ((MODE) == SAI_StreoMode))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_TRIState_Management
+  * @{
+  */
+
+#define SAI_Output_NotReleased              ((uint32_t)0x00000000)
+#define SAI_Output_Released                 ((uint32_t)SAI_xCR2_TRIS)
+#define IS_SAI_BLOCK_TRISTATE_MANAGEMENT(STATE) (((STATE) == SAI_Output_NotReleased) ||\
+                                                 ((STATE) == SAI_Output_Released))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Fifo_Threshold 
+  * @{
+  */
+
+#define SAI_Threshold_FIFOEmpty           ((uint32_t)0x00000000)
+#define SAI_FIFOThreshold_1QuarterFull    ((uint32_t)0x00000001)
+#define SAI_FIFOThreshold_HalfFull        ((uint32_t)0x00000002) 
+#define SAI_FIFOThreshold_3QuartersFull   ((uint32_t)0x00000003)
+#define SAI_FIFOThreshold_Full            ((uint32_t)0x00000004)
+#define IS_SAI_BLOCK_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == SAI_Threshold_FIFOEmpty)         || \
+                                                ((THRESHOLD) == SAI_FIFOThreshold_1QuarterFull)  || \
+                                                ((THRESHOLD) == SAI_FIFOThreshold_HalfFull)      || \
+                                                ((THRESHOLD) == SAI_FIFOThreshold_3QuartersFull) || \
+                                                ((THRESHOLD) == SAI_FIFOThreshold_Full))
+/**
+  * @}
+  */
+  
+/** @defgroup SAI_Block_Companding_Mode
+  * @{
+  */
+  
+#define SAI_NoCompanding                  ((uint32_t)0x00000000)
+#define SAI_ULaw_1CPL_Companding          ((uint32_t)0x00008000)
+#define SAI_ALaw_1CPL_Companding          ((uint32_t)0x0000C000)
+#define SAI_ULaw_2CPL_Companding          ((uint32_t)0x0000A000)
+#define SAI_ALaw_2CPL_Companding          ((uint32_t)0x0000E000)
+#define IS_SAI_BLOCK_COMPANDING_MODE(MODE)    (((MODE) == SAI_NoCompanding)        || \
+                                              ((MODE) == SAI_ULaw_1CPL_Companding) || \
+                                              ((MODE) == SAI_ALaw_1CPL_Companding) || \
+                                              ((MODE) == SAI_ULaw_2CPL_Companding) || \
+                                              ((MODE) == SAI_ALaw_2CPL_Companding))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Mute_Value
+  * @{
+  */
+  
+#define SAI_ZeroValue                     ((uint32_t)0x00000000)
+#define SAI_LastSentValue                 ((uint32_t)SAI_xCR2_MUTEVAL)
+#define IS_SAI_BLOCK_MUTE_VALUE(VALUE)    (((VALUE) == SAI_ZeroValue)     || \
+                                           ((VALUE) == SAI_LastSentValue))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Mute_Frame_Counter
+  * @{
+  */
+  
+#define IS_SAI_BLOCK_MUTE_COUNTER(COUNTER) ((COUNTER) <= 63)
+
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Interrupts_Definition 
+  * @{
+  */
+
+#define SAI_IT_OVRUDR                     ((uint32_t)SAI_xIMR_OVRUDRIE)
+#define SAI_IT_MUTEDET                    ((uint32_t)SAI_xIMR_MUTEDETIE)
+#define SAI_IT_WCKCFG                     ((uint32_t)SAI_xIMR_WCKCFGIE)
+#define SAI_IT_FREQ                       ((uint32_t)SAI_xIMR_FREQIE)
+#define SAI_IT_CNRDY                      ((uint32_t)SAI_xIMR_CNRDYIE)
+#define SAI_IT_AFSDET                     ((uint32_t)SAI_xIMR_AFSDETIE)
+#define SAI_IT_LFSDET                     ((uint32_t)SAI_xIMR_LFSDETIE)
+
+#define IS_SAI_BLOCK_CONFIG_IT(IT) (((IT) == SAI_IT_OVRUDR)  || \
+                                    ((IT) == SAI_IT_MUTEDET) || \
+                                    ((IT) == SAI_IT_WCKCFG)  || \
+                                    ((IT) == SAI_IT_FREQ)    || \
+                                    ((IT) == SAI_IT_CNRDY)   || \
+                                    ((IT) == SAI_IT_AFSDET)  || \
+                                    ((IT) == SAI_IT_LFSDET))
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Block_Flags_Definition 
+  * @{
+  */
+
+#define SAI_FLAG_OVRUDR                   ((uint32_t)SAI_xSR_OVRUDR)
+#define SAI_FLAG_MUTEDET                  ((uint32_t)SAI_xSR_MUTEDET)
+#define SAI_FLAG_WCKCFG                   ((uint32_t)SAI_xSR_WCKCFG)
+#define SAI_FLAG_FREQ                     ((uint32_t)SAI_xSR_FREQ)
+#define SAI_FLAG_CNRDY                    ((uint32_t)SAI_xSR_CNRDY)
+#define SAI_FLAG_AFSDET                   ((uint32_t)SAI_xSR_AFSDET)
+#define SAI_FLAG_LFSDET                   ((uint32_t)SAI_xSR_LFSDET)
+
+#define IS_SAI_BLOCK_GET_FLAG(FLAG) (((FLAG) == SAI_FLAG_OVRUDR)  || \
+                                    ((FLAG) == SAI_FLAG_MUTEDET) || \
+                                    ((FLAG) == SAI_FLAG_WCKCFG)  || \
+                                    ((FLAG) == SAI_FLAG_FREQ)    || \
+                                    ((FLAG) == SAI_FLAG_CNRDY)   || \
+                                    ((FLAG) == SAI_FLAG_AFSDET)  || \
+                                    ((FLAG) == SAI_FLAG_LFSDET))
+                                   
+#define IS_SAI_BLOCK_CLEAR_FLAG(FLAG) (((FLAG) == SAI_FLAG_OVRUDR)  || \
+                                       ((FLAG) == SAI_FLAG_MUTEDET) || \
+                                       ((FLAG) == SAI_FLAG_WCKCFG)  || \
+                                       ((FLAG) == SAI_FLAG_FREQ)    || \
+                                       ((FLAG) == SAI_FLAG_CNRDY)   || \
+                                       ((FLAG) == SAI_FLAG_AFSDET)  || \
+                                       ((FLAG) == SAI_FLAG_LFSDET))
+/**
+  * @}
+  */
+  
+/** @defgroup SAI_Block_Fifo_Status_Level 
+  * @{
+  */
+#define SAI_FIFOStatus_Empty              ((uint32_t)0x00000000)
+#define SAI_FIFOStatus_Less1QuarterFull   ((uint32_t)0x00010000)
+#define SAI_FIFOStatus_1QuarterFull       ((uint32_t)0x00020000)
+#define SAI_FIFOStatus_HalfFull           ((uint32_t)0x00030000) 
+#define SAI_FIFOStatus_3QuartersFull      ((uint32_t)0x00040000)
+#define SAI_FIFOStatus_Full               ((uint32_t)0x00050000)
+
+#define IS_SAI_BLOCK_FIFO_STATUS(STATUS) (((STATUS) == SAI_FIFOStatus_Less1QuarterFull ) || \
+                                          ((STATUS) == SAI_FIFOStatus_HalfFull)          || \
+                                          ((STATUS) == SAI_FIFOStatus_1QuarterFull)      || \
+                                          ((STATUS) == SAI_FIFOStatus_3QuartersFull)     || \
+                                          ((STATUS) == SAI_FIFOStatus_Full)              || \
+                                          ((STATUS) == SAI_FIFOStatus_Empty)) 
+/**
+  * @}
+  */
+
+  
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the SAI configuration to the default reset state *****/ 
+void SAI_DeInit(SAI_TypeDef* SAIx);
+
+/* Initialization and Configuration functions *********************************/
+void SAI_Init(SAI_Block_TypeDef* SAI_Block_x, SAI_InitTypeDef* SAI_InitStruct);
+void SAI_FrameInit(SAI_Block_TypeDef* SAI_Block_x, SAI_FrameInitTypeDef* SAI_FrameInitStruct);
+void SAI_SlotInit(SAI_Block_TypeDef* SAI_Block_x, SAI_SlotInitTypeDef* SAI_SlotInitStruct);
+void SAI_StructInit(SAI_InitTypeDef* SAI_InitStruct);
+void SAI_FrameStructInit(SAI_FrameInitTypeDef* SAI_FrameInitStruct);
+void SAI_SlotStructInit(SAI_SlotInitTypeDef* SAI_SlotInitStruct);
+
+void SAI_Cmd(SAI_Block_TypeDef* SAI_Block_x, FunctionalState NewState);
+void SAI_MonoModeConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_Mono_StreoMode);
+void SAI_TRIStateConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_TRIState);
+void SAI_CompandingModeConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_CompandingMode);
+void SAI_MuteModeCmd(SAI_Block_TypeDef* SAI_Block_x, FunctionalState NewState);
+void SAI_MuteValueConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_MuteValue);
+void SAI_MuteFrameCounterConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_MuteCounter);
+void SAI_FlushFIFO(SAI_Block_TypeDef* SAI_Block_x);
+
+/* Data transfers functions ***************************************************/ 
+void SAI_SendData(SAI_Block_TypeDef* SAI_Block_x, uint32_t Data);
+uint32_t SAI_ReceiveData(SAI_Block_TypeDef* SAI_Block_x);
+
+/* DMA transfers management functions *****************************************/
+void SAI_DMACmd(SAI_Block_TypeDef* SAI_Block_x, FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void SAI_ITConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT, FunctionalState NewState);
+FlagStatus SAI_GetFlagStatus(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_FLAG);
+void SAI_ClearFlag(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_FLAG);
+ITStatus SAI_GetITStatus(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT);
+void SAI_ClearITPendingBit(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT);
+FunctionalState SAI_GetCmdStatus(SAI_Block_TypeDef* SAI_Block_x);
+uint32_t SAI_GetFIFOStatus(SAI_Block_TypeDef* SAI_Block_x);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_SAI_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h
new file mode 100644
index 0000000000000000000000000000000000000000..05e0afa3c89d891aea8d0777250bdf789203f95d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_sdio.h
@@ -0,0 +1,536 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_sdio.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the SDIO firmware
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_SDIO_H
+#define __STM32F4xx_SDIO_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup SDIO
+  * @{
+  */
+
+/* Exported types ------------------------------------------------------------*/
+
+typedef struct
+{
+  uint32_t SDIO_ClockEdge;            /*!< Specifies the clock transition on which the bit capture is made.
+                                           This parameter can be a value of @ref SDIO_Clock_Edge */
+
+  uint32_t SDIO_ClockBypass;          /*!< Specifies whether the SDIO Clock divider bypass is
+                                           enabled or disabled.
+                                           This parameter can be a value of @ref SDIO_Clock_Bypass */
+
+  uint32_t SDIO_ClockPowerSave;       /*!< Specifies whether SDIO Clock output is enabled or
+                                           disabled when the bus is idle.
+                                           This parameter can be a value of @ref SDIO_Clock_Power_Save */
+
+  uint32_t SDIO_BusWide;              /*!< Specifies the SDIO bus width.
+                                           This parameter can be a value of @ref SDIO_Bus_Wide */
+
+  uint32_t SDIO_HardwareFlowControl;  /*!< Specifies whether the SDIO hardware flow control is enabled or disabled.
+                                           This parameter can be a value of @ref SDIO_Hardware_Flow_Control */
+
+  uint8_t SDIO_ClockDiv;              /*!< Specifies the clock frequency of the SDIO controller.
+                                           This parameter can be a value between 0x00 and 0xFF. */
+                                           
+} SDIO_InitTypeDef;
+
+typedef struct
+{
+  uint32_t SDIO_Argument;  /*!< Specifies the SDIO command argument which is sent
+                                to a card as part of a command message. If a command
+                                contains an argument, it must be loaded into this register
+                                before writing the command to the command register */
+
+  uint32_t SDIO_CmdIndex;  /*!< Specifies the SDIO command index. It must be lower than 0x40. */
+
+  uint32_t SDIO_Response;  /*!< Specifies the SDIO response type.
+                                This parameter can be a value of @ref SDIO_Response_Type */
+
+  uint32_t SDIO_Wait;      /*!< Specifies whether SDIO wait for interrupt request is enabled or disabled.
+                                This parameter can be a value of @ref SDIO_Wait_Interrupt_State */
+
+  uint32_t SDIO_CPSM;      /*!< Specifies whether SDIO Command path state machine (CPSM)
+                                is enabled or disabled.
+                                This parameter can be a value of @ref SDIO_CPSM_State */
+} SDIO_CmdInitTypeDef;
+
+typedef struct
+{
+  uint32_t SDIO_DataTimeOut;    /*!< Specifies the data timeout period in card bus clock periods. */
+
+  uint32_t SDIO_DataLength;     /*!< Specifies the number of data bytes to be transferred. */
+ 
+  uint32_t SDIO_DataBlockSize;  /*!< Specifies the data block size for block transfer.
+                                     This parameter can be a value of @ref SDIO_Data_Block_Size */
+ 
+  uint32_t SDIO_TransferDir;    /*!< Specifies the data transfer direction, whether the transfer
+                                     is a read or write.
+                                     This parameter can be a value of @ref SDIO_Transfer_Direction */
+ 
+  uint32_t SDIO_TransferMode;   /*!< Specifies whether data transfer is in stream or block mode.
+                                     This parameter can be a value of @ref SDIO_Transfer_Type */
+ 
+  uint32_t SDIO_DPSM;           /*!< Specifies whether SDIO Data path state machine (DPSM)
+                                     is enabled or disabled.
+                                     This parameter can be a value of @ref SDIO_DPSM_State */
+} SDIO_DataInitTypeDef;
+
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup SDIO_Exported_Constants
+  * @{
+  */
+
+/** @defgroup SDIO_Clock_Edge 
+  * @{
+  */
+
+#define SDIO_ClockEdge_Rising               ((uint32_t)0x00000000)
+#define SDIO_ClockEdge_Falling              ((uint32_t)0x00002000)
+#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \
+                                  ((EDGE) == SDIO_ClockEdge_Falling))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Clock_Bypass 
+  * @{
+  */
+
+#define SDIO_ClockBypass_Disable             ((uint32_t)0x00000000)
+#define SDIO_ClockBypass_Enable              ((uint32_t)0x00000400)    
+#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \
+                                     ((BYPASS) == SDIO_ClockBypass_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup SDIO_Clock_Power_Save 
+  * @{
+  */
+
+#define SDIO_ClockPowerSave_Disable         ((uint32_t)0x00000000)
+#define SDIO_ClockPowerSave_Enable          ((uint32_t)0x00000200) 
+#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \
+                                        ((SAVE) == SDIO_ClockPowerSave_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Bus_Wide 
+  * @{
+  */
+
+#define SDIO_BusWide_1b                     ((uint32_t)0x00000000)
+#define SDIO_BusWide_4b                     ((uint32_t)0x00000800)
+#define SDIO_BusWide_8b                     ((uint32_t)0x00001000)
+#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \
+                                ((WIDE) == SDIO_BusWide_8b))
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Hardware_Flow_Control 
+  * @{
+  */
+
+#define SDIO_HardwareFlowControl_Disable    ((uint32_t)0x00000000)
+#define SDIO_HardwareFlowControl_Enable     ((uint32_t)0x00004000)
+#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \
+                                                ((CONTROL) == SDIO_HardwareFlowControl_Enable))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Power_State 
+  * @{
+  */
+
+#define SDIO_PowerState_OFF                 ((uint32_t)0x00000000)
+#define SDIO_PowerState_ON                  ((uint32_t)0x00000003)
+#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup SDIO_Interrupt_sources
+  * @{
+  */
+
+#define SDIO_IT_CCRCFAIL                    ((uint32_t)0x00000001)
+#define SDIO_IT_DCRCFAIL                    ((uint32_t)0x00000002)
+#define SDIO_IT_CTIMEOUT                    ((uint32_t)0x00000004)
+#define SDIO_IT_DTIMEOUT                    ((uint32_t)0x00000008)
+#define SDIO_IT_TXUNDERR                    ((uint32_t)0x00000010)
+#define SDIO_IT_RXOVERR                     ((uint32_t)0x00000020)
+#define SDIO_IT_CMDREND                     ((uint32_t)0x00000040)
+#define SDIO_IT_CMDSENT                     ((uint32_t)0x00000080)
+#define SDIO_IT_DATAEND                     ((uint32_t)0x00000100)
+#define SDIO_IT_STBITERR                    ((uint32_t)0x00000200)
+#define SDIO_IT_DBCKEND                     ((uint32_t)0x00000400)
+#define SDIO_IT_CMDACT                      ((uint32_t)0x00000800)
+#define SDIO_IT_TXACT                       ((uint32_t)0x00001000)
+#define SDIO_IT_RXACT                       ((uint32_t)0x00002000)
+#define SDIO_IT_TXFIFOHE                    ((uint32_t)0x00004000)
+#define SDIO_IT_RXFIFOHF                    ((uint32_t)0x00008000)
+#define SDIO_IT_TXFIFOF                     ((uint32_t)0x00010000)
+#define SDIO_IT_RXFIFOF                     ((uint32_t)0x00020000)
+#define SDIO_IT_TXFIFOE                     ((uint32_t)0x00040000)
+#define SDIO_IT_RXFIFOE                     ((uint32_t)0x00080000)
+#define SDIO_IT_TXDAVL                      ((uint32_t)0x00100000)
+#define SDIO_IT_RXDAVL                      ((uint32_t)0x00200000)
+#define SDIO_IT_SDIOIT                      ((uint32_t)0x00400000)
+#define SDIO_IT_CEATAEND                    ((uint32_t)0x00800000)
+#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup SDIO_Command_Index
+  * @{
+  */
+
+#define IS_SDIO_CMD_INDEX(INDEX)            ((INDEX) < 0x40)
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Response_Type
+  * @{
+  */
+
+#define SDIO_Response_No                    ((uint32_t)0x00000000)
+#define SDIO_Response_Short                 ((uint32_t)0x00000040)
+#define SDIO_Response_Long                  ((uint32_t)0x000000C0)
+#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \
+                                    ((RESPONSE) == SDIO_Response_Short) || \
+                                    ((RESPONSE) == SDIO_Response_Long))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Wait_Interrupt_State
+  * @{
+  */
+
+#define SDIO_Wait_No                        ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */
+#define SDIO_Wait_IT                        ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */
+#define SDIO_Wait_Pend                      ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */
+#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \
+                            ((WAIT) == SDIO_Wait_Pend))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_CPSM_State
+  * @{
+  */
+
+#define SDIO_CPSM_Disable                    ((uint32_t)0x00000000)
+#define SDIO_CPSM_Enable                     ((uint32_t)0x00000400)
+#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup SDIO_Response_Registers
+  * @{
+  */
+
+#define SDIO_RESP1                          ((uint32_t)0x00000000)
+#define SDIO_RESP2                          ((uint32_t)0x00000004)
+#define SDIO_RESP3                          ((uint32_t)0x00000008)
+#define SDIO_RESP4                          ((uint32_t)0x0000000C)
+#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \
+                            ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Data_Length 
+  * @{
+  */
+
+#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF)
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Data_Block_Size 
+  * @{
+  */
+
+#define SDIO_DataBlockSize_1b               ((uint32_t)0x00000000)
+#define SDIO_DataBlockSize_2b               ((uint32_t)0x00000010)
+#define SDIO_DataBlockSize_4b               ((uint32_t)0x00000020)
+#define SDIO_DataBlockSize_8b               ((uint32_t)0x00000030)
+#define SDIO_DataBlockSize_16b              ((uint32_t)0x00000040)
+#define SDIO_DataBlockSize_32b              ((uint32_t)0x00000050)
+#define SDIO_DataBlockSize_64b              ((uint32_t)0x00000060)
+#define SDIO_DataBlockSize_128b             ((uint32_t)0x00000070)
+#define SDIO_DataBlockSize_256b             ((uint32_t)0x00000080)
+#define SDIO_DataBlockSize_512b             ((uint32_t)0x00000090)
+#define SDIO_DataBlockSize_1024b            ((uint32_t)0x000000A0)
+#define SDIO_DataBlockSize_2048b            ((uint32_t)0x000000B0)
+#define SDIO_DataBlockSize_4096b            ((uint32_t)0x000000C0)
+#define SDIO_DataBlockSize_8192b            ((uint32_t)0x000000D0)
+#define SDIO_DataBlockSize_16384b           ((uint32_t)0x000000E0)
+#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_2b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_4b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_8b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_16b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_32b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_64b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_128b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_256b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_512b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_1024b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_2048b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_4096b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_8192b) || \
+                                  ((SIZE) == SDIO_DataBlockSize_16384b)) 
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Transfer_Direction 
+  * @{
+  */
+
+#define SDIO_TransferDir_ToCard             ((uint32_t)0x00000000)
+#define SDIO_TransferDir_ToSDIO             ((uint32_t)0x00000002)
+#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \
+                                   ((DIR) == SDIO_TransferDir_ToSDIO))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Transfer_Type 
+  * @{
+  */
+
+#define SDIO_TransferMode_Block             ((uint32_t)0x00000000)
+#define SDIO_TransferMode_Stream            ((uint32_t)0x00000004)
+#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \
+                                     ((MODE) == SDIO_TransferMode_Block))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_DPSM_State 
+  * @{
+  */
+
+#define SDIO_DPSM_Disable                    ((uint32_t)0x00000000)
+#define SDIO_DPSM_Enable                     ((uint32_t)0x00000001)
+#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Flags 
+  * @{
+  */
+
+#define SDIO_FLAG_CCRCFAIL                  ((uint32_t)0x00000001)
+#define SDIO_FLAG_DCRCFAIL                  ((uint32_t)0x00000002)
+#define SDIO_FLAG_CTIMEOUT                  ((uint32_t)0x00000004)
+#define SDIO_FLAG_DTIMEOUT                  ((uint32_t)0x00000008)
+#define SDIO_FLAG_TXUNDERR                  ((uint32_t)0x00000010)
+#define SDIO_FLAG_RXOVERR                   ((uint32_t)0x00000020)
+#define SDIO_FLAG_CMDREND                   ((uint32_t)0x00000040)
+#define SDIO_FLAG_CMDSENT                   ((uint32_t)0x00000080)
+#define SDIO_FLAG_DATAEND                   ((uint32_t)0x00000100)
+#define SDIO_FLAG_STBITERR                  ((uint32_t)0x00000200)
+#define SDIO_FLAG_DBCKEND                   ((uint32_t)0x00000400)
+#define SDIO_FLAG_CMDACT                    ((uint32_t)0x00000800)
+#define SDIO_FLAG_TXACT                     ((uint32_t)0x00001000)
+#define SDIO_FLAG_RXACT                     ((uint32_t)0x00002000)
+#define SDIO_FLAG_TXFIFOHE                  ((uint32_t)0x00004000)
+#define SDIO_FLAG_RXFIFOHF                  ((uint32_t)0x00008000)
+#define SDIO_FLAG_TXFIFOF                   ((uint32_t)0x00010000)
+#define SDIO_FLAG_RXFIFOF                   ((uint32_t)0x00020000)
+#define SDIO_FLAG_TXFIFOE                   ((uint32_t)0x00040000)
+#define SDIO_FLAG_RXFIFOE                   ((uint32_t)0x00080000)
+#define SDIO_FLAG_TXDAVL                    ((uint32_t)0x00100000)
+#define SDIO_FLAG_RXDAVL                    ((uint32_t)0x00200000)
+#define SDIO_FLAG_SDIOIT                    ((uint32_t)0x00400000)
+#define SDIO_FLAG_CEATAEND                  ((uint32_t)0x00800000)
+#define IS_SDIO_FLAG(FLAG) (((FLAG)  == SDIO_FLAG_CCRCFAIL) || \
+                            ((FLAG)  == SDIO_FLAG_DCRCFAIL) || \
+                            ((FLAG)  == SDIO_FLAG_CTIMEOUT) || \
+                            ((FLAG)  == SDIO_FLAG_DTIMEOUT) || \
+                            ((FLAG)  == SDIO_FLAG_TXUNDERR) || \
+                            ((FLAG)  == SDIO_FLAG_RXOVERR) || \
+                            ((FLAG)  == SDIO_FLAG_CMDREND) || \
+                            ((FLAG)  == SDIO_FLAG_CMDSENT) || \
+                            ((FLAG)  == SDIO_FLAG_DATAEND) || \
+                            ((FLAG)  == SDIO_FLAG_STBITERR) || \
+                            ((FLAG)  == SDIO_FLAG_DBCKEND) || \
+                            ((FLAG)  == SDIO_FLAG_CMDACT) || \
+                            ((FLAG)  == SDIO_FLAG_TXACT) || \
+                            ((FLAG)  == SDIO_FLAG_RXACT) || \
+                            ((FLAG)  == SDIO_FLAG_TXFIFOHE) || \
+                            ((FLAG)  == SDIO_FLAG_RXFIFOHF) || \
+                            ((FLAG)  == SDIO_FLAG_TXFIFOF) || \
+                            ((FLAG)  == SDIO_FLAG_RXFIFOF) || \
+                            ((FLAG)  == SDIO_FLAG_TXFIFOE) || \
+                            ((FLAG)  == SDIO_FLAG_RXFIFOE) || \
+                            ((FLAG)  == SDIO_FLAG_TXDAVL) || \
+                            ((FLAG)  == SDIO_FLAG_RXDAVL) || \
+                            ((FLAG)  == SDIO_FLAG_SDIOIT) || \
+                            ((FLAG)  == SDIO_FLAG_CEATAEND))
+
+#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00))
+
+#define IS_SDIO_GET_IT(IT) (((IT)  == SDIO_IT_CCRCFAIL) || \
+                            ((IT)  == SDIO_IT_DCRCFAIL) || \
+                            ((IT)  == SDIO_IT_CTIMEOUT) || \
+                            ((IT)  == SDIO_IT_DTIMEOUT) || \
+                            ((IT)  == SDIO_IT_TXUNDERR) || \
+                            ((IT)  == SDIO_IT_RXOVERR) || \
+                            ((IT)  == SDIO_IT_CMDREND) || \
+                            ((IT)  == SDIO_IT_CMDSENT) || \
+                            ((IT)  == SDIO_IT_DATAEND) || \
+                            ((IT)  == SDIO_IT_STBITERR) || \
+                            ((IT)  == SDIO_IT_DBCKEND) || \
+                            ((IT)  == SDIO_IT_CMDACT) || \
+                            ((IT)  == SDIO_IT_TXACT) || \
+                            ((IT)  == SDIO_IT_RXACT) || \
+                            ((IT)  == SDIO_IT_TXFIFOHE) || \
+                            ((IT)  == SDIO_IT_RXFIFOHF) || \
+                            ((IT)  == SDIO_IT_TXFIFOF) || \
+                            ((IT)  == SDIO_IT_RXFIFOF) || \
+                            ((IT)  == SDIO_IT_TXFIFOE) || \
+                            ((IT)  == SDIO_IT_RXFIFOE) || \
+                            ((IT)  == SDIO_IT_TXDAVL) || \
+                            ((IT)  == SDIO_IT_RXDAVL) || \
+                            ((IT)  == SDIO_IT_SDIOIT) || \
+                            ((IT)  == SDIO_IT_CEATAEND))
+
+#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00))
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Read_Wait_Mode 
+  * @{
+  */
+
+#define SDIO_ReadWaitMode_DATA2             ((uint32_t)0x00000000)
+#define SDIO_ReadWaitMode_CLK               ((uint32_t)0x00000001)
+#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \
+                                     ((MODE) == SDIO_ReadWaitMode_DATA2))
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+/*  Function used to set the SDIO configuration to the default reset state ****/
+void SDIO_DeInit(void);
+
+/* Initialization and Configuration functions *********************************/
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct);
+void SDIO_ClockCmd(FunctionalState NewState);
+void SDIO_SetPowerState(uint32_t SDIO_PowerState);
+uint32_t SDIO_GetPowerState(void);
+
+/* Command path state machine (CPSM) management functions *********************/
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct);
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct);
+uint8_t SDIO_GetCommandResponse(void);
+uint32_t SDIO_GetResponse(uint32_t SDIO_RESP);
+
+/* Data path state machine (DPSM) management functions ************************/
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct);
+uint32_t SDIO_GetDataCounter(void);
+uint32_t SDIO_ReadData(void);
+void SDIO_WriteData(uint32_t Data);
+uint32_t SDIO_GetFIFOCount(void);
+
+/* SDIO IO Cards mode management functions ************************************/
+void SDIO_StartSDIOReadWait(FunctionalState NewState);
+void SDIO_StopSDIOReadWait(FunctionalState NewState);
+void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode);
+void SDIO_SetSDIOOperation(FunctionalState NewState);
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState);
+
+/* CE-ATA mode management functions *******************************************/
+void SDIO_CommandCompletionCmd(FunctionalState NewState);
+void SDIO_CEATAITCmd(FunctionalState NewState);
+void SDIO_SendCEATACmd(FunctionalState NewState);
+
+/* DMA transfers management functions *****************************************/
+void SDIO_DMACmd(FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState);
+FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG);
+void SDIO_ClearFlag(uint32_t SDIO_FLAG);
+ITStatus SDIO_GetITStatus(uint32_t SDIO_IT);
+void SDIO_ClearITPendingBit(uint32_t SDIO_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_SDIO_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h
new file mode 100644
index 0000000000000000000000000000000000000000..7f4834bfdd3093500f4e90a6fb5a4c0ed629a0cf
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_spi.h
@@ -0,0 +1,549 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_spi.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the SPI 
+  *          firmware library. 
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_SPI_H
+#define __STM32F4xx_SPI_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup SPI
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  SPI Init structure definition  
+  */
+
+typedef struct
+{
+  uint16_t SPI_Direction;           /*!< Specifies the SPI unidirectional or bidirectional data mode.
+                                         This parameter can be a value of @ref SPI_data_direction */
+
+  uint16_t SPI_Mode;                /*!< Specifies the SPI operating mode.
+                                         This parameter can be a value of @ref SPI_mode */
+
+  uint16_t SPI_DataSize;            /*!< Specifies the SPI data size.
+                                         This parameter can be a value of @ref SPI_data_size */
+
+  uint16_t SPI_CPOL;                /*!< Specifies the serial clock steady state.
+                                         This parameter can be a value of @ref SPI_Clock_Polarity */
+
+  uint16_t SPI_CPHA;                /*!< Specifies the clock active edge for the bit capture.
+                                         This parameter can be a value of @ref SPI_Clock_Phase */
+
+  uint16_t SPI_NSS;                 /*!< Specifies whether the NSS signal is managed by
+                                         hardware (NSS pin) or by software using the SSI bit.
+                                         This parameter can be a value of @ref SPI_Slave_Select_management */
+ 
+  uint16_t SPI_BaudRatePrescaler;   /*!< Specifies the Baud Rate prescaler value which will be
+                                         used to configure the transmit and receive SCK clock.
+                                         This parameter can be a value of @ref SPI_BaudRate_Prescaler
+                                         @note The communication clock is derived from the master
+                                               clock. The slave clock does not need to be set. */
+
+  uint16_t SPI_FirstBit;            /*!< Specifies whether data transfers start from MSB or LSB bit.
+                                         This parameter can be a value of @ref SPI_MSB_LSB_transmission */
+
+  uint16_t SPI_CRCPolynomial;       /*!< Specifies the polynomial used for the CRC calculation. */
+}SPI_InitTypeDef;
+
+/** 
+  * @brief  I2S Init structure definition  
+  */
+
+typedef struct
+{
+
+  uint16_t I2S_Mode;         /*!< Specifies the I2S operating mode.
+                                  This parameter can be a value of @ref I2S_Mode */
+
+  uint16_t I2S_Standard;     /*!< Specifies the standard used for the I2S communication.
+                                  This parameter can be a value of @ref I2S_Standard */
+
+  uint16_t I2S_DataFormat;   /*!< Specifies the data format for the I2S communication.
+                                  This parameter can be a value of @ref I2S_Data_Format */
+
+  uint16_t I2S_MCLKOutput;   /*!< Specifies whether the I2S MCLK output is enabled or not.
+                                  This parameter can be a value of @ref I2S_MCLK_Output */
+
+  uint32_t I2S_AudioFreq;    /*!< Specifies the frequency selected for the I2S communication.
+                                  This parameter can be a value of @ref I2S_Audio_Frequency */
+
+  uint16_t I2S_CPOL;         /*!< Specifies the idle state of the I2S clock.
+                                  This parameter can be a value of @ref I2S_Clock_Polarity */
+}I2S_InitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup SPI_Exported_Constants
+  * @{
+  */
+
+#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \
+                                   ((PERIPH) == SPI2) || \
+                                   ((PERIPH) == SPI3) || \
+                                   ((PERIPH) == SPI4) || \
+                                   ((PERIPH) == SPI5) || \
+                                   ((PERIPH) == SPI6))
+
+#define IS_SPI_ALL_PERIPH_EXT(PERIPH) (((PERIPH) == SPI1)    || \
+                                       ((PERIPH) == SPI2)    || \
+                                       ((PERIPH) == SPI3)    || \
+                                       ((PERIPH) == SPI4)    || \
+                                       ((PERIPH) == SPI5)    || \
+                                       ((PERIPH) == SPI6)    || \
+                                       ((PERIPH) == I2S2ext) || \
+                                       ((PERIPH) == I2S3ext))
+
+#define IS_SPI_23_PERIPH(PERIPH)  (((PERIPH) == SPI2) || \
+                                   ((PERIPH) == SPI3))
+
+#define IS_SPI_23_PERIPH_EXT(PERIPH)  (((PERIPH) == SPI2)    || \
+                                       ((PERIPH) == SPI3)    || \
+                                       ((PERIPH) == I2S2ext) || \
+                                       ((PERIPH) == I2S3ext))
+
+#define IS_I2S_EXT_PERIPH(PERIPH)  (((PERIPH) == I2S2ext) || \
+                                    ((PERIPH) == I2S3ext))
+
+
+/** @defgroup SPI_data_direction 
+  * @{
+  */
+  
+#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000)
+#define SPI_Direction_2Lines_RxOnly     ((uint16_t)0x0400)
+#define SPI_Direction_1Line_Rx          ((uint16_t)0x8000)
+#define SPI_Direction_1Line_Tx          ((uint16_t)0xC000)
+#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \
+                                     ((MODE) == SPI_Direction_2Lines_RxOnly) || \
+                                     ((MODE) == SPI_Direction_1Line_Rx) || \
+                                     ((MODE) == SPI_Direction_1Line_Tx))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_mode 
+  * @{
+  */
+
+#define SPI_Mode_Master                 ((uint16_t)0x0104)
+#define SPI_Mode_Slave                  ((uint16_t)0x0000)
+#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \
+                           ((MODE) == SPI_Mode_Slave))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_data_size 
+  * @{
+  */
+
+#define SPI_DataSize_16b                ((uint16_t)0x0800)
+#define SPI_DataSize_8b                 ((uint16_t)0x0000)
+#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \
+                                   ((DATASIZE) == SPI_DataSize_8b))
+/**
+  * @}
+  */ 
+
+/** @defgroup SPI_Clock_Polarity 
+  * @{
+  */
+
+#define SPI_CPOL_Low                    ((uint16_t)0x0000)
+#define SPI_CPOL_High                   ((uint16_t)0x0002)
+#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \
+                           ((CPOL) == SPI_CPOL_High))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Clock_Phase 
+  * @{
+  */
+
+#define SPI_CPHA_1Edge                  ((uint16_t)0x0000)
+#define SPI_CPHA_2Edge                  ((uint16_t)0x0001)
+#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \
+                           ((CPHA) == SPI_CPHA_2Edge))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Slave_Select_management 
+  * @{
+  */
+
+#define SPI_NSS_Soft                    ((uint16_t)0x0200)
+#define SPI_NSS_Hard                    ((uint16_t)0x0000)
+#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \
+                         ((NSS) == SPI_NSS_Hard))
+/**
+  * @}
+  */ 
+
+/** @defgroup SPI_BaudRate_Prescaler 
+  * @{
+  */
+
+#define SPI_BaudRatePrescaler_2         ((uint16_t)0x0000)
+#define SPI_BaudRatePrescaler_4         ((uint16_t)0x0008)
+#define SPI_BaudRatePrescaler_8         ((uint16_t)0x0010)
+#define SPI_BaudRatePrescaler_16        ((uint16_t)0x0018)
+#define SPI_BaudRatePrescaler_32        ((uint16_t)0x0020)
+#define SPI_BaudRatePrescaler_64        ((uint16_t)0x0028)
+#define SPI_BaudRatePrescaler_128       ((uint16_t)0x0030)
+#define SPI_BaudRatePrescaler_256       ((uint16_t)0x0038)
+#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_4) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_8) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_16) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_32) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_64) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_128) || \
+                                              ((PRESCALER) == SPI_BaudRatePrescaler_256))
+/**
+  * @}
+  */ 
+
+/** @defgroup SPI_MSB_LSB_transmission 
+  * @{
+  */
+
+#define SPI_FirstBit_MSB                ((uint16_t)0x0000)
+#define SPI_FirstBit_LSB                ((uint16_t)0x0080)
+#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \
+                               ((BIT) == SPI_FirstBit_LSB))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_Mode 
+  * @{
+  */
+
+#define I2S_Mode_SlaveTx                ((uint16_t)0x0000)
+#define I2S_Mode_SlaveRx                ((uint16_t)0x0100)
+#define I2S_Mode_MasterTx               ((uint16_t)0x0200)
+#define I2S_Mode_MasterRx               ((uint16_t)0x0300)
+#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \
+                           ((MODE) == I2S_Mode_SlaveRx) || \
+                           ((MODE) == I2S_Mode_MasterTx)|| \
+                           ((MODE) == I2S_Mode_MasterRx))
+/**
+  * @}
+  */
+  
+
+/** @defgroup SPI_I2S_Standard 
+  * @{
+  */
+
+#define I2S_Standard_Phillips           ((uint16_t)0x0000)
+#define I2S_Standard_MSB                ((uint16_t)0x0010)
+#define I2S_Standard_LSB                ((uint16_t)0x0020)
+#define I2S_Standard_PCMShort           ((uint16_t)0x0030)
+#define I2S_Standard_PCMLong            ((uint16_t)0x00B0)
+#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \
+                                   ((STANDARD) == I2S_Standard_MSB) || \
+                                   ((STANDARD) == I2S_Standard_LSB) || \
+                                   ((STANDARD) == I2S_Standard_PCMShort) || \
+                                   ((STANDARD) == I2S_Standard_PCMLong))
+/**
+  * @}
+  */
+  
+/** @defgroup SPI_I2S_Data_Format 
+  * @{
+  */
+
+#define I2S_DataFormat_16b              ((uint16_t)0x0000)
+#define I2S_DataFormat_16bextended      ((uint16_t)0x0001)
+#define I2S_DataFormat_24b              ((uint16_t)0x0003)
+#define I2S_DataFormat_32b              ((uint16_t)0x0005)
+#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \
+                                    ((FORMAT) == I2S_DataFormat_16bextended) || \
+                                    ((FORMAT) == I2S_DataFormat_24b) || \
+                                    ((FORMAT) == I2S_DataFormat_32b))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_MCLK_Output 
+  * @{
+  */
+
+#define I2S_MCLKOutput_Enable           ((uint16_t)0x0200)
+#define I2S_MCLKOutput_Disable          ((uint16_t)0x0000)
+#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \
+                                    ((OUTPUT) == I2S_MCLKOutput_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_Audio_Frequency 
+  * @{
+  */
+
+#define I2S_AudioFreq_192k               ((uint32_t)192000)
+#define I2S_AudioFreq_96k                ((uint32_t)96000)
+#define I2S_AudioFreq_48k                ((uint32_t)48000)
+#define I2S_AudioFreq_44k                ((uint32_t)44100)
+#define I2S_AudioFreq_32k                ((uint32_t)32000)
+#define I2S_AudioFreq_22k                ((uint32_t)22050)
+#define I2S_AudioFreq_16k                ((uint32_t)16000)
+#define I2S_AudioFreq_11k                ((uint32_t)11025)
+#define I2S_AudioFreq_8k                 ((uint32_t)8000)
+#define I2S_AudioFreq_Default            ((uint32_t)2)
+
+#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \
+                                 ((FREQ) <= I2S_AudioFreq_192k)) || \
+                                 ((FREQ) == I2S_AudioFreq_Default))
+/**
+  * @}
+  */
+            
+/** @defgroup SPI_I2S_Clock_Polarity 
+  * @{
+  */
+
+#define I2S_CPOL_Low                    ((uint16_t)0x0000)
+#define I2S_CPOL_High                   ((uint16_t)0x0008)
+#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \
+                           ((CPOL) == I2S_CPOL_High))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_DMA_transfer_requests 
+  * @{
+  */
+
+#define SPI_I2S_DMAReq_Tx               ((uint16_t)0x0002)
+#define SPI_I2S_DMAReq_Rx               ((uint16_t)0x0001)
+#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_NSS_internal_software_management 
+  * @{
+  */
+
+#define SPI_NSSInternalSoft_Set         ((uint16_t)0x0100)
+#define SPI_NSSInternalSoft_Reset       ((uint16_t)0xFEFF)
+#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \
+                                       ((INTERNAL) == SPI_NSSInternalSoft_Reset))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_CRC_Transmit_Receive 
+  * @{
+  */
+
+#define SPI_CRC_Tx                      ((uint8_t)0x00)
+#define SPI_CRC_Rx                      ((uint8_t)0x01)
+#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_direction_transmit_receive 
+  * @{
+  */
+
+#define SPI_Direction_Rx                ((uint16_t)0xBFFF)
+#define SPI_Direction_Tx                ((uint16_t)0x4000)
+#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \
+                                     ((DIRECTION) == SPI_Direction_Tx))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_interrupts_definition 
+  * @{
+  */
+
+#define SPI_I2S_IT_TXE                  ((uint8_t)0x71)
+#define SPI_I2S_IT_RXNE                 ((uint8_t)0x60)
+#define SPI_I2S_IT_ERR                  ((uint8_t)0x50)
+#define I2S_IT_UDR                      ((uint8_t)0x53)
+#define SPI_I2S_IT_TIFRFE               ((uint8_t)0x58)
+
+#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \
+                                  ((IT) == SPI_I2S_IT_RXNE) || \
+                                  ((IT) == SPI_I2S_IT_ERR))
+
+#define SPI_I2S_IT_OVR                  ((uint8_t)0x56)
+#define SPI_IT_MODF                     ((uint8_t)0x55)
+#define SPI_IT_CRCERR                   ((uint8_t)0x54)
+
+#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR))
+
+#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE)|| ((IT) == SPI_I2S_IT_TXE) || \
+                               ((IT) == SPI_IT_CRCERR)  || ((IT) == SPI_IT_MODF) || \
+                               ((IT) == SPI_I2S_IT_OVR) || ((IT) == I2S_IT_UDR) ||\
+                               ((IT) == SPI_I2S_IT_TIFRFE))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_flags_definition 
+  * @{
+  */
+
+#define SPI_I2S_FLAG_RXNE               ((uint16_t)0x0001)
+#define SPI_I2S_FLAG_TXE                ((uint16_t)0x0002)
+#define I2S_FLAG_CHSIDE                 ((uint16_t)0x0004)
+#define I2S_FLAG_UDR                    ((uint16_t)0x0008)
+#define SPI_FLAG_CRCERR                 ((uint16_t)0x0010)
+#define SPI_FLAG_MODF                   ((uint16_t)0x0020)
+#define SPI_I2S_FLAG_OVR                ((uint16_t)0x0040)
+#define SPI_I2S_FLAG_BSY                ((uint16_t)0x0080)
+#define SPI_I2S_FLAG_TIFRFE             ((uint16_t)0x0100)
+
+#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR))
+#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \
+                                   ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \
+                                   ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \
+                                   ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE)|| \
+                                   ((FLAG) == SPI_I2S_FLAG_TIFRFE))
+/**
+  * @}
+  */
+
+/** @defgroup SPI_CRC_polynomial 
+  * @{
+  */
+
+#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1)
+/**
+  * @}
+  */
+
+/** @defgroup SPI_I2S_Legacy 
+  * @{
+  */
+
+#define SPI_DMAReq_Tx                SPI_I2S_DMAReq_Tx
+#define SPI_DMAReq_Rx                SPI_I2S_DMAReq_Rx
+#define SPI_IT_TXE                   SPI_I2S_IT_TXE
+#define SPI_IT_RXNE                  SPI_I2S_IT_RXNE
+#define SPI_IT_ERR                   SPI_I2S_IT_ERR
+#define SPI_IT_OVR                   SPI_I2S_IT_OVR
+#define SPI_FLAG_RXNE                SPI_I2S_FLAG_RXNE
+#define SPI_FLAG_TXE                 SPI_I2S_FLAG_TXE
+#define SPI_FLAG_OVR                 SPI_I2S_FLAG_OVR
+#define SPI_FLAG_BSY                 SPI_I2S_FLAG_BSY
+#define SPI_DeInit                   SPI_I2S_DeInit
+#define SPI_ITConfig                 SPI_I2S_ITConfig
+#define SPI_DMACmd                   SPI_I2S_DMACmd
+#define SPI_SendData                 SPI_I2S_SendData
+#define SPI_ReceiveData              SPI_I2S_ReceiveData
+#define SPI_GetFlagStatus            SPI_I2S_GetFlagStatus
+#define SPI_ClearFlag                SPI_I2S_ClearFlag
+#define SPI_GetITStatus              SPI_I2S_GetITStatus
+#define SPI_ClearITPendingBit        SPI_I2S_ClearITPendingBit
+/**
+  * @}
+  */
+  
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/*  Function used to set the SPI configuration to the default reset state *****/ 
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx);
+
+/* Initialization and Configuration functions *********************************/
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct);
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct);
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct);
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct);
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize);
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction);
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft);
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState);
+
+void I2S_FullDuplexConfig(SPI_TypeDef* I2Sxext, I2S_InitTypeDef* I2S_InitStruct);
+
+/* Data transfers functions ***************************************************/ 
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data);
+uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx);
+
+/* Hardware CRC Calculation functions *****************************************/
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState);
+void SPI_TransmitCRC(SPI_TypeDef* SPIx);
+uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC);
+uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx);
+
+/* DMA transfers management functions *****************************************/
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState);
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_SPI_H */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h
new file mode 100644
index 0000000000000000000000000000000000000000..7d3cc4288adf949d13d24c14a07c4d71167f329b
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_syscfg.h
@@ -0,0 +1,210 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_syscfg.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the SYSCFG firmware
+  *          library. 
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_SYSCFG_H
+#define __STM32F4xx_SYSCFG_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup SYSCFG
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+  
+/** @defgroup SYSCFG_Exported_Constants 
+  * @{
+  */ 
+
+/** @defgroup SYSCFG_EXTI_Port_Sources 
+  * @{
+  */ 
+#define EXTI_PortSourceGPIOA       ((uint8_t)0x00)
+#define EXTI_PortSourceGPIOB       ((uint8_t)0x01)
+#define EXTI_PortSourceGPIOC       ((uint8_t)0x02)
+#define EXTI_PortSourceGPIOD       ((uint8_t)0x03)
+#define EXTI_PortSourceGPIOE       ((uint8_t)0x04)
+#define EXTI_PortSourceGPIOF       ((uint8_t)0x05)
+#define EXTI_PortSourceGPIOG       ((uint8_t)0x06)
+#define EXTI_PortSourceGPIOH       ((uint8_t)0x07)
+#define EXTI_PortSourceGPIOI       ((uint8_t)0x08)
+#define EXTI_PortSourceGPIOJ       ((uint8_t)0x09)
+#define EXTI_PortSourceGPIOK       ((uint8_t)0x0A)
+
+#define IS_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == EXTI_PortSourceGPIOA) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOB) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOC) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOD) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOE) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOF) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOG) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOH) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOI) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOJ) || \
+                                         ((PORTSOURCE) == EXTI_PortSourceGPIOK))
+                                         
+/**
+  * @}
+  */ 
+
+
+/** @defgroup SYSCFG_EXTI_Pin_Sources 
+  * @{
+  */ 
+#define EXTI_PinSource0            ((uint8_t)0x00)
+#define EXTI_PinSource1            ((uint8_t)0x01)
+#define EXTI_PinSource2            ((uint8_t)0x02)
+#define EXTI_PinSource3            ((uint8_t)0x03)
+#define EXTI_PinSource4            ((uint8_t)0x04)
+#define EXTI_PinSource5            ((uint8_t)0x05)
+#define EXTI_PinSource6            ((uint8_t)0x06)
+#define EXTI_PinSource7            ((uint8_t)0x07)
+#define EXTI_PinSource8            ((uint8_t)0x08)
+#define EXTI_PinSource9            ((uint8_t)0x09)
+#define EXTI_PinSource10           ((uint8_t)0x0A)
+#define EXTI_PinSource11           ((uint8_t)0x0B)
+#define EXTI_PinSource12           ((uint8_t)0x0C)
+#define EXTI_PinSource13           ((uint8_t)0x0D)
+#define EXTI_PinSource14           ((uint8_t)0x0E)
+#define EXTI_PinSource15           ((uint8_t)0x0F)
+#define IS_EXTI_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == EXTI_PinSource0)  || \
+                                       ((PINSOURCE) == EXTI_PinSource1)  || \
+                                       ((PINSOURCE) == EXTI_PinSource2)  || \
+                                       ((PINSOURCE) == EXTI_PinSource3)  || \
+                                       ((PINSOURCE) == EXTI_PinSource4)  || \
+                                       ((PINSOURCE) == EXTI_PinSource5)  || \
+                                       ((PINSOURCE) == EXTI_PinSource6)  || \
+                                       ((PINSOURCE) == EXTI_PinSource7)  || \
+                                       ((PINSOURCE) == EXTI_PinSource8)  || \
+                                       ((PINSOURCE) == EXTI_PinSource9)  || \
+                                       ((PINSOURCE) == EXTI_PinSource10) || \
+                                       ((PINSOURCE) == EXTI_PinSource11) || \
+                                       ((PINSOURCE) == EXTI_PinSource12) || \
+                                       ((PINSOURCE) == EXTI_PinSource13) || \
+                                       ((PINSOURCE) == EXTI_PinSource14) || \
+                                       ((PINSOURCE) == EXTI_PinSource15))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup SYSCFG_Memory_Remap_Config 
+  * @{
+  */ 
+#define SYSCFG_MemoryRemap_Flash       ((uint8_t)0x00)
+#define SYSCFG_MemoryRemap_SystemFlash ((uint8_t)0x01)
+#define SYSCFG_MemoryRemap_SRAM        ((uint8_t)0x03)
+#define SYSCFG_MemoryRemap_SDRAM       ((uint8_t)0x04)
+
+#if defined (STM32F40_41xxx)
+#define SYSCFG_MemoryRemap_FSMC        ((uint8_t)0x02) 
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define SYSCFG_MemoryRemap_FMC         ((uint8_t)0x02) 
+#endif /* STM32F427_437xx ||  STM32F429_439xx */  
+
+#if defined (STM32F40_41xxx) 
+#define IS_SYSCFG_MEMORY_REMAP_CONFING(REMAP) (((REMAP) == SYSCFG_MemoryRemap_Flash)       || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_SystemFlash) || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_SRAM)        || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_FSMC))
+#endif /* STM32F40_41xxx */
+
+#if defined (STM32F401xx) 
+#define IS_SYSCFG_MEMORY_REMAP_CONFING(REMAP) (((REMAP) == SYSCFG_MemoryRemap_Flash)       || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_SystemFlash) || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_SRAM))
+#endif /* STM32F401xx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+#define IS_SYSCFG_MEMORY_REMAP_CONFING(REMAP) (((REMAP) == SYSCFG_MemoryRemap_Flash)       || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_SystemFlash) || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_SRAM)        || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_SDRAM)       || \
+                                               ((REMAP) == SYSCFG_MemoryRemap_FMC))
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+                                                                                              
+/**
+  * @}
+  */ 
+
+
+/** @defgroup SYSCFG_ETHERNET_Media_Interface 
+  * @{
+  */ 
+#define SYSCFG_ETH_MediaInterface_MII    ((uint32_t)0x00000000)
+#define SYSCFG_ETH_MediaInterface_RMII   ((uint32_t)0x00000001)
+
+#define IS_SYSCFG_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == SYSCFG_ETH_MediaInterface_MII) || \
+                                                 ((INTERFACE) == SYSCFG_ETH_MediaInterface_RMII))
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+ 
+void SYSCFG_DeInit(void);
+void       SYSCFG_MemoryRemapConfig(uint8_t SYSCFG_MemoryRemap);
+void       SYSCFG_MemorySwappingBank(FunctionalState NewState);
+void       SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex);
+void       SYSCFG_ETH_MediaInterfaceConfig(uint32_t SYSCFG_ETH_MediaInterface); 
+void       SYSCFG_CompensationCellCmd(FunctionalState NewState); 
+FlagStatus SYSCFG_GetCompensationCellStatus(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_SYSCFG_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h
new file mode 100644
index 0000000000000000000000000000000000000000..7983cc024a441d9a773c6ea069318212cb0dae4f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_tim.h
@@ -0,0 +1,1150 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_tim.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the TIM firmware 
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_TIM_H
+#define __STM32F4xx_TIM_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup TIM
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+
+/** 
+  * @brief  TIM Time Base Init structure definition  
+  * @note   This structure is used with all TIMx except for TIM6 and TIM7.  
+  */
+
+typedef struct
+{
+  uint16_t TIM_Prescaler;         /*!< Specifies the prescaler value used to divide the TIM clock.
+                                       This parameter can be a number between 0x0000 and 0xFFFF */
+
+  uint16_t TIM_CounterMode;       /*!< Specifies the counter mode.
+                                       This parameter can be a value of @ref TIM_Counter_Mode */
+
+  uint32_t TIM_Period;            /*!< Specifies the period value to be loaded into the active
+                                       Auto-Reload Register at the next update event.
+                                       This parameter must be a number between 0x0000 and 0xFFFF.  */ 
+
+  uint16_t TIM_ClockDivision;     /*!< Specifies the clock division.
+                                      This parameter can be a value of @ref TIM_Clock_Division_CKD */
+
+  uint8_t TIM_RepetitionCounter;  /*!< Specifies the repetition counter value. Each time the RCR downcounter
+                                       reaches zero, an update event is generated and counting restarts
+                                       from the RCR value (N).
+                                       This means in PWM mode that (N+1) corresponds to:
+                                          - the number of PWM periods in edge-aligned mode
+                                          - the number of half PWM period in center-aligned mode
+                                       This parameter must be a number between 0x00 and 0xFF. 
+                                       @note This parameter is valid only for TIM1 and TIM8. */
+} TIM_TimeBaseInitTypeDef; 
+
+/** 
+  * @brief  TIM Output Compare Init structure definition  
+  */
+
+typedef struct
+{
+  uint16_t TIM_OCMode;        /*!< Specifies the TIM mode.
+                                   This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */
+
+  uint16_t TIM_OutputState;   /*!< Specifies the TIM Output Compare state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_State */
+
+  uint16_t TIM_OutputNState;  /*!< Specifies the TIM complementary Output Compare state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_N_State
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+
+  uint32_t TIM_Pulse;         /*!< Specifies the pulse value to be loaded into the Capture Compare Register. 
+                                   This parameter can be a number between 0x0000 and 0xFFFF */
+
+  uint16_t TIM_OCPolarity;    /*!< Specifies the output polarity.
+                                   This parameter can be a value of @ref TIM_Output_Compare_Polarity */
+
+  uint16_t TIM_OCNPolarity;   /*!< Specifies the complementary output polarity.
+                                   This parameter can be a value of @ref TIM_Output_Compare_N_Polarity
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+
+  uint16_t TIM_OCIdleState;   /*!< Specifies the TIM Output Compare pin state during Idle state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_Idle_State
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+
+  uint16_t TIM_OCNIdleState;  /*!< Specifies the TIM Output Compare pin state during Idle state.
+                                   This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State
+                                   @note This parameter is valid only for TIM1 and TIM8. */
+} TIM_OCInitTypeDef;
+
+/** 
+  * @brief  TIM Input Capture Init structure definition  
+  */
+
+typedef struct
+{
+
+  uint16_t TIM_Channel;      /*!< Specifies the TIM channel.
+                                  This parameter can be a value of @ref TIM_Channel */
+
+  uint16_t TIM_ICPolarity;   /*!< Specifies the active edge of the input signal.
+                                  This parameter can be a value of @ref TIM_Input_Capture_Polarity */
+
+  uint16_t TIM_ICSelection;  /*!< Specifies the input.
+                                  This parameter can be a value of @ref TIM_Input_Capture_Selection */
+
+  uint16_t TIM_ICPrescaler;  /*!< Specifies the Input Capture Prescaler.
+                                  This parameter can be a value of @ref TIM_Input_Capture_Prescaler */
+
+  uint16_t TIM_ICFilter;     /*!< Specifies the input capture filter.
+                                  This parameter can be a number between 0x0 and 0xF */
+} TIM_ICInitTypeDef;
+
+/** 
+  * @brief  BDTR structure definition 
+  * @note   This structure is used only with TIM1 and TIM8.    
+  */
+
+typedef struct
+{
+
+  uint16_t TIM_OSSRState;        /*!< Specifies the Off-State selection used in Run mode.
+                                      This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */
+
+  uint16_t TIM_OSSIState;        /*!< Specifies the Off-State used in Idle state.
+                                      This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */
+
+  uint16_t TIM_LOCKLevel;        /*!< Specifies the LOCK level parameters.
+                                      This parameter can be a value of @ref TIM_Lock_level */ 
+
+  uint16_t TIM_DeadTime;         /*!< Specifies the delay time between the switching-off and the
+                                      switching-on of the outputs.
+                                      This parameter can be a number between 0x00 and 0xFF  */
+
+  uint16_t TIM_Break;            /*!< Specifies whether the TIM Break input is enabled or not. 
+                                      This parameter can be a value of @ref TIM_Break_Input_enable_disable */
+
+  uint16_t TIM_BreakPolarity;    /*!< Specifies the TIM Break Input pin polarity.
+                                      This parameter can be a value of @ref TIM_Break_Polarity */
+
+  uint16_t TIM_AutomaticOutput;  /*!< Specifies whether the TIM Automatic Output feature is enabled or not. 
+                                      This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */
+} TIM_BDTRInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup TIM_Exported_constants 
+  * @{
+  */
+
+#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                   ((PERIPH) == TIM2) || \
+                                   ((PERIPH) == TIM3) || \
+                                   ((PERIPH) == TIM4) || \
+                                   ((PERIPH) == TIM5) || \
+                                   ((PERIPH) == TIM6) || \
+                                   ((PERIPH) == TIM7) || \
+                                   ((PERIPH) == TIM8) || \
+                                   ((PERIPH) == TIM9) || \
+                                   ((PERIPH) == TIM10) || \
+                                   ((PERIPH) == TIM11) || \
+                                   ((PERIPH) == TIM12) || \
+                                   (((PERIPH) == TIM13) || \
+                                   ((PERIPH) == TIM14)))
+/* LIST1: TIM1, TIM2, TIM3, TIM4, TIM5, TIM8, TIM9, TIM10, TIM11, TIM12, TIM13 and TIM14 */                                         
+#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                     ((PERIPH) == TIM2) || \
+                                     ((PERIPH) == TIM3) || \
+                                     ((PERIPH) == TIM4) || \
+                                     ((PERIPH) == TIM5) || \
+                                     ((PERIPH) == TIM8) || \
+                                     ((PERIPH) == TIM9) || \
+                                     ((PERIPH) == TIM10) || \
+                                     ((PERIPH) == TIM11) || \
+                                     ((PERIPH) == TIM12) || \
+                                     ((PERIPH) == TIM13) || \
+                                     ((PERIPH) == TIM14))
+                                     
+/* LIST2: TIM1, TIM2, TIM3, TIM4, TIM5, TIM8, TIM9 and TIM12 */
+#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                     ((PERIPH) == TIM2) || \
+                                     ((PERIPH) == TIM3) || \
+                                     ((PERIPH) == TIM4) || \
+                                     ((PERIPH) == TIM5) || \
+                                     ((PERIPH) == TIM8) || \
+                                     ((PERIPH) == TIM9) || \
+                                     ((PERIPH) == TIM12))
+/* LIST3: TIM1, TIM2, TIM3, TIM4, TIM5 and TIM8 */
+#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                     ((PERIPH) == TIM2) || \
+                                     ((PERIPH) == TIM3) || \
+                                     ((PERIPH) == TIM4) || \
+                                     ((PERIPH) == TIM5) || \
+                                     ((PERIPH) == TIM8))
+/* LIST4: TIM1 and TIM8 */
+#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                     ((PERIPH) == TIM8))
+/* LIST5: TIM1, TIM2, TIM3, TIM4, TIM5, TIM6, TIM7 and TIM8 */
+#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \
+                                     ((PERIPH) == TIM2) || \
+                                     ((PERIPH) == TIM3) || \
+                                     ((PERIPH) == TIM4) || \
+                                     ((PERIPH) == TIM5) || \
+                                     ((PERIPH) == TIM6) || \
+                                     ((PERIPH) == TIM7) || \
+                                     ((PERIPH) == TIM8))
+/* LIST6: TIM2, TIM5 and TIM11 */                               
+#define IS_TIM_LIST6_PERIPH(TIMx)(((TIMx) == TIM2) || \
+                                 ((TIMx) == TIM5) || \
+                                 ((TIMx) == TIM11))
+
+/** @defgroup TIM_Output_Compare_and_PWM_modes 
+  * @{
+  */
+
+#define TIM_OCMode_Timing                  ((uint16_t)0x0000)
+#define TIM_OCMode_Active                  ((uint16_t)0x0010)
+#define TIM_OCMode_Inactive                ((uint16_t)0x0020)
+#define TIM_OCMode_Toggle                  ((uint16_t)0x0030)
+#define TIM_OCMode_PWM1                    ((uint16_t)0x0060)
+#define TIM_OCMode_PWM2                    ((uint16_t)0x0070)
+#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \
+                              ((MODE) == TIM_OCMode_Active) || \
+                              ((MODE) == TIM_OCMode_Inactive) || \
+                              ((MODE) == TIM_OCMode_Toggle)|| \
+                              ((MODE) == TIM_OCMode_PWM1) || \
+                              ((MODE) == TIM_OCMode_PWM2))
+#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \
+                          ((MODE) == TIM_OCMode_Active) || \
+                          ((MODE) == TIM_OCMode_Inactive) || \
+                          ((MODE) == TIM_OCMode_Toggle)|| \
+                          ((MODE) == TIM_OCMode_PWM1) || \
+                          ((MODE) == TIM_OCMode_PWM2) ||	\
+                          ((MODE) == TIM_ForcedAction_Active) || \
+                          ((MODE) == TIM_ForcedAction_InActive))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_One_Pulse_Mode 
+  * @{
+  */
+
+#define TIM_OPMode_Single                  ((uint16_t)0x0008)
+#define TIM_OPMode_Repetitive              ((uint16_t)0x0000)
+#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \
+                               ((MODE) == TIM_OPMode_Repetitive))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Channel 
+  * @{
+  */
+
+#define TIM_Channel_1                      ((uint16_t)0x0000)
+#define TIM_Channel_2                      ((uint16_t)0x0004)
+#define TIM_Channel_3                      ((uint16_t)0x0008)
+#define TIM_Channel_4                      ((uint16_t)0x000C)
+                                 
+#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+                                 ((CHANNEL) == TIM_Channel_2) || \
+                                 ((CHANNEL) == TIM_Channel_3) || \
+                                 ((CHANNEL) == TIM_Channel_4))
+                                 
+#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+                                      ((CHANNEL) == TIM_Channel_2))
+#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \
+                                               ((CHANNEL) == TIM_Channel_2) || \
+                                               ((CHANNEL) == TIM_Channel_3))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Clock_Division_CKD 
+  * @{
+  */
+
+#define TIM_CKD_DIV1                       ((uint16_t)0x0000)
+#define TIM_CKD_DIV2                       ((uint16_t)0x0100)
+#define TIM_CKD_DIV4                       ((uint16_t)0x0200)
+#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \
+                             ((DIV) == TIM_CKD_DIV2) || \
+                             ((DIV) == TIM_CKD_DIV4))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Counter_Mode 
+  * @{
+  */
+
+#define TIM_CounterMode_Up                 ((uint16_t)0x0000)
+#define TIM_CounterMode_Down               ((uint16_t)0x0010)
+#define TIM_CounterMode_CenterAligned1     ((uint16_t)0x0020)
+#define TIM_CounterMode_CenterAligned2     ((uint16_t)0x0040)
+#define TIM_CounterMode_CenterAligned3     ((uint16_t)0x0060)
+#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) ||  \
+                                   ((MODE) == TIM_CounterMode_Down) || \
+                                   ((MODE) == TIM_CounterMode_CenterAligned1) || \
+                                   ((MODE) == TIM_CounterMode_CenterAligned2) || \
+                                   ((MODE) == TIM_CounterMode_CenterAligned3))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_Polarity 
+  * @{
+  */
+
+#define TIM_OCPolarity_High                ((uint16_t)0x0000)
+#define TIM_OCPolarity_Low                 ((uint16_t)0x0002)
+#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \
+                                      ((POLARITY) == TIM_OCPolarity_Low))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Output_Compare_N_Polarity 
+  * @{
+  */
+  
+#define TIM_OCNPolarity_High               ((uint16_t)0x0000)
+#define TIM_OCNPolarity_Low                ((uint16_t)0x0008)
+#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \
+                                       ((POLARITY) == TIM_OCNPolarity_Low))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Output_Compare_State 
+  * @{
+  */
+
+#define TIM_OutputState_Disable            ((uint16_t)0x0000)
+#define TIM_OutputState_Enable             ((uint16_t)0x0001)
+#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \
+                                    ((STATE) == TIM_OutputState_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_N_State
+  * @{
+  */
+
+#define TIM_OutputNState_Disable           ((uint16_t)0x0000)
+#define TIM_OutputNState_Enable            ((uint16_t)0x0004)
+#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \
+                                     ((STATE) == TIM_OutputNState_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Capture_Compare_State
+  * @{
+  */
+
+#define TIM_CCx_Enable                      ((uint16_t)0x0001)
+#define TIM_CCx_Disable                     ((uint16_t)0x0000)
+#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \
+                         ((CCX) == TIM_CCx_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Capture_Compare_N_State
+  * @{
+  */
+
+#define TIM_CCxN_Enable                     ((uint16_t)0x0004)
+#define TIM_CCxN_Disable                    ((uint16_t)0x0000)
+#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \
+                           ((CCXN) == TIM_CCxN_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Break_Input_enable_disable 
+  * @{
+  */
+
+#define TIM_Break_Enable                   ((uint16_t)0x1000)
+#define TIM_Break_Disable                  ((uint16_t)0x0000)
+#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \
+                                   ((STATE) == TIM_Break_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Break_Polarity 
+  * @{
+  */
+
+#define TIM_BreakPolarity_Low              ((uint16_t)0x0000)
+#define TIM_BreakPolarity_High             ((uint16_t)0x2000)
+#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \
+                                         ((POLARITY) == TIM_BreakPolarity_High))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_AOE_Bit_Set_Reset 
+  * @{
+  */
+
+#define TIM_AutomaticOutput_Enable         ((uint16_t)0x4000)
+#define TIM_AutomaticOutput_Disable        ((uint16_t)0x0000)
+#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \
+                                              ((STATE) == TIM_AutomaticOutput_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Lock_level
+  * @{
+  */
+
+#define TIM_LOCKLevel_OFF                  ((uint16_t)0x0000)
+#define TIM_LOCKLevel_1                    ((uint16_t)0x0100)
+#define TIM_LOCKLevel_2                    ((uint16_t)0x0200)
+#define TIM_LOCKLevel_3                    ((uint16_t)0x0300)
+#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \
+                                  ((LEVEL) == TIM_LOCKLevel_1) || \
+                                  ((LEVEL) == TIM_LOCKLevel_2) || \
+                                  ((LEVEL) == TIM_LOCKLevel_3))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state 
+  * @{
+  */
+
+#define TIM_OSSIState_Enable               ((uint16_t)0x0400)
+#define TIM_OSSIState_Disable              ((uint16_t)0x0000)
+#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \
+                                  ((STATE) == TIM_OSSIState_Disable))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state
+  * @{
+  */
+
+#define TIM_OSSRState_Enable               ((uint16_t)0x0800)
+#define TIM_OSSRState_Disable              ((uint16_t)0x0000)
+#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \
+                                  ((STATE) == TIM_OSSRState_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_Idle_State 
+  * @{
+  */
+
+#define TIM_OCIdleState_Set                ((uint16_t)0x0100)
+#define TIM_OCIdleState_Reset              ((uint16_t)0x0000)
+#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \
+                                    ((STATE) == TIM_OCIdleState_Reset))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_N_Idle_State 
+  * @{
+  */
+
+#define TIM_OCNIdleState_Set               ((uint16_t)0x0200)
+#define TIM_OCNIdleState_Reset             ((uint16_t)0x0000)
+#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \
+                                     ((STATE) == TIM_OCNIdleState_Reset))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Polarity 
+  * @{
+  */
+
+#define  TIM_ICPolarity_Rising             ((uint16_t)0x0000)
+#define  TIM_ICPolarity_Falling            ((uint16_t)0x0002)
+#define  TIM_ICPolarity_BothEdge           ((uint16_t)0x000A)
+#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \
+                                      ((POLARITY) == TIM_ICPolarity_Falling)|| \
+                                      ((POLARITY) == TIM_ICPolarity_BothEdge))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Selection 
+  * @{
+  */
+
+#define TIM_ICSelection_DirectTI           ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be 
+                                                                   connected to IC1, IC2, IC3 or IC4, respectively */
+#define TIM_ICSelection_IndirectTI         ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be
+                                                                   connected to IC2, IC1, IC4 or IC3, respectively. */
+#define TIM_ICSelection_TRC                ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */
+#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \
+                                        ((SELECTION) == TIM_ICSelection_IndirectTI) || \
+                                        ((SELECTION) == TIM_ICSelection_TRC))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Prescaler 
+  * @{
+  */
+
+#define TIM_ICPSC_DIV1                     ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */
+#define TIM_ICPSC_DIV2                     ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */
+#define TIM_ICPSC_DIV4                     ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */
+#define TIM_ICPSC_DIV8                     ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */
+#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \
+                                        ((PRESCALER) == TIM_ICPSC_DIV2) || \
+                                        ((PRESCALER) == TIM_ICPSC_DIV4) || \
+                                        ((PRESCALER) == TIM_ICPSC_DIV8))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_interrupt_sources 
+  * @{
+  */
+
+#define TIM_IT_Update                      ((uint16_t)0x0001)
+#define TIM_IT_CC1                         ((uint16_t)0x0002)
+#define TIM_IT_CC2                         ((uint16_t)0x0004)
+#define TIM_IT_CC3                         ((uint16_t)0x0008)
+#define TIM_IT_CC4                         ((uint16_t)0x0010)
+#define TIM_IT_COM                         ((uint16_t)0x0020)
+#define TIM_IT_Trigger                     ((uint16_t)0x0040)
+#define TIM_IT_Break                       ((uint16_t)0x0080)
+#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000))
+
+#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \
+                           ((IT) == TIM_IT_CC1) || \
+                           ((IT) == TIM_IT_CC2) || \
+                           ((IT) == TIM_IT_CC3) || \
+                           ((IT) == TIM_IT_CC4) || \
+                           ((IT) == TIM_IT_COM) || \
+                           ((IT) == TIM_IT_Trigger) || \
+                           ((IT) == TIM_IT_Break))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_DMA_Base_address 
+  * @{
+  */
+
+#define TIM_DMABase_CR1                    ((uint16_t)0x0000)
+#define TIM_DMABase_CR2                    ((uint16_t)0x0001)
+#define TIM_DMABase_SMCR                   ((uint16_t)0x0002)
+#define TIM_DMABase_DIER                   ((uint16_t)0x0003)
+#define TIM_DMABase_SR                     ((uint16_t)0x0004)
+#define TIM_DMABase_EGR                    ((uint16_t)0x0005)
+#define TIM_DMABase_CCMR1                  ((uint16_t)0x0006)
+#define TIM_DMABase_CCMR2                  ((uint16_t)0x0007)
+#define TIM_DMABase_CCER                   ((uint16_t)0x0008)
+#define TIM_DMABase_CNT                    ((uint16_t)0x0009)
+#define TIM_DMABase_PSC                    ((uint16_t)0x000A)
+#define TIM_DMABase_ARR                    ((uint16_t)0x000B)
+#define TIM_DMABase_RCR                    ((uint16_t)0x000C)
+#define TIM_DMABase_CCR1                   ((uint16_t)0x000D)
+#define TIM_DMABase_CCR2                   ((uint16_t)0x000E)
+#define TIM_DMABase_CCR3                   ((uint16_t)0x000F)
+#define TIM_DMABase_CCR4                   ((uint16_t)0x0010)
+#define TIM_DMABase_BDTR                   ((uint16_t)0x0011)
+#define TIM_DMABase_DCR                    ((uint16_t)0x0012)
+#define TIM_DMABase_OR                     ((uint16_t)0x0013)
+#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \
+                               ((BASE) == TIM_DMABase_CR2) || \
+                               ((BASE) == TIM_DMABase_SMCR) || \
+                               ((BASE) == TIM_DMABase_DIER) || \
+                               ((BASE) == TIM_DMABase_SR) || \
+                               ((BASE) == TIM_DMABase_EGR) || \
+                               ((BASE) == TIM_DMABase_CCMR1) || \
+                               ((BASE) == TIM_DMABase_CCMR2) || \
+                               ((BASE) == TIM_DMABase_CCER) || \
+                               ((BASE) == TIM_DMABase_CNT) || \
+                               ((BASE) == TIM_DMABase_PSC) || \
+                               ((BASE) == TIM_DMABase_ARR) || \
+                               ((BASE) == TIM_DMABase_RCR) || \
+                               ((BASE) == TIM_DMABase_CCR1) || \
+                               ((BASE) == TIM_DMABase_CCR2) || \
+                               ((BASE) == TIM_DMABase_CCR3) || \
+                               ((BASE) == TIM_DMABase_CCR4) || \
+                               ((BASE) == TIM_DMABase_BDTR) || \
+                               ((BASE) == TIM_DMABase_DCR) || \
+                               ((BASE) == TIM_DMABase_OR))                     
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_DMA_Burst_Length 
+  * @{
+  */
+
+#define TIM_DMABurstLength_1Transfer           ((uint16_t)0x0000)
+#define TIM_DMABurstLength_2Transfers          ((uint16_t)0x0100)
+#define TIM_DMABurstLength_3Transfers          ((uint16_t)0x0200)
+#define TIM_DMABurstLength_4Transfers          ((uint16_t)0x0300)
+#define TIM_DMABurstLength_5Transfers          ((uint16_t)0x0400)
+#define TIM_DMABurstLength_6Transfers          ((uint16_t)0x0500)
+#define TIM_DMABurstLength_7Transfers          ((uint16_t)0x0600)
+#define TIM_DMABurstLength_8Transfers          ((uint16_t)0x0700)
+#define TIM_DMABurstLength_9Transfers          ((uint16_t)0x0800)
+#define TIM_DMABurstLength_10Transfers         ((uint16_t)0x0900)
+#define TIM_DMABurstLength_11Transfers         ((uint16_t)0x0A00)
+#define TIM_DMABurstLength_12Transfers         ((uint16_t)0x0B00)
+#define TIM_DMABurstLength_13Transfers         ((uint16_t)0x0C00)
+#define TIM_DMABurstLength_14Transfers         ((uint16_t)0x0D00)
+#define TIM_DMABurstLength_15Transfers         ((uint16_t)0x0E00)
+#define TIM_DMABurstLength_16Transfers         ((uint16_t)0x0F00)
+#define TIM_DMABurstLength_17Transfers         ((uint16_t)0x1000)
+#define TIM_DMABurstLength_18Transfers         ((uint16_t)0x1100)
+#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Transfer) || \
+                                   ((LENGTH) == TIM_DMABurstLength_2Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_3Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_4Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_5Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_6Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_7Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_8Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_9Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_10Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_11Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_12Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_13Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_14Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_15Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_16Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_17Transfers) || \
+                                   ((LENGTH) == TIM_DMABurstLength_18Transfers))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_DMA_sources 
+  * @{
+  */
+
+#define TIM_DMA_Update                     ((uint16_t)0x0100)
+#define TIM_DMA_CC1                        ((uint16_t)0x0200)
+#define TIM_DMA_CC2                        ((uint16_t)0x0400)
+#define TIM_DMA_CC3                        ((uint16_t)0x0800)
+#define TIM_DMA_CC4                        ((uint16_t)0x1000)
+#define TIM_DMA_COM                        ((uint16_t)0x2000)
+#define TIM_DMA_Trigger                    ((uint16_t)0x4000)
+#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_External_Trigger_Prescaler 
+  * @{
+  */
+
+#define TIM_ExtTRGPSC_OFF                  ((uint16_t)0x0000)
+#define TIM_ExtTRGPSC_DIV2                 ((uint16_t)0x1000)
+#define TIM_ExtTRGPSC_DIV4                 ((uint16_t)0x2000)
+#define TIM_ExtTRGPSC_DIV8                 ((uint16_t)0x3000)
+#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \
+                                         ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \
+                                         ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \
+                                         ((PRESCALER) == TIM_ExtTRGPSC_DIV8))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Internal_Trigger_Selection 
+  * @{
+  */
+
+#define TIM_TS_ITR0                        ((uint16_t)0x0000)
+#define TIM_TS_ITR1                        ((uint16_t)0x0010)
+#define TIM_TS_ITR2                        ((uint16_t)0x0020)
+#define TIM_TS_ITR3                        ((uint16_t)0x0030)
+#define TIM_TS_TI1F_ED                     ((uint16_t)0x0040)
+#define TIM_TS_TI1FP1                      ((uint16_t)0x0050)
+#define TIM_TS_TI2FP2                      ((uint16_t)0x0060)
+#define TIM_TS_ETRF                        ((uint16_t)0x0070)
+#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+                                             ((SELECTION) == TIM_TS_ITR1) || \
+                                             ((SELECTION) == TIM_TS_ITR2) || \
+                                             ((SELECTION) == TIM_TS_ITR3) || \
+                                             ((SELECTION) == TIM_TS_TI1F_ED) || \
+                                             ((SELECTION) == TIM_TS_TI1FP1) || \
+                                             ((SELECTION) == TIM_TS_TI2FP2) || \
+                                             ((SELECTION) == TIM_TS_ETRF))
+#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \
+                                                      ((SELECTION) == TIM_TS_ITR1) || \
+                                                      ((SELECTION) == TIM_TS_ITR2) || \
+                                                      ((SELECTION) == TIM_TS_ITR3))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_TIx_External_Clock_Source 
+  * @{
+  */
+
+#define TIM_TIxExternalCLK1Source_TI1      ((uint16_t)0x0050)
+#define TIM_TIxExternalCLK1Source_TI2      ((uint16_t)0x0060)
+#define TIM_TIxExternalCLK1Source_TI1ED    ((uint16_t)0x0040)
+
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_External_Trigger_Polarity 
+  * @{
+  */ 
+#define TIM_ExtTRGPolarity_Inverted        ((uint16_t)0x8000)
+#define TIM_ExtTRGPolarity_NonInverted     ((uint16_t)0x0000)
+#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \
+                                       ((POLARITY) == TIM_ExtTRGPolarity_NonInverted))
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Prescaler_Reload_Mode 
+  * @{
+  */
+
+#define TIM_PSCReloadMode_Update           ((uint16_t)0x0000)
+#define TIM_PSCReloadMode_Immediate        ((uint16_t)0x0001)
+#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \
+                                         ((RELOAD) == TIM_PSCReloadMode_Immediate))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Forced_Action 
+  * @{
+  */
+
+#define TIM_ForcedAction_Active            ((uint16_t)0x0050)
+#define TIM_ForcedAction_InActive          ((uint16_t)0x0040)
+#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \
+                                      ((ACTION) == TIM_ForcedAction_InActive))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Encoder_Mode 
+  * @{
+  */
+
+#define TIM_EncoderMode_TI1                ((uint16_t)0x0001)
+#define TIM_EncoderMode_TI2                ((uint16_t)0x0002)
+#define TIM_EncoderMode_TI12               ((uint16_t)0x0003)
+#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \
+                                   ((MODE) == TIM_EncoderMode_TI2) || \
+                                   ((MODE) == TIM_EncoderMode_TI12))
+/**
+  * @}
+  */ 
+
+
+/** @defgroup TIM_Event_Source 
+  * @{
+  */
+
+#define TIM_EventSource_Update             ((uint16_t)0x0001)
+#define TIM_EventSource_CC1                ((uint16_t)0x0002)
+#define TIM_EventSource_CC2                ((uint16_t)0x0004)
+#define TIM_EventSource_CC3                ((uint16_t)0x0008)
+#define TIM_EventSource_CC4                ((uint16_t)0x0010)
+#define TIM_EventSource_COM                ((uint16_t)0x0020)
+#define TIM_EventSource_Trigger            ((uint16_t)0x0040)
+#define TIM_EventSource_Break              ((uint16_t)0x0080)
+#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000))                                          
+  
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Update_Source 
+  * @{
+  */
+
+#define TIM_UpdateSource_Global            ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow
+                                                                   or the setting of UG bit, or an update generation
+                                                                   through the slave mode controller. */
+#define TIM_UpdateSource_Regular           ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */
+#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \
+                                      ((SOURCE) == TIM_UpdateSource_Regular))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_Preload_State 
+  * @{
+  */
+
+#define TIM_OCPreload_Enable               ((uint16_t)0x0008)
+#define TIM_OCPreload_Disable              ((uint16_t)0x0000)
+#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \
+                                       ((STATE) == TIM_OCPreload_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_Fast_State 
+  * @{
+  */
+
+#define TIM_OCFast_Enable                  ((uint16_t)0x0004)
+#define TIM_OCFast_Disable                 ((uint16_t)0x0000)
+#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \
+                                    ((STATE) == TIM_OCFast_Disable))
+                                     
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Output_Compare_Clear_State 
+  * @{
+  */
+
+#define TIM_OCClear_Enable                 ((uint16_t)0x0080)
+#define TIM_OCClear_Disable                ((uint16_t)0x0000)
+#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \
+                                     ((STATE) == TIM_OCClear_Disable))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Trigger_Output_Source 
+  * @{
+  */
+
+#define TIM_TRGOSource_Reset               ((uint16_t)0x0000)
+#define TIM_TRGOSource_Enable              ((uint16_t)0x0010)
+#define TIM_TRGOSource_Update              ((uint16_t)0x0020)
+#define TIM_TRGOSource_OC1                 ((uint16_t)0x0030)
+#define TIM_TRGOSource_OC1Ref              ((uint16_t)0x0040)
+#define TIM_TRGOSource_OC2Ref              ((uint16_t)0x0050)
+#define TIM_TRGOSource_OC3Ref              ((uint16_t)0x0060)
+#define TIM_TRGOSource_OC4Ref              ((uint16_t)0x0070)
+#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \
+                                    ((SOURCE) == TIM_TRGOSource_Enable) || \
+                                    ((SOURCE) == TIM_TRGOSource_Update) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC1) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC1Ref) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC2Ref) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC3Ref) || \
+                                    ((SOURCE) == TIM_TRGOSource_OC4Ref))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Slave_Mode 
+  * @{
+  */
+
+#define TIM_SlaveMode_Reset                ((uint16_t)0x0004)
+#define TIM_SlaveMode_Gated                ((uint16_t)0x0005)
+#define TIM_SlaveMode_Trigger              ((uint16_t)0x0006)
+#define TIM_SlaveMode_External1            ((uint16_t)0x0007)
+#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \
+                                 ((MODE) == TIM_SlaveMode_Gated) || \
+                                 ((MODE) == TIM_SlaveMode_Trigger) || \
+                                 ((MODE) == TIM_SlaveMode_External1))
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Master_Slave_Mode 
+  * @{
+  */
+
+#define TIM_MasterSlaveMode_Enable         ((uint16_t)0x0080)
+#define TIM_MasterSlaveMode_Disable        ((uint16_t)0x0000)
+#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \
+                                 ((STATE) == TIM_MasterSlaveMode_Disable))
+/**
+  * @}
+  */ 
+/** @defgroup TIM_Remap 
+  * @{
+  */
+
+#define TIM2_TIM8_TRGO                     ((uint16_t)0x0000)
+#define TIM2_ETH_PTP                       ((uint16_t)0x0400)
+#define TIM2_USBFS_SOF                     ((uint16_t)0x0800)
+#define TIM2_USBHS_SOF                     ((uint16_t)0x0C00)
+
+#define TIM5_GPIO                          ((uint16_t)0x0000)
+#define TIM5_LSI                           ((uint16_t)0x0040)
+#define TIM5_LSE                           ((uint16_t)0x0080)
+#define TIM5_RTC                           ((uint16_t)0x00C0)
+
+#define TIM11_GPIO                         ((uint16_t)0x0000)
+#define TIM11_HSE                          ((uint16_t)0x0002)
+
+#define IS_TIM_REMAP(TIM_REMAP)	 (((TIM_REMAP) == TIM2_TIM8_TRGO)||\
+                                  ((TIM_REMAP) == TIM2_ETH_PTP)||\
+                                  ((TIM_REMAP) == TIM2_USBFS_SOF)||\
+                                  ((TIM_REMAP) == TIM2_USBHS_SOF)||\
+                                  ((TIM_REMAP) == TIM5_GPIO)||\
+                                  ((TIM_REMAP) == TIM5_LSI)||\
+                                  ((TIM_REMAP) == TIM5_LSE)||\
+                                  ((TIM_REMAP) == TIM5_RTC)||\
+                                  ((TIM_REMAP) == TIM11_GPIO)||\
+                                  ((TIM_REMAP) == TIM11_HSE))
+
+/**
+  * @}
+  */ 
+/** @defgroup TIM_Flags 
+  * @{
+  */
+
+#define TIM_FLAG_Update                    ((uint16_t)0x0001)
+#define TIM_FLAG_CC1                       ((uint16_t)0x0002)
+#define TIM_FLAG_CC2                       ((uint16_t)0x0004)
+#define TIM_FLAG_CC3                       ((uint16_t)0x0008)
+#define TIM_FLAG_CC4                       ((uint16_t)0x0010)
+#define TIM_FLAG_COM                       ((uint16_t)0x0020)
+#define TIM_FLAG_Trigger                   ((uint16_t)0x0040)
+#define TIM_FLAG_Break                     ((uint16_t)0x0080)
+#define TIM_FLAG_CC1OF                     ((uint16_t)0x0200)
+#define TIM_FLAG_CC2OF                     ((uint16_t)0x0400)
+#define TIM_FLAG_CC3OF                     ((uint16_t)0x0800)
+#define TIM_FLAG_CC4OF                     ((uint16_t)0x1000)
+#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \
+                               ((FLAG) == TIM_FLAG_CC1) || \
+                               ((FLAG) == TIM_FLAG_CC2) || \
+                               ((FLAG) == TIM_FLAG_CC3) || \
+                               ((FLAG) == TIM_FLAG_CC4) || \
+                               ((FLAG) == TIM_FLAG_COM) || \
+                               ((FLAG) == TIM_FLAG_Trigger) || \
+                               ((FLAG) == TIM_FLAG_Break) || \
+                               ((FLAG) == TIM_FLAG_CC1OF) || \
+                               ((FLAG) == TIM_FLAG_CC2OF) || \
+                               ((FLAG) == TIM_FLAG_CC3OF) || \
+                               ((FLAG) == TIM_FLAG_CC4OF))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Input_Capture_Filer_Value 
+  * @{
+  */
+
+#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) 
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_External_Trigger_Filter 
+  * @{
+  */
+
+#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF)
+/**
+  * @}
+  */ 
+
+/** @defgroup TIM_Legacy 
+  * @{
+  */
+
+#define TIM_DMABurstLength_1Byte           TIM_DMABurstLength_1Transfer
+#define TIM_DMABurstLength_2Bytes          TIM_DMABurstLength_2Transfers
+#define TIM_DMABurstLength_3Bytes          TIM_DMABurstLength_3Transfers
+#define TIM_DMABurstLength_4Bytes          TIM_DMABurstLength_4Transfers
+#define TIM_DMABurstLength_5Bytes          TIM_DMABurstLength_5Transfers
+#define TIM_DMABurstLength_6Bytes          TIM_DMABurstLength_6Transfers
+#define TIM_DMABurstLength_7Bytes          TIM_DMABurstLength_7Transfers
+#define TIM_DMABurstLength_8Bytes          TIM_DMABurstLength_8Transfers
+#define TIM_DMABurstLength_9Bytes          TIM_DMABurstLength_9Transfers
+#define TIM_DMABurstLength_10Bytes         TIM_DMABurstLength_10Transfers
+#define TIM_DMABurstLength_11Bytes         TIM_DMABurstLength_11Transfers
+#define TIM_DMABurstLength_12Bytes         TIM_DMABurstLength_12Transfers
+#define TIM_DMABurstLength_13Bytes         TIM_DMABurstLength_13Transfers
+#define TIM_DMABurstLength_14Bytes         TIM_DMABurstLength_14Transfers
+#define TIM_DMABurstLength_15Bytes         TIM_DMABurstLength_15Transfers
+#define TIM_DMABurstLength_16Bytes         TIM_DMABurstLength_16Transfers
+#define TIM_DMABurstLength_17Bytes         TIM_DMABurstLength_17Transfers
+#define TIM_DMABurstLength_18Bytes         TIM_DMABurstLength_18Transfers
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/ 
+
+/* TimeBase management ********************************************************/
+void TIM_DeInit(TIM_TypeDef* TIMx);
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct);
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode);
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode);
+void TIM_SetCounter(TIM_TypeDef* TIMx, uint32_t Counter);
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint32_t Autoreload);
+uint32_t TIM_GetCounter(TIM_TypeDef* TIMx);
+uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx);
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource);
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode);
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD);
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState);
+
+/* Output Compare management **************************************************/
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct);
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode);
+void TIM_SetCompare1(TIM_TypeDef* TIMx, uint32_t Compare1);
+void TIM_SetCompare2(TIM_TypeDef* TIMx, uint32_t Compare2);
+void TIM_SetCompare3(TIM_TypeDef* TIMx, uint32_t Compare3);
+void TIM_SetCompare4(TIM_TypeDef* TIMx, uint32_t Compare4);
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction);
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload);
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast);
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear);
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity);
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity);
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity);
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity);
+void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx);
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN);
+
+/* Input Capture management ***************************************************/
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct);
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct);
+uint32_t TIM_GetCapture1(TIM_TypeDef* TIMx);
+uint32_t TIM_GetCapture2(TIM_TypeDef* TIMx);
+uint32_t TIM_GetCapture3(TIM_TypeDef* TIMx);
+uint32_t TIM_GetCapture4(TIM_TypeDef* TIMx);
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC);
+
+/* Advanced-control timers (TIM1 and TIM8) specific features ******************/
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct);
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct);
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState);
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState);
+
+/* Interrupts, DMA and flags management ***************************************/
+void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState);
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource);
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG);
+void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG);
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT);
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT);
+void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength);
+void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState);
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState);
+
+/* Clocks management **********************************************************/
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx);
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource);
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource,
+                                uint16_t TIM_ICPolarity, uint16_t ICFilter);
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity,
+                             uint16_t ExtTRGFilter);
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, 
+                             uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter);
+
+/* Synchronization management *************************************************/
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource);
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource);
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode);
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode);
+void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity,
+                   uint16_t ExtTRGFilter);
+
+/* Specific interface management **********************************************/   
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode,
+                                uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity);
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState);
+
+/* Specific remapping management **********************************************/
+void TIM_RemapConfig(TIM_TypeDef* TIMx, uint16_t TIM_Remap);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__STM32F4xx_TIM_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h
new file mode 100644
index 0000000000000000000000000000000000000000..dc011da7b1f51f1e7e4f21472e36cc5f79d6586f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_usart.h
@@ -0,0 +1,431 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_usart.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the USART 
+  *          firmware library.    
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_USART_H
+#define __STM32F4xx_USART_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup USART
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/ 
+
+/** 
+  * @brief  USART Init Structure definition  
+  */ 
+  
+typedef struct
+{
+  uint32_t USART_BaudRate;            /*!< This member configures the USART communication baud rate.
+                                           The baud rate is computed using the following formula:
+                                            - IntegerDivider = ((PCLKx) / (8 * (OVR8+1) * (USART_InitStruct->USART_BaudRate)))
+                                            - FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 8 * (OVR8+1)) + 0.5 
+                                           Where OVR8 is the "oversampling by 8 mode" configuration bit in the CR1 register. */
+
+  uint16_t USART_WordLength;          /*!< Specifies the number of data bits transmitted or received in a frame.
+                                           This parameter can be a value of @ref USART_Word_Length */
+
+  uint16_t USART_StopBits;            /*!< Specifies the number of stop bits transmitted.
+                                           This parameter can be a value of @ref USART_Stop_Bits */
+
+  uint16_t USART_Parity;              /*!< Specifies the parity mode.
+                                           This parameter can be a value of @ref USART_Parity
+                                           @note When parity is enabled, the computed parity is inserted
+                                                 at the MSB position of the transmitted data (9th bit when
+                                                 the word length is set to 9 data bits; 8th bit when the
+                                                 word length is set to 8 data bits). */
+ 
+  uint16_t USART_Mode;                /*!< Specifies wether the Receive or Transmit mode is enabled or disabled.
+                                           This parameter can be a value of @ref USART_Mode */
+
+  uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled
+                                           or disabled.
+                                           This parameter can be a value of @ref USART_Hardware_Flow_Control */
+} USART_InitTypeDef;
+
+/** 
+  * @brief  USART Clock Init Structure definition  
+  */ 
+  
+typedef struct
+{
+
+  uint16_t USART_Clock;   /*!< Specifies whether the USART clock is enabled or disabled.
+                               This parameter can be a value of @ref USART_Clock */
+
+  uint16_t USART_CPOL;    /*!< Specifies the steady state of the serial clock.
+                               This parameter can be a value of @ref USART_Clock_Polarity */
+
+  uint16_t USART_CPHA;    /*!< Specifies the clock transition on which the bit capture is made.
+                               This parameter can be a value of @ref USART_Clock_Phase */
+
+  uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted
+                               data bit (MSB) has to be output on the SCLK pin in synchronous mode.
+                               This parameter can be a value of @ref USART_Last_Bit */
+} USART_ClockInitTypeDef;
+
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup USART_Exported_Constants
+  * @{
+  */ 
+  
+#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \
+                                     ((PERIPH) == USART2) || \
+                                     ((PERIPH) == USART3) || \
+                                     ((PERIPH) == UART4)  || \
+                                     ((PERIPH) == UART5)  || \
+                                     ((PERIPH) == USART6) || \
+                                     ((PERIPH) == UART7)  || \
+                                     ((PERIPH) == UART8))
+
+#define IS_USART_1236_PERIPH(PERIPH) (((PERIPH) == USART1) || \
+                                      ((PERIPH) == USART2) || \
+                                      ((PERIPH) == USART3) || \
+                                      ((PERIPH) == USART6))
+
+/** @defgroup USART_Word_Length 
+  * @{
+  */ 
+  
+#define USART_WordLength_8b                  ((uint16_t)0x0000)
+#define USART_WordLength_9b                  ((uint16_t)0x1000)
+                                    
+#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \
+                                      ((LENGTH) == USART_WordLength_9b))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Stop_Bits 
+  * @{
+  */ 
+  
+#define USART_StopBits_1                     ((uint16_t)0x0000)
+#define USART_StopBits_0_5                   ((uint16_t)0x1000)
+#define USART_StopBits_2                     ((uint16_t)0x2000)
+#define USART_StopBits_1_5                   ((uint16_t)0x3000)
+#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \
+                                     ((STOPBITS) == USART_StopBits_0_5) || \
+                                     ((STOPBITS) == USART_StopBits_2) || \
+                                     ((STOPBITS) == USART_StopBits_1_5))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Parity 
+  * @{
+  */ 
+  
+#define USART_Parity_No                      ((uint16_t)0x0000)
+#define USART_Parity_Even                    ((uint16_t)0x0400)
+#define USART_Parity_Odd                     ((uint16_t)0x0600) 
+#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \
+                                 ((PARITY) == USART_Parity_Even) || \
+                                 ((PARITY) == USART_Parity_Odd))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Mode 
+  * @{
+  */ 
+  
+#define USART_Mode_Rx                        ((uint16_t)0x0004)
+#define USART_Mode_Tx                        ((uint16_t)0x0008)
+#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Hardware_Flow_Control 
+  * @{
+  */ 
+#define USART_HardwareFlowControl_None       ((uint16_t)0x0000)
+#define USART_HardwareFlowControl_RTS        ((uint16_t)0x0100)
+#define USART_HardwareFlowControl_CTS        ((uint16_t)0x0200)
+#define USART_HardwareFlowControl_RTS_CTS    ((uint16_t)0x0300)
+#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\
+                              (((CONTROL) == USART_HardwareFlowControl_None) || \
+                               ((CONTROL) == USART_HardwareFlowControl_RTS) || \
+                               ((CONTROL) == USART_HardwareFlowControl_CTS) || \
+                               ((CONTROL) == USART_HardwareFlowControl_RTS_CTS))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Clock 
+  * @{
+  */ 
+#define USART_Clock_Disable                  ((uint16_t)0x0000)
+#define USART_Clock_Enable                   ((uint16_t)0x0800)
+#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \
+                               ((CLOCK) == USART_Clock_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Clock_Polarity 
+  * @{
+  */
+  
+#define USART_CPOL_Low                       ((uint16_t)0x0000)
+#define USART_CPOL_High                      ((uint16_t)0x0400)
+#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Clock_Phase
+  * @{
+  */
+
+#define USART_CPHA_1Edge                     ((uint16_t)0x0000)
+#define USART_CPHA_2Edge                     ((uint16_t)0x0200)
+#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge))
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Last_Bit
+  * @{
+  */
+
+#define USART_LastBit_Disable                ((uint16_t)0x0000)
+#define USART_LastBit_Enable                 ((uint16_t)0x0100)
+#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \
+                                   ((LASTBIT) == USART_LastBit_Enable))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Interrupt_definition 
+  * @{
+  */
+  
+#define USART_IT_PE                          ((uint16_t)0x0028)
+#define USART_IT_TXE                         ((uint16_t)0x0727)
+#define USART_IT_TC                          ((uint16_t)0x0626)
+#define USART_IT_RXNE                        ((uint16_t)0x0525)
+#define USART_IT_ORE_RX                      ((uint16_t)0x0325) /* In case interrupt is generated if the RXNEIE bit is set */
+#define USART_IT_IDLE                        ((uint16_t)0x0424)
+#define USART_IT_LBD                         ((uint16_t)0x0846)
+#define USART_IT_CTS                         ((uint16_t)0x096A)
+#define USART_IT_ERR                         ((uint16_t)0x0060)
+#define USART_IT_ORE_ER                      ((uint16_t)0x0360) /* In case interrupt is generated if the EIE bit is set */
+#define USART_IT_NE                          ((uint16_t)0x0260)
+#define USART_IT_FE                          ((uint16_t)0x0160)
+
+/** @defgroup USART_Legacy 
+  * @{
+  */
+#define USART_IT_ORE                          USART_IT_ORE_ER               
+/**
+  * @}
+  */
+
+#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+                                ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+                                ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+                                ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR))
+#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \
+                             ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+                             ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \
+                             ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \
+                             ((IT) == USART_IT_ORE_RX) || ((IT) == USART_IT_ORE_ER) || \
+                             ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE))
+#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \
+                               ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS))
+/**
+  * @}
+  */
+
+/** @defgroup USART_DMA_Requests 
+  * @{
+  */
+
+#define USART_DMAReq_Tx                      ((uint16_t)0x0080)
+#define USART_DMAReq_Rx                      ((uint16_t)0x0040)
+#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00))
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_WakeUp_methods
+  * @{
+  */
+
+#define USART_WakeUp_IdleLine                ((uint16_t)0x0000)
+#define USART_WakeUp_AddressMark             ((uint16_t)0x0800)
+#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \
+                                 ((WAKEUP) == USART_WakeUp_AddressMark))
+/**
+  * @}
+  */
+
+/** @defgroup USART_LIN_Break_Detection_Length 
+  * @{
+  */
+  
+#define USART_LINBreakDetectLength_10b      ((uint16_t)0x0000)
+#define USART_LINBreakDetectLength_11b      ((uint16_t)0x0020)
+#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \
+                               (((LENGTH) == USART_LINBreakDetectLength_10b) || \
+                                ((LENGTH) == USART_LINBreakDetectLength_11b))
+/**
+  * @}
+  */
+
+/** @defgroup USART_IrDA_Low_Power 
+  * @{
+  */
+
+#define USART_IrDAMode_LowPower              ((uint16_t)0x0004)
+#define USART_IrDAMode_Normal                ((uint16_t)0x0000)
+#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \
+                                  ((MODE) == USART_IrDAMode_Normal))
+/**
+  * @}
+  */ 
+
+/** @defgroup USART_Flags 
+  * @{
+  */
+
+#define USART_FLAG_CTS                       ((uint16_t)0x0200)
+#define USART_FLAG_LBD                       ((uint16_t)0x0100)
+#define USART_FLAG_TXE                       ((uint16_t)0x0080)
+#define USART_FLAG_TC                        ((uint16_t)0x0040)
+#define USART_FLAG_RXNE                      ((uint16_t)0x0020)
+#define USART_FLAG_IDLE                      ((uint16_t)0x0010)
+#define USART_FLAG_ORE                       ((uint16_t)0x0008)
+#define USART_FLAG_NE                        ((uint16_t)0x0004)
+#define USART_FLAG_FE                        ((uint16_t)0x0002)
+#define USART_FLAG_PE                        ((uint16_t)0x0001)
+#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \
+                             ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \
+                             ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \
+                             ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \
+                             ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE))
+                              
+#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00))
+
+#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 7500001))
+#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF)
+#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF)
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/  
+
+/*  Function used to set the USART configuration to the default reset state ***/ 
+void USART_DeInit(USART_TypeDef* USARTx);
+
+/* Initialization and Configuration functions *********************************/
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct);
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct);
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct);
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler);
+void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+
+/* Data transfers functions ***************************************************/ 
+void USART_SendData(USART_TypeDef* USARTx, uint16_t Data);
+uint16_t USART_ReceiveData(USART_TypeDef* USARTx);
+
+/* Multi-Processor Communication functions ************************************/
+void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address);
+void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp);
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+
+/* LIN mode functions *********************************************************/
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength);
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SendBreak(USART_TypeDef* USARTx);
+
+/* Half-duplex mode function **************************************************/
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+
+/* Smartcard mode functions ***************************************************/
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState);
+void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime);
+
+/* IrDA mode functions ********************************************************/
+void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode);
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState);
+
+/* DMA transfers management functions *****************************************/
+void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState);
+
+/* Interrupts and flags management functions **********************************/
+void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState);
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG);
+void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG);
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT);
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_USART_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h
new file mode 100644
index 0000000000000000000000000000000000000000..8faf518ae5d330f13ad7a79a4f772f6b2bd78999
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/inc/stm32f4xx_wwdg.h
@@ -0,0 +1,111 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_wwdg.h
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file contains all the functions prototypes for the WWDG firmware
+  *          library.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32F4xx_WWDG_H
+#define __STM32F4xx_WWDG_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @addtogroup WWDG
+  * @{
+  */ 
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/** @defgroup WWDG_Exported_Constants
+  * @{
+  */ 
+  
+/** @defgroup WWDG_Prescaler 
+  * @{
+  */
+  
+#define WWDG_Prescaler_1    ((uint32_t)0x00000000)
+#define WWDG_Prescaler_2    ((uint32_t)0x00000080)
+#define WWDG_Prescaler_4    ((uint32_t)0x00000100)
+#define WWDG_Prescaler_8    ((uint32_t)0x00000180)
+#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \
+                                      ((PRESCALER) == WWDG_Prescaler_2) || \
+                                      ((PRESCALER) == WWDG_Prescaler_4) || \
+                                      ((PRESCALER) == WWDG_Prescaler_8))
+#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F)
+#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F))
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions --------------------------------------------------------*/
+  
+/*  Function used to set the WWDG configuration to the default reset state ****/  
+void WWDG_DeInit(void);
+
+/* Prescaler, Refresh window and Counter configuration functions **************/
+void WWDG_SetPrescaler(uint32_t WWDG_Prescaler);
+void WWDG_SetWindowValue(uint8_t WindowValue);
+void WWDG_EnableIT(void);
+void WWDG_SetCounter(uint8_t Counter);
+
+/* WWDG activation function ***************************************************/
+void WWDG_Enable(uint8_t Counter);
+
+/* Interrupts and flags management functions **********************************/
+FlagStatus WWDG_GetFlagStatus(void);
+void WWDG_ClearFlag(void);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32F4xx_WWDG_H */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c
new file mode 100644
index 0000000000000000000000000000000000000000..9e230c08e0e0a7f52dc23c60e621349db2533296
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c
@@ -0,0 +1,1745 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_adc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Analog to Digital Convertor (ADC) peripheral:
+  *           + Initialization and Configuration (in addition to ADC multi mode 
+  *             selection)
+  *           + Analog Watchdog configuration
+  *           + Temperature Sensor & Vrefint (Voltage Reference internal) & VBAT
+  *             management 
+  *           + Regular Channels Configuration
+  *           + Regular Channels DMA Configuration
+  *           + Injected channels Configuration
+  *           + Interrupts and flags management
+  *         
+  @verbatim
+ ===============================================================================
+                     ##### How to use this driver #####
+ ===============================================================================
+    [..]
+    (#) Enable the ADC interface clock using 
+        RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADCx, ENABLE); 
+       
+    (#) ADC pins configuration
+         (++) Enable the clock for the ADC GPIOs using the following function:
+             RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);   
+         (++) Configure these ADC pins in analog mode using GPIO_Init();  
+  
+     (#) Configure the ADC Prescaler, conversion resolution and data 
+         alignment using the ADC_Init() function.
+     (#) Activate the ADC peripheral using ADC_Cmd() function.
+  
+     *** Regular channels group configuration ***
+     ============================================
+     [..]    
+       (+) To configure the ADC regular channels group features, use 
+           ADC_Init() and ADC_RegularChannelConfig() functions.
+       (+) To activate the continuous mode, use the ADC_continuousModeCmd()
+           function.
+       (+) To configurate and activate the Discontinuous mode, use the 
+           ADC_DiscModeChannelCountConfig() and ADC_DiscModeCmd() functions.
+       (+) To read the ADC converted values, use the ADC_GetConversionValue()
+           function.
+  
+     *** Multi mode ADCs Regular channels configuration ***
+     ======================================================
+     [..]
+       (+) Refer to "Regular channels group configuration" description to
+           configure the ADC1, ADC2 and ADC3 regular channels.        
+       (+) Select the Multi mode ADC regular channels features (dual or 
+           triple mode) using ADC_CommonInit() function and configure 
+           the DMA mode using ADC_MultiModeDMARequestAfterLastTransferCmd() 
+           functions.        
+       (+) Read the ADCs converted values using the 
+           ADC_GetMultiModeConversionValue() function.
+  
+     *** DMA for Regular channels group features configuration ***
+     ============================================================= 
+     [..]
+       (+) To enable the DMA mode for regular channels group, use the 
+           ADC_DMACmd() function.
+       (+) To enable the generation of DMA requests continuously at the end
+           of the last DMA transfer, use the ADC_DMARequestAfterLastTransferCmd() 
+           function.
+  
+     *** Injected channels group configuration ***
+     =============================================    
+     [..]
+       (+) To configure the ADC Injected channels group features, use 
+           ADC_InjectedChannelConfig() and  ADC_InjectedSequencerLengthConfig()
+           functions.
+       (+) To activate the continuous mode, use the ADC_continuousModeCmd()
+           function.
+       (+) To activate the Injected Discontinuous mode, use the 
+           ADC_InjectedDiscModeCmd() function.  
+       (+) To activate the AutoInjected mode, use the ADC_AutoInjectedConvCmd() 
+           function.        
+       (+) To read the ADC converted values, use the ADC_GetInjectedConversionValue() 
+           function.
+  
+    @endverbatim
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_adc.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup ADC 
+  * @brief ADC driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/ 
+
+/* ADC DISCNUM mask */
+#define CR1_DISCNUM_RESET         ((uint32_t)0xFFFF1FFF)
+
+/* ADC AWDCH mask */
+#define CR1_AWDCH_RESET           ((uint32_t)0xFFFFFFE0)   
+
+/* ADC Analog watchdog enable mode mask */
+#define CR1_AWDMode_RESET         ((uint32_t)0xFF3FFDFF)   
+
+/* CR1 register Mask */
+#define CR1_CLEAR_MASK            ((uint32_t)0xFCFFFEFF)
+
+/* ADC EXTEN mask */
+#define CR2_EXTEN_RESET           ((uint32_t)0xCFFFFFFF)  
+
+/* ADC JEXTEN mask */
+#define CR2_JEXTEN_RESET          ((uint32_t)0xFFCFFFFF)  
+
+/* ADC JEXTSEL mask */
+#define CR2_JEXTSEL_RESET         ((uint32_t)0xFFF0FFFF)  
+
+/* CR2 register Mask */
+#define CR2_CLEAR_MASK            ((uint32_t)0xC0FFF7FD)
+
+/* ADC SQx mask */
+#define SQR3_SQ_SET               ((uint32_t)0x0000001F)  
+#define SQR2_SQ_SET               ((uint32_t)0x0000001F)  
+#define SQR1_SQ_SET               ((uint32_t)0x0000001F)  
+
+/* ADC L Mask */
+#define SQR1_L_RESET              ((uint32_t)0xFF0FFFFF) 
+
+/* ADC JSQx mask */
+#define JSQR_JSQ_SET              ((uint32_t)0x0000001F) 
+
+/* ADC JL mask */
+#define JSQR_JL_SET               ((uint32_t)0x00300000) 
+#define JSQR_JL_RESET             ((uint32_t)0xFFCFFFFF) 
+
+/* ADC SMPx mask */
+#define SMPR1_SMP_SET             ((uint32_t)0x00000007)  
+#define SMPR2_SMP_SET             ((uint32_t)0x00000007) 
+
+/* ADC JDRx registers offset */
+#define JDR_OFFSET                ((uint8_t)0x28) 
+
+/* ADC CDR register base address */
+#define CDR_ADDRESS               ((uint32_t)0x40012308)   
+
+/* ADC CCR register Mask */
+#define CR_CLEAR_MASK             ((uint32_t)0xFFFC30E0)  
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup ADC_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup ADC_Group1 Initialization and Configuration functions
+ *  @brief    Initialization and Configuration functions 
+ *
+@verbatim    
+ ===============================================================================
+              ##### Initialization and Configuration functions #####
+ ===============================================================================
+    [..]  This section provides functions allowing to:
+      (+) Initialize and configure the ADC Prescaler
+      (+) ADC Conversion Resolution (12bit..6bit)
+      (+) Scan Conversion Mode (multichannel or one channel) for regular group
+      (+) ADC Continuous Conversion Mode (Continuous or Single conversion) for 
+          regular group
+      (+) External trigger Edge and source of regular group, 
+      (+) Converted data alignment (left or right)
+      (+) The number of ADC conversions that will be done using the sequencer for 
+          regular channel group
+      (+) Multi ADC mode selection
+      (+) Direct memory access mode selection for multi ADC mode  
+      (+) Delay between 2 sampling phases (used in dual or triple interleaved modes)
+      (+) Enable or disable the ADC peripheral   
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes all ADCs peripherals registers to their default reset 
+  *         values.
+  * @param  None
+  * @retval None
+  */
+void ADC_DeInit(void)
+{
+  /* Enable all ADCs reset state */
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC, ENABLE);
+  
+  /* Release all ADCs from reset state */
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC, DISABLE);
+}
+
+/**
+  * @brief  Initializes the ADCx peripheral according to the specified parameters 
+  *         in the ADC_InitStruct.
+  * @note   This function is used to configure the global features of the ADC ( 
+  *         Resolution and Data Alignment), however, the rest of the configuration
+  *         parameters are specific to the regular channels group (scan mode 
+  *         activation, continuous mode activation, External trigger source and 
+  *         edge, number of conversion in the regular channels group sequencer).  
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains
+  *         the configuration information for the specified ADC peripheral.
+  * @retval None
+  */
+void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct)
+{
+  uint32_t tmpreg1 = 0;
+  uint8_t tmpreg2 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_RESOLUTION(ADC_InitStruct->ADC_Resolution)); 
+  assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode));
+  assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode)); 
+  assert_param(IS_ADC_EXT_TRIG_EDGE(ADC_InitStruct->ADC_ExternalTrigConvEdge)); 
+  assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv));    
+  assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); 
+  assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfConversion));
+  
+  /*---------------------------- ADCx CR1 Configuration -----------------*/
+  /* Get the ADCx CR1 value */
+  tmpreg1 = ADCx->CR1;
+  
+  /* Clear RES and SCAN bits */
+  tmpreg1 &= CR1_CLEAR_MASK;
+  
+  /* Configure ADCx: scan conversion mode and resolution */
+  /* Set SCAN bit according to ADC_ScanConvMode value */
+  /* Set RES bit according to ADC_Resolution value */ 
+  tmpreg1 |= (uint32_t)(((uint32_t)ADC_InitStruct->ADC_ScanConvMode << 8) | \
+                                   ADC_InitStruct->ADC_Resolution);
+  /* Write to ADCx CR1 */
+  ADCx->CR1 = tmpreg1;
+  /*---------------------------- ADCx CR2 Configuration -----------------*/
+  /* Get the ADCx CR2 value */
+  tmpreg1 = ADCx->CR2;
+  
+  /* Clear CONT, ALIGN, EXTEN and EXTSEL bits */
+  tmpreg1 &= CR2_CLEAR_MASK;
+  
+  /* Configure ADCx: external trigger event and edge, data alignment and 
+     continuous conversion mode */
+  /* Set ALIGN bit according to ADC_DataAlign value */
+  /* Set EXTEN bits according to ADC_ExternalTrigConvEdge value */ 
+  /* Set EXTSEL bits according to ADC_ExternalTrigConv value */
+  /* Set CONT bit according to ADC_ContinuousConvMode value */
+  tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_DataAlign | \
+                        ADC_InitStruct->ADC_ExternalTrigConv | 
+                        ADC_InitStruct->ADC_ExternalTrigConvEdge | \
+                        ((uint32_t)ADC_InitStruct->ADC_ContinuousConvMode << 1));
+                        
+  /* Write to ADCx CR2 */
+  ADCx->CR2 = tmpreg1;
+  /*---------------------------- ADCx SQR1 Configuration -----------------*/
+  /* Get the ADCx SQR1 value */
+  tmpreg1 = ADCx->SQR1;
+  
+  /* Clear L bits */
+  tmpreg1 &= SQR1_L_RESET;
+  
+  /* Configure ADCx: regular channel sequence length */
+  /* Set L bits according to ADC_NbrOfConversion value */
+  tmpreg2 |= (uint8_t)(ADC_InitStruct->ADC_NbrOfConversion - (uint8_t)1);
+  tmpreg1 |= ((uint32_t)tmpreg2 << 20);
+  
+  /* Write to ADCx SQR1 */
+  ADCx->SQR1 = tmpreg1;
+}
+
+/**
+  * @brief  Fills each ADC_InitStruct member with its default value.
+  * @note   This function is used to initialize the global features of the ADC ( 
+  *         Resolution and Data Alignment), however, the rest of the configuration
+  *         parameters are specific to the regular channels group (scan mode 
+  *         activation, continuous mode activation, External trigger source and 
+  *         edge, number of conversion in the regular channels group sequencer).  
+  * @param  ADC_InitStruct: pointer to an ADC_InitTypeDef structure which will 
+  *         be initialized.
+  * @retval None
+  */
+void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct)
+{
+  /* Initialize the ADC_Mode member */
+  ADC_InitStruct->ADC_Resolution = ADC_Resolution_12b;
+
+  /* initialize the ADC_ScanConvMode member */
+  ADC_InitStruct->ADC_ScanConvMode = DISABLE;
+
+  /* Initialize the ADC_ContinuousConvMode member */
+  ADC_InitStruct->ADC_ContinuousConvMode = DISABLE;
+
+  /* Initialize the ADC_ExternalTrigConvEdge member */
+  ADC_InitStruct->ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
+
+  /* Initialize the ADC_ExternalTrigConv member */
+  ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
+
+  /* Initialize the ADC_DataAlign member */
+  ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right;
+
+  /* Initialize the ADC_NbrOfConversion member */
+  ADC_InitStruct->ADC_NbrOfConversion = 1;
+}
+
+/**
+  * @brief  Initializes the ADCs peripherals according to the specified parameters 
+  *         in the ADC_CommonInitStruct.
+  * @param  ADC_CommonInitStruct: pointer to an ADC_CommonInitTypeDef structure 
+  *         that contains the configuration information for  All ADCs peripherals.
+  * @retval None
+  */
+void ADC_CommonInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct)
+{
+  uint32_t tmpreg1 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_MODE(ADC_CommonInitStruct->ADC_Mode));
+  assert_param(IS_ADC_PRESCALER(ADC_CommonInitStruct->ADC_Prescaler));
+  assert_param(IS_ADC_DMA_ACCESS_MODE(ADC_CommonInitStruct->ADC_DMAAccessMode));
+  assert_param(IS_ADC_SAMPLING_DELAY(ADC_CommonInitStruct->ADC_TwoSamplingDelay));
+  /*---------------------------- ADC CCR Configuration -----------------*/
+  /* Get the ADC CCR value */
+  tmpreg1 = ADC->CCR;
+  
+  /* Clear MULTI, DELAY, DMA and ADCPRE bits */
+  tmpreg1 &= CR_CLEAR_MASK;
+  
+  /* Configure ADCx: Multi mode, Delay between two sampling time, ADC prescaler,
+     and DMA access mode for multimode */
+  /* Set MULTI bits according to ADC_Mode value */
+  /* Set ADCPRE bits according to ADC_Prescaler value */
+  /* Set DMA bits according to ADC_DMAAccessMode value */
+  /* Set DELAY bits according to ADC_TwoSamplingDelay value */    
+  tmpreg1 |= (uint32_t)(ADC_CommonInitStruct->ADC_Mode | 
+                        ADC_CommonInitStruct->ADC_Prescaler | 
+                        ADC_CommonInitStruct->ADC_DMAAccessMode | 
+                        ADC_CommonInitStruct->ADC_TwoSamplingDelay);
+                        
+  /* Write to ADC CCR */
+  ADC->CCR = tmpreg1;
+}
+
+/**
+  * @brief  Fills each ADC_CommonInitStruct member with its default value.
+  * @param  ADC_CommonInitStruct: pointer to an ADC_CommonInitTypeDef structure
+  *         which will be initialized.
+  * @retval None
+  */
+void ADC_CommonStructInit(ADC_CommonInitTypeDef* ADC_CommonInitStruct)
+{
+  /* Initialize the ADC_Mode member */
+  ADC_CommonInitStruct->ADC_Mode = ADC_Mode_Independent;
+
+  /* initialize the ADC_Prescaler member */
+  ADC_CommonInitStruct->ADC_Prescaler = ADC_Prescaler_Div2;
+
+  /* Initialize the ADC_DMAAccessMode member */
+  ADC_CommonInitStruct->ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
+
+  /* Initialize the ADC_TwoSamplingDelay member */
+  ADC_CommonInitStruct->ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
+}
+
+/**
+  * @brief  Enables or disables the specified ADC peripheral.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the ADCx peripheral. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the ADON bit to wake up the ADC from power down mode */
+    ADCx->CR2 |= (uint32_t)ADC_CR2_ADON;
+  }
+  else
+  {
+    /* Disable the selected ADC peripheral */
+    ADCx->CR2 &= (uint32_t)(~ADC_CR2_ADON);
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Group2 Analog Watchdog configuration functions
+ *  @brief    Analog Watchdog configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+             ##### Analog Watchdog configuration functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to configure the Analog Watchdog
+         (AWD) feature in the ADC.
+  
+    [..] A typical configuration Analog Watchdog is done following these steps :
+      (#) the ADC guarded channel(s) is (are) selected using the 
+          ADC_AnalogWatchdogSingleChannelConfig() function.
+      (#) The Analog watchdog lower and higher threshold are configured using the  
+          ADC_AnalogWatchdogThresholdsConfig() function.
+      (#) The Analog watchdog is enabled and configured to enable the check, on one
+          or more channels, using the  ADC_AnalogWatchdogCmd() function.
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Enables or disables the analog watchdog on single/all regular or 
+  *         injected channels
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_AnalogWatchdog: the ADC analog watchdog configuration.
+  *         This parameter can be one of the following values:
+  *            @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel
+  *            @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel
+  *            @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel
+  *            @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on all regular channel
+  *            @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on all injected channel
+  *            @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels
+  *            @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog
+  * @retval None	  
+  */
+void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog));
+  
+  /* Get the old register value */
+  tmpreg = ADCx->CR1;
+  
+  /* Clear AWDEN, JAWDEN and AWDSGL bits */
+  tmpreg &= CR1_AWDMode_RESET;
+  
+  /* Set the analog watchdog enable mode */
+  tmpreg |= ADC_AnalogWatchdog;
+  
+  /* Store the new register value */
+  ADCx->CR1 = tmpreg;
+}
+
+/**
+  * @brief  Configures the high and low thresholds of the analog watchdog.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  HighThreshold: the ADC analog watchdog High threshold value.
+  *          This parameter must be a 12-bit value.
+  * @param  LowThreshold:  the ADC analog watchdog Low threshold value.
+  *          This parameter must be a 12-bit value.
+  * @retval None
+  */
+void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold,
+                                        uint16_t LowThreshold)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_THRESHOLD(HighThreshold));
+  assert_param(IS_ADC_THRESHOLD(LowThreshold));
+  
+  /* Set the ADCx high threshold */
+  ADCx->HTR = HighThreshold;
+  
+  /* Set the ADCx low threshold */
+  ADCx->LTR = LowThreshold;
+}
+
+/**
+  * @brief  Configures the analog watchdog guarded single channel
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_Channel: the ADC channel to configure for the analog watchdog. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_Channel_0: ADC Channel0 selected
+  *            @arg ADC_Channel_1: ADC Channel1 selected
+  *            @arg ADC_Channel_2: ADC Channel2 selected
+  *            @arg ADC_Channel_3: ADC Channel3 selected
+  *            @arg ADC_Channel_4: ADC Channel4 selected
+  *            @arg ADC_Channel_5: ADC Channel5 selected
+  *            @arg ADC_Channel_6: ADC Channel6 selected
+  *            @arg ADC_Channel_7: ADC Channel7 selected
+  *            @arg ADC_Channel_8: ADC Channel8 selected
+  *            @arg ADC_Channel_9: ADC Channel9 selected
+  *            @arg ADC_Channel_10: ADC Channel10 selected
+  *            @arg ADC_Channel_11: ADC Channel11 selected
+  *            @arg ADC_Channel_12: ADC Channel12 selected
+  *            @arg ADC_Channel_13: ADC Channel13 selected
+  *            @arg ADC_Channel_14: ADC Channel14 selected
+  *            @arg ADC_Channel_15: ADC Channel15 selected
+  *            @arg ADC_Channel_16: ADC Channel16 selected
+  *            @arg ADC_Channel_17: ADC Channel17 selected
+  *            @arg ADC_Channel_18: ADC Channel18 selected
+  * @retval None
+  */
+void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CHANNEL(ADC_Channel));
+  
+  /* Get the old register value */
+  tmpreg = ADCx->CR1;
+  
+  /* Clear the Analog watchdog channel select bits */
+  tmpreg &= CR1_AWDCH_RESET;
+  
+  /* Set the Analog watchdog channel */
+  tmpreg |= ADC_Channel;
+  
+  /* Store the new register value */
+  ADCx->CR1 = tmpreg;
+}
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Group3 Temperature Sensor, Vrefint (Voltage Reference internal) 
+ *            and VBAT (Voltage BATtery) management functions
+ *  @brief   Temperature Sensor, Vrefint and VBAT management functions 
+ *
+@verbatim   
+ ===============================================================================
+      ##### Temperature Sensor, Vrefint and VBAT management functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to enable/ disable the internal 
+         connections between the ADC and the Temperature Sensor, the Vrefint and 
+         the Vbat sources.
+     
+    [..] A typical configuration to get the Temperature sensor and Vrefint channels 
+         voltages is done following these steps :
+      (#) Enable the internal connection of Temperature sensor and Vrefint sources 
+          with the ADC channels using ADC_TempSensorVrefintCmd() function. 
+      (#) Select the ADC_Channel_TempSensor and/or ADC_Channel_Vrefint using 
+          ADC_RegularChannelConfig() or  ADC_InjectedChannelConfig() functions 
+      (#) Get the voltage values, using ADC_GetConversionValue() or  
+          ADC_GetInjectedConversionValue().
+
+    [..] A typical configuration to get the VBAT channel voltage is done following 
+         these steps :
+      (#) Enable the internal connection of VBAT source with the ADC channel using 
+          ADC_VBATCmd() function. 
+      (#) Select the ADC_Channel_Vbat using ADC_RegularChannelConfig() or  
+          ADC_InjectedChannelConfig() functions 
+      (#) Get the voltage value, using ADC_GetConversionValue() or  
+          ADC_GetInjectedConversionValue().
+ 
+@endverbatim
+  * @{
+  */
+  
+  
+/**
+  * @brief  Enables or disables the temperature sensor and Vrefint channels.
+  * @param  NewState: new state of the temperature sensor and Vrefint channels.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_TempSensorVrefintCmd(FunctionalState NewState)                
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the temperature sensor and Vrefint channel*/
+    ADC->CCR |= (uint32_t)ADC_CCR_TSVREFE;
+  }
+  else
+  {
+    /* Disable the temperature sensor and Vrefint channel*/
+    ADC->CCR &= (uint32_t)(~ADC_CCR_TSVREFE);
+  }
+}
+
+/**
+  * @brief  Enables or disables the VBAT (Voltage Battery) channel.
+  * 
+  * @note   the Battery voltage measured is equal to VBAT/2 on STM32F40xx and 
+  *         STM32F41xx devices and equal to VBAT/4 on STM32F42xx and STM32F43xx devices 
+  *              
+  * @param  NewState: new state of the VBAT channel.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_VBATCmd(FunctionalState NewState)                             
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the VBAT channel*/
+    ADC->CCR |= (uint32_t)ADC_CCR_VBATE;
+  }
+  else
+  {
+    /* Disable the VBAT channel*/
+    ADC->CCR &= (uint32_t)(~ADC_CCR_VBATE);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Group4 Regular Channels Configuration functions
+ *  @brief   Regular Channels Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+             ##### Regular Channels Configuration functions #####
+ ===============================================================================  
+
+    [..] This section provides functions allowing to manage the ADC's regular channels,
+         it is composed of 2 sub sections : 
+  
+      (#) Configuration and management functions for regular channels: This subsection 
+          provides functions allowing to configure the ADC regular channels :    
+         (++) Configure the rank in the regular group sequencer for each channel
+         (++) Configure the sampling time for each channel
+         (++) select the conversion Trigger for regular channels
+         (++) select the desired EOC event behavior configuration
+         (++) Activate the continuous Mode  (*)
+         (++) Activate the Discontinuous Mode 
+         -@@- Please Note that the following features for regular channels 
+             are configurated using the ADC_Init() function : 
+           (+@@) scan mode activation 
+           (+@@) continuous mode activation (**) 
+           (+@@) External trigger source  
+           (+@@) External trigger edge 
+           (+@@) number of conversion in the regular channels group sequencer.
+     
+         -@@- (*) and (**) are performing the same configuration
+     
+      (#) Get the conversion data: This subsection provides an important function in 
+          the ADC peripheral since it returns the converted data of the current 
+          regular channel. When the Conversion value is read, the EOC Flag is 
+          automatically cleared.
+     
+          -@- For multi ADC mode, the last ADC1, ADC2 and ADC3 regular conversions 
+              results data (in the selected multi mode) can be returned in the same 
+              time using ADC_GetMultiModeConversionValue() function. 
+         
+@endverbatim
+  * @{
+  */
+/**
+  * @brief  Configures for the selected ADC regular channel its corresponding
+  *         rank in the sequencer and its sample time.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_Channel: the ADC channel to configure. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_Channel_0: ADC Channel0 selected
+  *            @arg ADC_Channel_1: ADC Channel1 selected
+  *            @arg ADC_Channel_2: ADC Channel2 selected
+  *            @arg ADC_Channel_3: ADC Channel3 selected
+  *            @arg ADC_Channel_4: ADC Channel4 selected
+  *            @arg ADC_Channel_5: ADC Channel5 selected
+  *            @arg ADC_Channel_6: ADC Channel6 selected
+  *            @arg ADC_Channel_7: ADC Channel7 selected
+  *            @arg ADC_Channel_8: ADC Channel8 selected
+  *            @arg ADC_Channel_9: ADC Channel9 selected
+  *            @arg ADC_Channel_10: ADC Channel10 selected
+  *            @arg ADC_Channel_11: ADC Channel11 selected
+  *            @arg ADC_Channel_12: ADC Channel12 selected
+  *            @arg ADC_Channel_13: ADC Channel13 selected
+  *            @arg ADC_Channel_14: ADC Channel14 selected
+  *            @arg ADC_Channel_15: ADC Channel15 selected
+  *            @arg ADC_Channel_16: ADC Channel16 selected
+  *            @arg ADC_Channel_17: ADC Channel17 selected
+  *            @arg ADC_Channel_18: ADC Channel18 selected                       
+  * @param  Rank: The rank in the regular group sequencer.
+  *          This parameter must be between 1 to 16.
+  * @param  ADC_SampleTime: The sample time value to be set for the selected channel. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_SampleTime_3Cycles: Sample time equal to 3 cycles
+  *            @arg ADC_SampleTime_15Cycles: Sample time equal to 15 cycles
+  *            @arg ADC_SampleTime_28Cycles: Sample time equal to 28 cycles
+  *            @arg ADC_SampleTime_56Cycles: Sample time equal to 56 cycles	
+  *            @arg ADC_SampleTime_84Cycles: Sample time equal to 84 cycles	
+  *            @arg ADC_SampleTime_112Cycles: Sample time equal to 112 cycles	
+  *            @arg ADC_SampleTime_144Cycles: Sample time equal to 144 cycles	
+  *            @arg ADC_SampleTime_480Cycles: Sample time equal to 480 cycles	
+  * @retval None
+  */
+void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime)
+{
+  uint32_t tmpreg1 = 0, tmpreg2 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CHANNEL(ADC_Channel));
+  assert_param(IS_ADC_REGULAR_RANK(Rank));
+  assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+  
+  /* if ADC_Channel_10 ... ADC_Channel_18 is selected */
+  if (ADC_Channel > ADC_Channel_9)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR1;
+    
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR1_SMP_SET << (3 * (ADC_Channel - 10));
+    
+    /* Clear the old sample time */
+    tmpreg1 &= ~tmpreg2;
+    
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10));
+    
+    /* Set the new sample time */
+    tmpreg1 |= tmpreg2;
+    
+    /* Store the new register value */
+    ADCx->SMPR1 = tmpreg1;
+  }
+  else /* ADC_Channel include in ADC_Channel_[0..9] */
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR2;
+    
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR2_SMP_SET << (3 * ADC_Channel);
+    
+    /* Clear the old sample time */
+    tmpreg1 &= ~tmpreg2;
+    
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
+    
+    /* Set the new sample time */
+    tmpreg1 |= tmpreg2;
+    
+    /* Store the new register value */
+    ADCx->SMPR2 = tmpreg1;
+  }
+  /* For Rank 1 to 6 */
+  if (Rank < 7)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SQR3;
+    
+    /* Calculate the mask to clear */
+    tmpreg2 = SQR3_SQ_SET << (5 * (Rank - 1));
+    
+    /* Clear the old SQx bits for the selected rank */
+    tmpreg1 &= ~tmpreg2;
+    
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1));
+    
+    /* Set the SQx bits for the selected rank */
+    tmpreg1 |= tmpreg2;
+    
+    /* Store the new register value */
+    ADCx->SQR3 = tmpreg1;
+  }
+  /* For Rank 7 to 12 */
+  else if (Rank < 13)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SQR2;
+    
+    /* Calculate the mask to clear */
+    tmpreg2 = SQR2_SQ_SET << (5 * (Rank - 7));
+    
+    /* Clear the old SQx bits for the selected rank */
+    tmpreg1 &= ~tmpreg2;
+    
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7));
+    
+    /* Set the SQx bits for the selected rank */
+    tmpreg1 |= tmpreg2;
+    
+    /* Store the new register value */
+    ADCx->SQR2 = tmpreg1;
+  }
+  /* For Rank 13 to 16 */
+  else
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SQR1;
+    
+    /* Calculate the mask to clear */
+    tmpreg2 = SQR1_SQ_SET << (5 * (Rank - 13));
+    
+    /* Clear the old SQx bits for the selected rank */
+    tmpreg1 &= ~tmpreg2;
+    
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13));
+    
+    /* Set the SQx bits for the selected rank */
+    tmpreg1 |= tmpreg2;
+    
+    /* Store the new register value */
+    ADCx->SQR1 = tmpreg1;
+  }
+}
+
+/**
+  * @brief  Enables the selected ADC software start conversion of the regular channels.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval None
+  */
+void ADC_SoftwareStartConv(ADC_TypeDef* ADCx)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  
+  /* Enable the selected ADC conversion for regular group */
+  ADCx->CR2 |= (uint32_t)ADC_CR2_SWSTART;
+}
+
+/**
+  * @brief  Gets the selected ADC Software start regular conversion Status.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The new state of ADC software start conversion (SET or RESET).
+  */
+FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  
+  /* Check the status of SWSTART bit */
+  if ((ADCx->CR2 & ADC_CR2_SWSTART) != (uint32_t)RESET)
+  {
+    /* SWSTART bit is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SWSTART bit is reset */
+    bitstatus = RESET;
+  }
+  
+  /* Return the SWSTART bit status */
+  return  bitstatus;
+}
+
+
+/**
+  * @brief  Enables or disables the EOC on each regular channel conversion
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC EOC flag rising
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_EOCOnEachRegularChannelCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC EOC rising on each regular channel conversion */
+    ADCx->CR2 |= (uint32_t)ADC_CR2_EOCS;
+  }
+  else
+  {
+    /* Disable the selected ADC EOC rising on each regular channel conversion */
+    ADCx->CR2 &= (uint32_t)(~ADC_CR2_EOCS);
+  }
+}
+
+/**
+  * @brief  Enables or disables the ADC continuous conversion mode 
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC continuous conversion mode
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_ContinuousModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC continuous conversion mode */
+    ADCx->CR2 |= (uint32_t)ADC_CR2_CONT;
+  }
+  else
+  {
+    /* Disable the selected ADC continuous conversion mode */
+    ADCx->CR2 &= (uint32_t)(~ADC_CR2_CONT);
+  }
+}
+
+/**
+  * @brief  Configures the discontinuous mode for the selected ADC regular group 
+  *         channel.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  Number: specifies the discontinuous mode regular channel count value.
+  *          This number must be between 1 and 8.
+  * @retval None
+  */
+void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number)
+{
+  uint32_t tmpreg1 = 0;
+  uint32_t tmpreg2 = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number));
+  
+  /* Get the old register value */
+  tmpreg1 = ADCx->CR1;
+  
+  /* Clear the old discontinuous mode channel count */
+  tmpreg1 &= CR1_DISCNUM_RESET;
+  
+  /* Set the discontinuous mode channel count */
+  tmpreg2 = Number - 1;
+  tmpreg1 |= tmpreg2 << 13;
+  
+  /* Store the new register value */
+  ADCx->CR1 = tmpreg1;
+}
+
+/**
+  * @brief  Enables or disables the discontinuous mode on regular group channel 
+  *         for the specified ADC
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC discontinuous mode on 
+  *         regular group channel.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC regular discontinuous mode */
+    ADCx->CR1 |= (uint32_t)ADC_CR1_DISCEN;
+  }
+  else
+  {
+    /* Disable the selected ADC regular discontinuous mode */
+    ADCx->CR1 &= (uint32_t)(~ADC_CR1_DISCEN);
+  }
+}
+
+/**
+  * @brief  Returns the last ADCx conversion result data for regular channel.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The Data conversion value.
+  */
+uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  
+  /* Return the selected ADC conversion value */
+  return (uint16_t) ADCx->DR;
+}
+
+/**
+  * @brief  Returns the last ADC1, ADC2 and ADC3 regular conversions results 
+  *         data in the selected multi mode.
+  * @param  None  
+  * @retval The Data conversion value.
+  * @note   In dual mode, the value returned by this function is as following
+  *           Data[15:0] : these bits contain the regular data of ADC1.
+  *           Data[31:16]: these bits contain the regular data of ADC2.
+  * @note   In triple mode, the value returned by this function is as following
+  *           Data[15:0] : these bits contain alternatively the regular data of ADC1, ADC3 and ADC2.
+  *           Data[31:16]: these bits contain alternatively the regular data of ADC2, ADC1 and ADC3.           
+  */
+uint32_t ADC_GetMultiModeConversionValue(void)
+{
+  /* Return the multi mode conversion value */
+  return (*(__IO uint32_t *) CDR_ADDRESS);
+}
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Group5 Regular Channels DMA Configuration functions
+ *  @brief   Regular Channels DMA Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+            ##### Regular Channels DMA Configuration functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to configure the DMA for ADC 
+         regular channels.
+         Since converted regular channel values are stored into a unique data 
+         register, it is useful to use DMA for conversion of more than one regular 
+         channel. This avoids the loss of the data already stored in the ADC 
+         Data register.   
+         When the DMA mode is enabled (using the ADC_DMACmd() function), after each
+         conversion of a regular channel, a DMA request is generated.
+    [..] Depending on the "DMA disable selection for Independent ADC mode" 
+         configuration (using the ADC_DMARequestAfterLastTransferCmd() function), 
+         at the end of the last DMA transfer, two possibilities are allowed:
+      (+) No new DMA request is issued to the DMA controller (feature DISABLED) 
+      (+) Requests can continue to be generated (feature ENABLED).  
+    [..] Depending on the "DMA disable selection for multi ADC mode" configuration 
+         (using the void ADC_MultiModeDMARequestAfterLastTransferCmd() function), 
+         at the end of the last DMA transfer, two possibilities are allowed:
+        (+) No new DMA request is issued to the DMA controller (feature DISABLED) 
+        (+) Requests can continue to be generated (feature ENABLED).
+
+@endverbatim
+  * @{
+  */
+  
+ /**
+  * @brief  Enables or disables the specified ADC DMA request.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC DMA transfer.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC DMA request */
+    ADCx->CR2 |= (uint32_t)ADC_CR2_DMA;
+  }
+  else
+  {
+    /* Disable the selected ADC DMA request */
+    ADCx->CR2 &= (uint32_t)(~ADC_CR2_DMA);
+  }
+}
+
+/**
+  * @brief  Enables or disables the ADC DMA request after last transfer (Single-ADC mode)  
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC DMA request after last transfer.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_DMARequestAfterLastTransferCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC DMA request after last transfer */
+    ADCx->CR2 |= (uint32_t)ADC_CR2_DDS;
+  }
+  else
+  {
+    /* Disable the selected ADC DMA request after last transfer */
+    ADCx->CR2 &= (uint32_t)(~ADC_CR2_DDS);
+  }
+}
+
+/**
+  * @brief  Enables or disables the ADC DMA request after last transfer in multi ADC mode       
+  * @param  NewState: new state of the selected ADC DMA request after last transfer.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @note   if Enabled, DMA requests are issued as long as data are converted and 
+  *         DMA mode for multi ADC mode (selected using ADC_CommonInit() function 
+  *         by ADC_CommonInitStruct.ADC_DMAAccessMode structure member) is 
+  *          ADC_DMAAccessMode_1, ADC_DMAAccessMode_2 or ADC_DMAAccessMode_3.     
+  * @retval None
+  */
+void ADC_MultiModeDMARequestAfterLastTransferCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC DMA request after last transfer */
+    ADC->CCR |= (uint32_t)ADC_CCR_DDS;
+  }
+  else
+  {
+    /* Disable the selected ADC DMA request after last transfer */
+    ADC->CCR &= (uint32_t)(~ADC_CCR_DDS);
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Group6 Injected channels Configuration functions
+ *  @brief   Injected channels Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Injected channels Configuration functions #####
+ ===============================================================================  
+
+    [..] This section provide functions allowing to configure the ADC Injected channels,
+         it is composed of 2 sub sections : 
+    
+      (#) Configuration functions for Injected channels: This subsection provides 
+          functions allowing to configure the ADC injected channels :    
+        (++) Configure the rank in the injected group sequencer for each channel
+        (++) Configure the sampling time for each channel    
+        (++) Activate the Auto injected Mode  
+        (++) Activate the Discontinuous Mode 
+        (++) scan mode activation  
+        (++) External/software trigger source   
+        (++) External trigger edge 
+        (++) injected channels sequencer.
+    
+      (#) Get the Specified Injected channel conversion data: This subsection 
+          provides an important function in the ADC peripheral since it returns the 
+          converted data of the specific injected channel.
+
+@endverbatim
+  * @{
+  */ 
+/**
+  * @brief  Configures for the selected ADC injected channel its corresponding
+  *         rank in the sequencer and its sample time.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_Channel: the ADC channel to configure. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_Channel_0: ADC Channel0 selected
+  *            @arg ADC_Channel_1: ADC Channel1 selected
+  *            @arg ADC_Channel_2: ADC Channel2 selected
+  *            @arg ADC_Channel_3: ADC Channel3 selected
+  *            @arg ADC_Channel_4: ADC Channel4 selected
+  *            @arg ADC_Channel_5: ADC Channel5 selected
+  *            @arg ADC_Channel_6: ADC Channel6 selected
+  *            @arg ADC_Channel_7: ADC Channel7 selected
+  *            @arg ADC_Channel_8: ADC Channel8 selected
+  *            @arg ADC_Channel_9: ADC Channel9 selected
+  *            @arg ADC_Channel_10: ADC Channel10 selected
+  *            @arg ADC_Channel_11: ADC Channel11 selected
+  *            @arg ADC_Channel_12: ADC Channel12 selected
+  *            @arg ADC_Channel_13: ADC Channel13 selected
+  *            @arg ADC_Channel_14: ADC Channel14 selected
+  *            @arg ADC_Channel_15: ADC Channel15 selected
+  *            @arg ADC_Channel_16: ADC Channel16 selected
+  *            @arg ADC_Channel_17: ADC Channel17 selected
+  *            @arg ADC_Channel_18: ADC Channel18 selected                       
+  * @param  Rank: The rank in the injected group sequencer. 
+  *          This parameter must be between 1 to 4.
+  * @param  ADC_SampleTime: The sample time value to be set for the selected channel. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_SampleTime_3Cycles: Sample time equal to 3 cycles
+  *            @arg ADC_SampleTime_15Cycles: Sample time equal to 15 cycles
+  *            @arg ADC_SampleTime_28Cycles: Sample time equal to 28 cycles
+  *            @arg ADC_SampleTime_56Cycles: Sample time equal to 56 cycles	
+  *            @arg ADC_SampleTime_84Cycles: Sample time equal to 84 cycles	
+  *            @arg ADC_SampleTime_112Cycles: Sample time equal to 112 cycles	
+  *            @arg ADC_SampleTime_144Cycles: Sample time equal to 144 cycles	
+  *            @arg ADC_SampleTime_480Cycles: Sample time equal to 480 cycles	
+  * @retval None
+  */
+void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime)
+{
+  uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CHANNEL(ADC_Channel));
+  assert_param(IS_ADC_INJECTED_RANK(Rank));
+  assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime));
+  /* if ADC_Channel_10 ... ADC_Channel_18 is selected */
+  if (ADC_Channel > ADC_Channel_9)
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR1;
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR1_SMP_SET << (3*(ADC_Channel - 10));
+    /* Clear the old sample time */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10));
+    /* Set the new sample time */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SMPR1 = tmpreg1;
+  }
+  else /* ADC_Channel include in ADC_Channel_[0..9] */
+  {
+    /* Get the old register value */
+    tmpreg1 = ADCx->SMPR2;
+    /* Calculate the mask to clear */
+    tmpreg2 = SMPR2_SMP_SET << (3 * ADC_Channel);
+    /* Clear the old sample time */
+    tmpreg1 &= ~tmpreg2;
+    /* Calculate the mask to set */
+    tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel);
+    /* Set the new sample time */
+    tmpreg1 |= tmpreg2;
+    /* Store the new register value */
+    ADCx->SMPR2 = tmpreg1;
+  }
+  /* Rank configuration */
+  /* Get the old register value */
+  tmpreg1 = ADCx->JSQR;
+  /* Get JL value: Number = JL+1 */
+  tmpreg3 =  (tmpreg1 & JSQR_JL_SET)>> 20;
+  /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */
+  tmpreg2 = JSQR_JSQ_SET << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1)));
+  /* Clear the old JSQx bits for the selected rank */
+  tmpreg1 &= ~tmpreg2;
+  /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */
+  tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1)));
+  /* Set the JSQx bits for the selected rank */
+  tmpreg1 |= tmpreg2;
+  /* Store the new register value */
+  ADCx->JSQR = tmpreg1;
+}
+
+/**
+  * @brief  Configures the sequencer length for injected channels
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  Length: The sequencer length. 
+  *          This parameter must be a number between 1 to 4.
+  * @retval None
+  */
+void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length)
+{
+  uint32_t tmpreg1 = 0;
+  uint32_t tmpreg2 = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_INJECTED_LENGTH(Length));
+  
+  /* Get the old register value */
+  tmpreg1 = ADCx->JSQR;
+  
+  /* Clear the old injected sequence length JL bits */
+  tmpreg1 &= JSQR_JL_RESET;
+  
+  /* Set the injected sequence length JL bits */
+  tmpreg2 = Length - 1; 
+  tmpreg1 |= tmpreg2 << 20;
+  
+  /* Store the new register value */
+  ADCx->JSQR = tmpreg1;
+}
+
+/**
+  * @brief  Set the injected channels conversion value offset
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_InjectedChannel: the ADC injected channel to set its offset. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_InjectedChannel_1: Injected Channel1 selected
+  *            @arg ADC_InjectedChannel_2: Injected Channel2 selected
+  *            @arg ADC_InjectedChannel_3: Injected Channel3 selected
+  *            @arg ADC_InjectedChannel_4: Injected Channel4 selected
+  * @param  Offset: the offset value for the selected ADC injected channel
+  *          This parameter must be a 12bit value.
+  * @retval None
+  */
+void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset)
+{
+    __IO uint32_t tmp = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+  assert_param(IS_ADC_OFFSET(Offset));
+  
+  tmp = (uint32_t)ADCx;
+  tmp += ADC_InjectedChannel;
+  
+  /* Set the selected injected channel data offset */
+ *(__IO uint32_t *) tmp = (uint32_t)Offset;
+}
+
+ /**
+  * @brief  Configures the ADCx external trigger for injected channels conversion.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_ExternalTrigInjecConv: specifies the ADC trigger to start injected conversion.
+  *          This parameter can be one of the following values:                    
+  *            @arg ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture compare4 selected 
+  *            @arg ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event selected 
+  *            @arg ADC_ExternalTrigInjecConv_T2_CC1: Timer2 capture compare1 selected 
+  *            @arg ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event selected 
+  *            @arg ADC_ExternalTrigInjecConv_T3_CC2: Timer3 capture compare2 selected 
+  *            @arg ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture compare4 selected 
+  *            @arg ADC_ExternalTrigInjecConv_T4_CC1: Timer4 capture compare1 selected                       
+  *            @arg ADC_ExternalTrigInjecConv_T4_CC2: Timer4 capture compare2 selected 
+  *            @arg ADC_ExternalTrigInjecConv_T4_CC3: Timer4 capture compare3 selected                        
+  *            @arg ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event selected 
+  *            @arg ADC_ExternalTrigInjecConv_T5_CC4: Timer5 capture compare4 selected                        
+  *            @arg ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event selected                        
+  *            @arg ADC_ExternalTrigInjecConv_T8_CC2: Timer8 capture compare2 selected
+  *            @arg ADC_ExternalTrigInjecConv_T8_CC3: Timer8 capture compare3 selected                        
+  *            @arg ADC_ExternalTrigInjecConv_T8_CC4: Timer8 capture compare4 selected 
+  *            @arg ADC_ExternalTrigInjecConv_Ext_IT15: External interrupt line 15 event selected                          
+  * @retval None
+  */
+void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv));
+  
+  /* Get the old register value */
+  tmpreg = ADCx->CR2;
+  
+  /* Clear the old external event selection for injected group */
+  tmpreg &= CR2_JEXTSEL_RESET;
+  
+  /* Set the external event selection for injected group */
+  tmpreg |= ADC_ExternalTrigInjecConv;
+  
+  /* Store the new register value */
+  ADCx->CR2 = tmpreg;
+}
+
+/**
+  * @brief  Configures the ADCx external trigger edge for injected channels conversion.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_ExternalTrigInjecConvEdge: specifies the ADC external trigger edge
+  *         to start injected conversion. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_ExternalTrigInjecConvEdge_None: external trigger disabled for 
+  *                                                     injected conversion
+  *            @arg ADC_ExternalTrigInjecConvEdge_Rising: detection on rising edge
+  *            @arg ADC_ExternalTrigInjecConvEdge_Falling: detection on falling edge
+  *            @arg ADC_ExternalTrigInjecConvEdge_RisingFalling: detection on both rising 
+  *                                                               and falling edge
+  * @retval None
+  */
+void ADC_ExternalTrigInjectedConvEdgeConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConvEdge)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_EXT_INJEC_TRIG_EDGE(ADC_ExternalTrigInjecConvEdge));
+  /* Get the old register value */
+  tmpreg = ADCx->CR2;
+  /* Clear the old external trigger edge for injected group */
+  tmpreg &= CR2_JEXTEN_RESET;
+  /* Set the new external trigger edge for injected group */
+  tmpreg |= ADC_ExternalTrigInjecConvEdge;
+  /* Store the new register value */
+  ADCx->CR2 = tmpreg;
+}
+
+/**
+  * @brief  Enables the selected ADC software start conversion of the injected channels.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval None
+  */
+void ADC_SoftwareStartInjectedConv(ADC_TypeDef* ADCx)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  /* Enable the selected ADC conversion for injected group */
+  ADCx->CR2 |= (uint32_t)ADC_CR2_JSWSTART;
+}
+
+/**
+  * @brief  Gets the selected ADC Software start injected conversion Status.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @retval The new state of ADC software start injected conversion (SET or RESET).
+  */
+FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  
+  /* Check the status of JSWSTART bit */
+  if ((ADCx->CR2 & ADC_CR2_JSWSTART) != (uint32_t)RESET)
+  {
+    /* JSWSTART bit is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* JSWSTART bit is reset */
+    bitstatus = RESET;
+  }
+  /* Return the JSWSTART bit status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Enables or disables the selected ADC automatic injected group 
+  *         conversion after regular one.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC auto injected conversion
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC automatic injected group conversion */
+    ADCx->CR1 |= (uint32_t)ADC_CR1_JAUTO;
+  }
+  else
+  {
+    /* Disable the selected ADC automatic injected group conversion */
+    ADCx->CR1 &= (uint32_t)(~ADC_CR1_JAUTO);
+  }
+}
+
+/**
+  * @brief  Enables or disables the discontinuous mode for injected group 
+  *         channel for the specified ADC
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  NewState: new state of the selected ADC discontinuous mode on injected
+  *         group channel.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC injected discontinuous mode */
+    ADCx->CR1 |= (uint32_t)ADC_CR1_JDISCEN;
+  }
+  else
+  {
+    /* Disable the selected ADC injected discontinuous mode */
+    ADCx->CR1 &= (uint32_t)(~ADC_CR1_JDISCEN);
+  }
+}
+
+/**
+  * @brief  Returns the ADC injected channel conversion result
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_InjectedChannel: the converted ADC injected channel.
+  *          This parameter can be one of the following values:
+  *            @arg ADC_InjectedChannel_1: Injected Channel1 selected
+  *            @arg ADC_InjectedChannel_2: Injected Channel2 selected
+  *            @arg ADC_InjectedChannel_3: Injected Channel3 selected
+  *            @arg ADC_InjectedChannel_4: Injected Channel4 selected
+  * @retval The Data conversion value.
+  */
+uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel)
+{
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel));
+
+  tmp = (uint32_t)ADCx;
+  tmp += ADC_InjectedChannel + JDR_OFFSET;
+  
+  /* Returns the selected injected channel conversion data value */
+  return (uint16_t) (*(__IO uint32_t*)  tmp); 
+}
+/**
+  * @}
+  */
+
+/** @defgroup ADC_Group7 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+            ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+    [..] This section provides functions allowing to configure the ADC Interrupts 
+         and to get the status and clear flags and Interrupts pending bits.
+  
+    [..] Each ADC provides 4 Interrupts sources and 6 Flags which can be divided
+        into 3 groups:
+  
+  *** Flags and Interrupts for ADC regular channels ***
+  =====================================================
+    [..]
+      (+) Flags :
+        (##) ADC_FLAG_OVR : Overrun detection when regular converted data are lost
+
+        (##) ADC_FLAG_EOC : Regular channel end of conversion ==> to indicate 
+             (depending on EOCS bit, managed by ADC_EOCOnEachRegularChannelCmd() )
+             the end of:
+             (+++) a regular CHANNEL conversion 
+             (+++) sequence of regular GROUP conversions .
+
+        (##) ADC_FLAG_STRT: Regular channel start ==> to indicate when regular 
+             CHANNEL conversion starts.
+    [..]
+      (+) Interrupts :
+        (##) ADC_IT_OVR : specifies the interrupt source for Overrun detection 
+             event.  
+        (##) ADC_IT_EOC : specifies the interrupt source for Regular channel end
+             of conversion event.
+  
+  
+  *** Flags and Interrupts for ADC Injected channels ***
+  ======================================================
+    [..]
+      (+) Flags :
+        (##) ADC_FLAG_JEOC : Injected channel end of conversion ==> to indicate 
+             at the end of injected GROUP conversion  
+              
+        (##) ADC_FLAG_JSTRT: Injected channel start ==> to indicate hardware when 
+             injected GROUP conversion starts.
+    [..]
+      (+) Interrupts :
+        (##) ADC_IT_JEOC : specifies the interrupt source for Injected channel 
+             end of conversion event.     
+
+  *** General Flags and Interrupts for the ADC ***
+  ================================================ 
+    [..]
+      (+)Flags :
+        (##) ADC_FLAG_AWD: Analog watchdog ==> to indicate if the converted voltage 
+             crosses the programmed thresholds values.
+    [..]          
+      (+) Interrupts :
+        (##) ADC_IT_AWD : specifies the interrupt source for Analog watchdog event. 
+
+  
+    [..] The user should identify which mode will be used in his application to 
+         manage the ADC controller events: Polling mode or Interrupt mode.
+  
+    [..] In the Polling Mode it is advised to use the following functions:
+      (+) ADC_GetFlagStatus() : to check if flags events occur. 
+      (+) ADC_ClearFlag()     : to clear the flags events.
+      
+    [..] In the Interrupt Mode it is advised to use the following functions:
+      (+) ADC_ITConfig()          : to enable or disable the interrupt source.
+      (+) ADC_GetITStatus()       : to check if Interrupt occurs.
+      (+) ADC_ClearITPendingBit() : to clear the Interrupt pending Bit 
+                                   (corresponding Flag). 
+@endverbatim
+  * @{
+  */ 
+/**
+  * @brief  Enables or disables the specified ADC interrupts.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_IT_EOC: End of conversion interrupt mask
+  *            @arg ADC_IT_AWD: Analog watchdog interrupt mask
+  *            @arg ADC_IT_JEOC: End of injected conversion interrupt mask
+  *            @arg ADC_IT_OVR: Overrun interrupt enable                       
+  * @param  NewState: new state of the specified ADC interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState)  
+{
+  uint32_t itmask = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_ADC_IT(ADC_IT)); 
+
+  /* Get the ADC IT index */
+  itmask = (uint8_t)ADC_IT;
+  itmask = (uint32_t)0x01 << itmask;    
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected ADC interrupts */
+    ADCx->CR1 |= itmask;
+  }
+  else
+  {
+    /* Disable the selected ADC interrupts */
+    ADCx->CR1 &= (~(uint32_t)itmask);
+  }
+}
+
+/**
+  * @brief  Checks whether the specified ADC flag is set or not.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_FLAG: specifies the flag to check. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_FLAG_AWD: Analog watchdog flag
+  *            @arg ADC_FLAG_EOC: End of conversion flag
+  *            @arg ADC_FLAG_JEOC: End of injected group conversion flag
+  *            @arg ADC_FLAG_JSTRT: Start of injected group conversion flag
+  *            @arg ADC_FLAG_STRT: Start of regular group conversion flag
+  *            @arg ADC_FLAG_OVR: Overrun flag                                                 
+  * @retval The new state of ADC_FLAG (SET or RESET).
+  */
+FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_GET_FLAG(ADC_FLAG));
+
+  /* Check the status of the specified ADC flag */
+  if ((ADCx->SR & ADC_FLAG) != (uint8_t)RESET)
+  {
+    /* ADC_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* ADC_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the ADC_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the ADCx's pending flags.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_FLAG: specifies the flag to clear. 
+  *          This parameter can be any combination of the following values:
+  *            @arg ADC_FLAG_AWD: Analog watchdog flag
+  *            @arg ADC_FLAG_EOC: End of conversion flag
+  *            @arg ADC_FLAG_JEOC: End of injected group conversion flag
+  *            @arg ADC_FLAG_JSTRT: Start of injected group conversion flag
+  *            @arg ADC_FLAG_STRT: Start of regular group conversion flag
+  *            @arg ADC_FLAG_OVR: Overrun flag                          
+  * @retval None
+  */
+void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG));
+
+  /* Clear the selected ADC flags */
+  ADCx->SR = ~(uint32_t)ADC_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified ADC interrupt has occurred or not.
+  * @param  ADCx:   where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_IT: specifies the ADC interrupt source to check. 
+  *          This parameter can be one of the following values:
+  *            @arg ADC_IT_EOC: End of conversion interrupt mask
+  *            @arg ADC_IT_AWD: Analog watchdog interrupt mask
+  *            @arg ADC_IT_JEOC: End of injected conversion interrupt mask
+  *            @arg ADC_IT_OVR: Overrun interrupt mask                        
+  * @retval The new state of ADC_IT (SET or RESET).
+  */
+ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t itmask = 0, enablestatus = 0;
+
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_IT(ADC_IT));
+
+  /* Get the ADC IT index */
+  itmask = ADC_IT >> 8;
+
+  /* Get the ADC_IT enable bit status */
+  enablestatus = (ADCx->CR1 & ((uint32_t)0x01 << (uint8_t)ADC_IT)) ;
+
+  /* Check the status of the specified ADC interrupt */
+  if (((ADCx->SR & itmask) != (uint32_t)RESET) && enablestatus)
+  {
+    /* ADC_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* ADC_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the ADC_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the ADCx's interrupt pending bits.
+  * @param  ADCx: where x can be 1, 2 or 3 to select the ADC peripheral.
+  * @param  ADC_IT: specifies the ADC interrupt pending bit to clear.
+  *          This parameter can be one of the following values:
+  *            @arg ADC_IT_EOC: End of conversion interrupt mask
+  *            @arg ADC_IT_AWD: Analog watchdog interrupt mask
+  *            @arg ADC_IT_JEOC: End of injected conversion interrupt mask
+  *            @arg ADC_IT_OVR: Overrun interrupt mask                         
+  * @retval None
+  */
+void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT)
+{
+  uint8_t itmask = 0;
+  /* Check the parameters */
+  assert_param(IS_ADC_ALL_PERIPH(ADCx));
+  assert_param(IS_ADC_IT(ADC_IT)); 
+  /* Get the ADC IT index */
+  itmask = (uint8_t)(ADC_IT >> 8);
+  /* Clear the selected ADC interrupt pending bits */
+  ADCx->SR = ~(uint32_t)itmask;
+}                    
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c
new file mode 100644
index 0000000000000000000000000000000000000000..b6ba529ded88f7db7b347902f88b0463d8b1e42b
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_can.c
@@ -0,0 +1,1701 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_can.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Controller area network (CAN) peripheral:           
+  *           + Initialization and Configuration 
+  *           + CAN Frames Transmission 
+  *           + CAN Frames Reception    
+  *           + Operation modes switch  
+  *           + Error management          
+  *           + Interrupts and flags        
+  *         
+@verbatim                                 
+ ===============================================================================      
+                        ##### How to use this driver #####
+ ===============================================================================
+    [..]            
+      (#) Enable the CAN controller interface clock using 
+          RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE); for CAN1 
+          and RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN2, ENABLE); for CAN2
+      -@- In case you are using CAN2 only, you have to enable the CAN1 clock.
+       
+      (#) CAN pins configuration
+        (++) Enable the clock for the CAN GPIOs using the following function:
+             RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);   
+        (++) Connect the involved CAN pins to AF9 using the following function 
+             GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_CANx); 
+        (++) Configure these CAN pins in alternate function mode by calling
+             the function  GPIO_Init();
+      
+      (#) Initialise and configure the CAN using CAN_Init() and 
+          CAN_FilterInit() functions.   
+                 
+      (#) Transmit the desired CAN frame using CAN_Transmit() function.
+           
+      (#) Check the transmission of a CAN frame using CAN_TransmitStatus()
+          function.
+                 
+      (#) Cancel the transmission of a CAN frame using CAN_CancelTransmit()
+          function.  
+              
+      (#) Receive a CAN frame using CAN_Recieve() function.
+           
+      (#) Release the receive FIFOs using CAN_FIFORelease() function.
+                 
+      (#) Return the number of pending received frames using 
+          CAN_MessagePending() function.            
+                     
+      (#) To control CAN events you can use one of the following two methods:
+        (++) Check on CAN flags using the CAN_GetFlagStatus() function.  
+        (++) Use CAN interrupts through the function CAN_ITConfig() at 
+             initialization phase and CAN_GetITStatus() function into 
+             interrupt routines to check if the event has occurred or not.
+             After checking on a flag you should clear it using CAN_ClearFlag()
+             function. And after checking on an interrupt event you should 
+             clear it using CAN_ClearITPendingBit() function.            
+                 
+                
+@endverbatim
+           
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_can.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CAN 
+  * @brief CAN driver modules
+  * @{
+  */ 
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* CAN Master Control Register bits */
+#define MCR_DBF           ((uint32_t)0x00010000) /* software master reset */
+
+/* CAN Mailbox Transmit Request */
+#define TMIDxR_TXRQ       ((uint32_t)0x00000001) /* Transmit mailbox request */
+
+/* CAN Filter Master Register bits */
+#define FMR_FINIT         ((uint32_t)0x00000001) /* Filter init mode */
+
+/* Time out for INAK bit */
+#define INAK_TIMEOUT      ((uint32_t)0x0000FFFF)
+/* Time out for SLAK bit */
+#define SLAK_TIMEOUT      ((uint32_t)0x0000FFFF)
+
+/* Flags in TSR register */
+#define CAN_FLAGS_TSR     ((uint32_t)0x08000000) 
+/* Flags in RF1R register */
+#define CAN_FLAGS_RF1R    ((uint32_t)0x04000000) 
+/* Flags in RF0R register */
+#define CAN_FLAGS_RF0R    ((uint32_t)0x02000000) 
+/* Flags in MSR register */
+#define CAN_FLAGS_MSR     ((uint32_t)0x01000000) 
+/* Flags in ESR register */
+#define CAN_FLAGS_ESR     ((uint32_t)0x00F00000) 
+
+/* Mailboxes definition */
+#define CAN_TXMAILBOX_0   ((uint8_t)0x00)
+#define CAN_TXMAILBOX_1   ((uint8_t)0x01)
+#define CAN_TXMAILBOX_2   ((uint8_t)0x02) 
+
+#define CAN_MODE_MASK     ((uint32_t) 0x00000003)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit);
+
+/** @defgroup CAN_Private_Functions
+  * @{
+  */
+
+/** @defgroup CAN_Group1 Initialization and Configuration functions
+ *  @brief    Initialization and Configuration functions 
+ *
+@verbatim    
+ ===============================================================================
+              ##### Initialization and Configuration functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to 
+      (+) Initialize the CAN peripherals : Prescaler, operating mode, the maximum 
+          number of time quanta to perform resynchronization, the number of time 
+          quanta in Bit Segment 1 and 2 and many other modes. 
+          Refer to  @ref CAN_InitTypeDef  for more details.
+      (+) Configures the CAN reception filter.                                      
+      (+) Select the start bank filter for slave CAN.
+      (+) Enables or disables the Debug Freeze mode for CAN
+      (+)Enables or disables the CAN Time Trigger Operation communication mode
+   
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Deinitializes the CAN peripheral registers to their default reset values.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @retval None.
+  */
+void CAN_DeInit(CAN_TypeDef* CANx)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+ 
+  if (CANx == CAN1)
+  {
+    /* Enable CAN1 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE);
+    /* Release CAN1 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE);
+  }
+  else
+  {  
+    /* Enable CAN2 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, ENABLE);
+    /* Release CAN2 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, DISABLE);
+  }
+}
+
+/**
+  * @brief  Initializes the CAN peripheral according to the specified
+  *         parameters in the CAN_InitStruct.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @param  CAN_InitStruct: pointer to a CAN_InitTypeDef structure that contains
+  *         the configuration information for the CAN peripheral.
+  * @retval Constant indicates initialization succeed which will be 
+  *         CAN_InitStatus_Failed or CAN_InitStatus_Success.
+  */
+uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct)
+{
+  uint8_t InitStatus = CAN_InitStatus_Failed;
+  uint32_t wait_ack = 0x00000000;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP));
+  assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode));
+  assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW));
+  assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1));
+  assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2));
+  assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler));
+
+  /* Exit from sleep mode */
+  CANx->MCR &= (~(uint32_t)CAN_MCR_SLEEP);
+
+  /* Request initialisation */
+  CANx->MCR |= CAN_MCR_INRQ ;
+
+  /* Wait the acknowledge */
+  while (((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT))
+  {
+    wait_ack++;
+  }
+
+  /* Check acknowledge */
+  if ((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK)
+  {
+    InitStatus = CAN_InitStatus_Failed;
+  }
+  else 
+  {
+    /* Set the time triggered communication mode */
+    if (CAN_InitStruct->CAN_TTCM == ENABLE)
+    {
+      CANx->MCR |= CAN_MCR_TTCM;
+    }
+    else
+    {
+      CANx->MCR &= ~(uint32_t)CAN_MCR_TTCM;
+    }
+
+    /* Set the automatic bus-off management */
+    if (CAN_InitStruct->CAN_ABOM == ENABLE)
+    {
+      CANx->MCR |= CAN_MCR_ABOM;
+    }
+    else
+    {
+      CANx->MCR &= ~(uint32_t)CAN_MCR_ABOM;
+    }
+
+    /* Set the automatic wake-up mode */
+    if (CAN_InitStruct->CAN_AWUM == ENABLE)
+    {
+      CANx->MCR |= CAN_MCR_AWUM;
+    }
+    else
+    {
+      CANx->MCR &= ~(uint32_t)CAN_MCR_AWUM;
+    }
+
+    /* Set the no automatic retransmission */
+    if (CAN_InitStruct->CAN_NART == ENABLE)
+    {
+      CANx->MCR |= CAN_MCR_NART;
+    }
+    else
+    {
+      CANx->MCR &= ~(uint32_t)CAN_MCR_NART;
+    }
+
+    /* Set the receive FIFO locked mode */
+    if (CAN_InitStruct->CAN_RFLM == ENABLE)
+    {
+      CANx->MCR |= CAN_MCR_RFLM;
+    }
+    else
+    {
+      CANx->MCR &= ~(uint32_t)CAN_MCR_RFLM;
+    }
+
+    /* Set the transmit FIFO priority */
+    if (CAN_InitStruct->CAN_TXFP == ENABLE)
+    {
+      CANx->MCR |= CAN_MCR_TXFP;
+    }
+    else
+    {
+      CANx->MCR &= ~(uint32_t)CAN_MCR_TXFP;
+    }
+
+    /* Set the bit timing register */
+    CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | \
+                ((uint32_t)CAN_InitStruct->CAN_SJW << 24) | \
+                ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | \
+                ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) | \
+               ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1);
+
+    /* Request leave initialisation */
+    CANx->MCR &= ~(uint32_t)CAN_MCR_INRQ;
+
+   /* Wait the acknowledge */
+   wait_ack = 0;
+
+   while (((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT))
+   {
+     wait_ack++;
+   }
+
+    /* ...and check acknowledged */
+    if ((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)
+    {
+      InitStatus = CAN_InitStatus_Failed;
+    }
+    else
+    {
+      InitStatus = CAN_InitStatus_Success ;
+    }
+  }
+
+  /* At this step, return the status of initialization */
+  return InitStatus;
+}
+
+/**
+  * @brief  Configures the CAN reception filter according to the specified
+  *         parameters in the CAN_FilterInitStruct.
+  * @param  CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef structure that
+  *         contains the configuration information.
+  * @retval None
+  */
+void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct)
+{
+  uint32_t filter_number_bit_pos = 0;
+  /* Check the parameters */
+  assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber));
+  assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode));
+  assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale));
+  assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment));
+  assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation));
+
+  filter_number_bit_pos = ((uint32_t)1) << CAN_FilterInitStruct->CAN_FilterNumber;
+
+  /* Initialisation mode for the filter */
+  CAN1->FMR |= FMR_FINIT;
+
+  /* Filter Deactivation */
+  CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos;
+
+  /* Filter Scale */
+  if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit)
+  {
+    /* 16-bit scale for the filter */
+    CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos;
+
+    /* First 16-bit identifier and First 16-bit mask */
+    /* Or First 16-bit identifier and Second 16-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = 
+       ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow);
+
+    /* Second 16-bit identifier and Second 16-bit mask */
+    /* Or Third 16-bit identifier and Fourth 16-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = 
+       ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh);
+  }
+
+  if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit)
+  {
+    /* 32-bit scale for the filter */
+    CAN1->FS1R |= filter_number_bit_pos;
+    /* 32-bit identifier or First 32-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = 
+       ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow);
+    /* 32-bit mask or Second 32-bit identifier */
+    CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = 
+       ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) |
+        (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow);
+  }
+
+  /* Filter Mode */
+  if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask)
+  {
+    /*Id/Mask mode for the filter*/
+    CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos;
+  }
+  else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */
+  {
+    /*Identifier list mode for the filter*/
+    CAN1->FM1R |= (uint32_t)filter_number_bit_pos;
+  }
+
+  /* Filter FIFO assignment */
+  if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO0)
+  {
+    /* FIFO 0 assignation for the filter */
+    CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos;
+  }
+
+  if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO1)
+  {
+    /* FIFO 1 assignation for the filter */
+    CAN1->FFA1R |= (uint32_t)filter_number_bit_pos;
+  }
+  
+  /* Filter activation */
+  if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE)
+  {
+    CAN1->FA1R |= filter_number_bit_pos;
+  }
+
+  /* Leave the initialisation mode for the filter */
+  CAN1->FMR &= ~FMR_FINIT;
+}
+
+/**
+  * @brief  Fills each CAN_InitStruct member with its default value.
+  * @param  CAN_InitStruct: pointer to a CAN_InitTypeDef structure which ill be initialized.
+  * @retval None
+  */
+void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct)
+{
+  /* Reset CAN init structure parameters values */
+  
+  /* Initialize the time triggered communication mode */
+  CAN_InitStruct->CAN_TTCM = DISABLE;
+  
+  /* Initialize the automatic bus-off management */
+  CAN_InitStruct->CAN_ABOM = DISABLE;
+  
+  /* Initialize the automatic wake-up mode */
+  CAN_InitStruct->CAN_AWUM = DISABLE;
+  
+  /* Initialize the no automatic retransmission */
+  CAN_InitStruct->CAN_NART = DISABLE;
+  
+  /* Initialize the receive FIFO locked mode */
+  CAN_InitStruct->CAN_RFLM = DISABLE;
+  
+  /* Initialize the transmit FIFO priority */
+  CAN_InitStruct->CAN_TXFP = DISABLE;
+  
+  /* Initialize the CAN_Mode member */
+  CAN_InitStruct->CAN_Mode = CAN_Mode_Normal;
+  
+  /* Initialize the CAN_SJW member */
+  CAN_InitStruct->CAN_SJW = CAN_SJW_1tq;
+  
+  /* Initialize the CAN_BS1 member */
+  CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq;
+  
+  /* Initialize the CAN_BS2 member */
+  CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq;
+  
+  /* Initialize the CAN_Prescaler member */
+  CAN_InitStruct->CAN_Prescaler = 1;
+}
+
+/**
+  * @brief  Select the start bank filter for slave CAN.
+  * @param  CAN_BankNumber: Select the start slave bank filter from 1..27.
+  * @retval None
+  */
+void CAN_SlaveStartBank(uint8_t CAN_BankNumber) 
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber));
+  
+  /* Enter Initialisation mode for the filter */
+  CAN1->FMR |= FMR_FINIT;
+  
+  /* Select the start slave bank */
+  CAN1->FMR &= (uint32_t)0xFFFFC0F1 ;
+  CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8;
+  
+  /* Leave Initialisation mode for the filter */
+  CAN1->FMR &= ~FMR_FINIT;
+}
+
+/**
+  * @brief  Enables or disables the DBG Freeze for CAN.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  NewState: new state of the CAN peripheral. 
+  *          This parameter can be: ENABLE (CAN reception/transmission is frozen
+  *          during debug. Reception FIFOs can still be accessed/controlled normally) 
+  *          or DISABLE (CAN is working during debug).
+  * @retval None
+  */
+void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable Debug Freeze  */
+    CANx->MCR |= MCR_DBF;
+  }
+  else
+  {
+    /* Disable Debug Freeze */
+    CANx->MCR &= ~MCR_DBF;
+  }
+}
+
+
+/**
+  * @brief  Enables or disables the CAN Time TriggerOperation communication mode.
+  * @note   DLC must be programmed as 8 in order Time Stamp (2 bytes) to be 
+  *         sent over the CAN bus.  
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  NewState: Mode new state. This parameter can be: ENABLE or DISABLE.
+  *         When enabled, Time stamp (TIME[15:0]) value is  sent in the last two
+  *         data bytes of the 8-byte message: TIME[7:0] in data byte 6 and TIME[15:8] 
+  *         in data byte 7. 
+  * @retval None
+  */
+void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the TTCM mode */
+    CANx->MCR |= CAN_MCR_TTCM;
+
+    /* Set TGT bits */
+    CANx->sTxMailBox[0].TDTR |= ((uint32_t)CAN_TDT0R_TGT);
+    CANx->sTxMailBox[1].TDTR |= ((uint32_t)CAN_TDT1R_TGT);
+    CANx->sTxMailBox[2].TDTR |= ((uint32_t)CAN_TDT2R_TGT);
+  }
+  else
+  {
+    /* Disable the TTCM mode */
+    CANx->MCR &= (uint32_t)(~(uint32_t)CAN_MCR_TTCM);
+
+    /* Reset TGT bits */
+    CANx->sTxMailBox[0].TDTR &= ((uint32_t)~CAN_TDT0R_TGT);
+    CANx->sTxMailBox[1].TDTR &= ((uint32_t)~CAN_TDT1R_TGT);
+    CANx->sTxMailBox[2].TDTR &= ((uint32_t)~CAN_TDT2R_TGT);
+  }
+}
+/**
+  * @}
+  */
+
+
+/** @defgroup CAN_Group2 CAN Frames Transmission functions
+ *  @brief    CAN Frames Transmission functions 
+ *
+@verbatim    
+ ===============================================================================
+                ##### CAN Frames Transmission functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to 
+      (+) Initiate and transmit a CAN frame message (if there is an empty mailbox).
+      (+) Check the transmission status of a CAN Frame
+      (+) Cancel a transmit request
+   
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Initiates and transmits a CAN frame message.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  TxMessage: pointer to a structure which contains CAN Id, CAN DLC and CAN data.
+  * @retval The number of the mailbox that is used for transmission or
+  *         CAN_TxStatus_NoMailBox if there is no empty mailbox.
+  */
+uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage)
+{
+  uint8_t transmit_mailbox = 0;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_IDTYPE(TxMessage->IDE));
+  assert_param(IS_CAN_RTR(TxMessage->RTR));
+  assert_param(IS_CAN_DLC(TxMessage->DLC));
+
+  /* Select one empty transmit mailbox */
+  if ((CANx->TSR&CAN_TSR_TME0) == CAN_TSR_TME0)
+  {
+    transmit_mailbox = 0;
+  }
+  else if ((CANx->TSR&CAN_TSR_TME1) == CAN_TSR_TME1)
+  {
+    transmit_mailbox = 1;
+  }
+  else if ((CANx->TSR&CAN_TSR_TME2) == CAN_TSR_TME2)
+  {
+    transmit_mailbox = 2;
+  }
+  else
+  {
+    transmit_mailbox = CAN_TxStatus_NoMailBox;
+  }
+
+  if (transmit_mailbox != CAN_TxStatus_NoMailBox)
+  {
+    /* Set up the Id */
+    CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ;
+    if (TxMessage->IDE == CAN_Id_Standard)
+    {
+      assert_param(IS_CAN_STDID(TxMessage->StdId));  
+      CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | \
+                                                  TxMessage->RTR);
+    }
+    else
+    {
+      assert_param(IS_CAN_EXTID(TxMessage->ExtId));
+      CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId << 3) | \
+                                                  TxMessage->IDE | \
+                                                  TxMessage->RTR);
+    }
+    
+    /* Set up the DLC */
+    TxMessage->DLC &= (uint8_t)0x0000000F;
+    CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0;
+    CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC;
+
+    /* Set up the data field */
+    CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | 
+                                             ((uint32_t)TxMessage->Data[2] << 16) |
+                                             ((uint32_t)TxMessage->Data[1] << 8) | 
+                                             ((uint32_t)TxMessage->Data[0]));
+    CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | 
+                                             ((uint32_t)TxMessage->Data[6] << 16) |
+                                             ((uint32_t)TxMessage->Data[5] << 8) |
+                                             ((uint32_t)TxMessage->Data[4]));
+    /* Request transmission */
+    CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ;
+  }
+  return transmit_mailbox;
+}
+
+/**
+  * @brief  Checks the transmission status of a CAN Frame.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @param  TransmitMailbox: the number of the mailbox that is used for transmission.
+  * @retval CAN_TxStatus_Ok if the CAN driver transmits the message, 
+  *         CAN_TxStatus_Failed in an other case.
+  */
+uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox)
+{
+  uint32_t state = 0;
+
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox));
+ 
+  switch (TransmitMailbox)
+  {
+    case (CAN_TXMAILBOX_0): 
+      state =   CANx->TSR &  (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0);
+      break;
+    case (CAN_TXMAILBOX_1): 
+      state =   CANx->TSR &  (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1);
+      break;
+    case (CAN_TXMAILBOX_2): 
+      state =   CANx->TSR &  (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2);
+      break;
+    default:
+      state = CAN_TxStatus_Failed;
+      break;
+  }
+  switch (state)
+  {
+      /* transmit pending  */
+    case (0x0): state = CAN_TxStatus_Pending;
+      break;
+      /* transmit failed  */
+     case (CAN_TSR_RQCP0 | CAN_TSR_TME0): state = CAN_TxStatus_Failed;
+      break;
+     case (CAN_TSR_RQCP1 | CAN_TSR_TME1): state = CAN_TxStatus_Failed;
+      break;
+     case (CAN_TSR_RQCP2 | CAN_TSR_TME2): state = CAN_TxStatus_Failed;
+      break;
+      /* transmit succeeded  */
+    case (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0):state = CAN_TxStatus_Ok;
+      break;
+    case (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1):state = CAN_TxStatus_Ok;
+      break;
+    case (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2):state = CAN_TxStatus_Ok;
+      break;
+    default: state = CAN_TxStatus_Failed;
+      break;
+  }
+  return (uint8_t) state;
+}
+
+/**
+  * @brief  Cancels a transmit request.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @param  Mailbox: Mailbox number.
+  * @retval None
+  */
+void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox));
+  /* abort transmission */
+  switch (Mailbox)
+  {
+    case (CAN_TXMAILBOX_0): CANx->TSR |= CAN_TSR_ABRQ0;
+      break;
+    case (CAN_TXMAILBOX_1): CANx->TSR |= CAN_TSR_ABRQ1;
+      break;
+    case (CAN_TXMAILBOX_2): CANx->TSR |= CAN_TSR_ABRQ2;
+      break;
+    default:
+      break;
+  }
+}
+/**
+  * @}
+  */
+
+
+/** @defgroup CAN_Group3 CAN Frames Reception functions
+ *  @brief    CAN Frames Reception functions 
+ *
+@verbatim    
+ ===============================================================================
+                ##### CAN Frames Reception functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to 
+      (+) Receive a correct CAN frame
+      (+) Release a specified receive FIFO (2 FIFOs are available)
+      (+) Return the number of the pending received CAN frames
+   
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Receives a correct CAN frame.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @param  FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+  * @param  RxMessage: pointer to a structure receive frame which contains CAN Id,
+  *         CAN DLC, CAN data and FMI number.
+  * @retval None
+  */
+void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FIFO(FIFONumber));
+  /* Get the Id */
+  RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR;
+  if (RxMessage->IDE == CAN_Id_Standard)
+  {
+    RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21);
+  }
+  else
+  {
+    RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3);
+  }
+  
+  RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR;
+  /* Get the DLC */
+  RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR;
+  /* Get the FMI */
+  RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8);
+  /* Get the data field */
+  RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR;
+  RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8);
+  RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16);
+  RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24);
+  RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR;
+  RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8);
+  RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16);
+  RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24);
+  /* Release the FIFO */
+  /* Release FIFO0 */
+  if (FIFONumber == CAN_FIFO0)
+  {
+    CANx->RF0R |= CAN_RF0R_RFOM0;
+  }
+  /* Release FIFO1 */
+  else /* FIFONumber == CAN_FIFO1 */
+  {
+    CANx->RF1R |= CAN_RF1R_RFOM1;
+  }
+}
+
+/**
+  * @brief  Releases the specified receive FIFO.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @param  FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1.
+  * @retval None
+  */
+void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FIFO(FIFONumber));
+  /* Release FIFO0 */
+  if (FIFONumber == CAN_FIFO0)
+  {
+    CANx->RF0R |= CAN_RF0R_RFOM0;
+  }
+  /* Release FIFO1 */
+  else /* FIFONumber == CAN_FIFO1 */
+  {
+    CANx->RF1R |= CAN_RF1R_RFOM1;
+  }
+}
+
+/**
+  * @brief  Returns the number of pending received messages.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @param  FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1.
+  * @retval NbMessage : which is the number of pending message.
+  */
+uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber)
+{
+  uint8_t message_pending=0;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_FIFO(FIFONumber));
+  if (FIFONumber == CAN_FIFO0)
+  {
+    message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03);
+  }
+  else if (FIFONumber == CAN_FIFO1)
+  {
+    message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03);
+  }
+  else
+  {
+    message_pending = 0;
+  }
+  return message_pending;
+}
+/**
+  * @}
+  */
+
+
+/** @defgroup CAN_Group4 CAN Operation modes functions
+ *  @brief    CAN Operation modes functions 
+ *
+@verbatim    
+ ===============================================================================
+                    ##### CAN Operation modes functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to select the CAN Operation modes
+      (+) sleep mode
+      (+) normal mode 
+      (+) initialization mode
+   
+@endverbatim
+  * @{
+  */
+  
+  
+/**
+  * @brief  Selects the CAN Operation mode.
+  * @param  CAN_OperatingMode: CAN Operating Mode.
+  *         This parameter can be one of @ref CAN_OperatingMode_TypeDef enumeration.
+  * @retval status of the requested mode which can be 
+  *         - CAN_ModeStatus_Failed:  CAN failed entering the specific mode 
+  *         - CAN_ModeStatus_Success: CAN Succeed entering the specific mode 
+  */
+uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode)
+{
+  uint8_t status = CAN_ModeStatus_Failed;
+  
+  /* Timeout for INAK or also for SLAK bits*/
+  uint32_t timeout = INAK_TIMEOUT; 
+
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_OPERATING_MODE(CAN_OperatingMode));
+
+  if (CAN_OperatingMode == CAN_OperatingMode_Initialization)
+  {
+    /* Request initialisation */
+    CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_SLEEP)) | CAN_MCR_INRQ);
+
+    /* Wait the acknowledge */
+    while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) && (timeout != 0))
+    {
+      timeout--;
+    }
+    if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK)
+    {
+      status = CAN_ModeStatus_Failed;
+    }
+    else
+    {
+      status = CAN_ModeStatus_Success;
+    }
+  }
+  else  if (CAN_OperatingMode == CAN_OperatingMode_Normal)
+  {
+    /* Request leave initialisation and sleep mode  and enter Normal mode */
+    CANx->MCR &= (uint32_t)(~(CAN_MCR_SLEEP|CAN_MCR_INRQ));
+
+    /* Wait the acknowledge */
+    while (((CANx->MSR & CAN_MODE_MASK) != 0) && (timeout!=0))
+    {
+      timeout--;
+    }
+    if ((CANx->MSR & CAN_MODE_MASK) != 0)
+    {
+      status = CAN_ModeStatus_Failed;
+    }
+    else
+    {
+      status = CAN_ModeStatus_Success;
+    }
+  }
+  else  if (CAN_OperatingMode == CAN_OperatingMode_Sleep)
+  {
+    /* Request Sleep mode */
+    CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP);
+
+    /* Wait the acknowledge */
+    while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) && (timeout!=0))
+    {
+      timeout--;
+    }
+    if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK)
+    {
+      status = CAN_ModeStatus_Failed;
+    }
+    else
+    {
+      status = CAN_ModeStatus_Success;
+    }
+  }
+  else
+  {
+    status = CAN_ModeStatus_Failed;
+  }
+
+  return  (uint8_t) status;
+}
+
+/**
+  * @brief  Enters the Sleep (low power) mode.
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @retval CAN_Sleep_Ok if sleep entered, CAN_Sleep_Failed otherwise.
+  */
+uint8_t CAN_Sleep(CAN_TypeDef* CANx)
+{
+  uint8_t sleepstatus = CAN_Sleep_Failed;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+    
+  /* Request Sleep mode */
+   CANx->MCR = (((CANx->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP);
+   
+  /* Sleep mode status */
+  if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK)
+  {
+    /* Sleep mode not entered */
+    sleepstatus =  CAN_Sleep_Ok;
+  }
+  /* return sleep mode status */
+   return (uint8_t)sleepstatus;
+}
+
+/**
+  * @brief  Wakes up the CAN peripheral from sleep mode .
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @retval CAN_WakeUp_Ok if sleep mode left, CAN_WakeUp_Failed otherwise.
+  */
+uint8_t CAN_WakeUp(CAN_TypeDef* CANx)
+{
+  uint32_t wait_slak = SLAK_TIMEOUT;
+  uint8_t wakeupstatus = CAN_WakeUp_Failed;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+    
+  /* Wake up request */
+  CANx->MCR &= ~(uint32_t)CAN_MCR_SLEEP;
+    
+  /* Sleep mode status */
+  while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00))
+  {
+   wait_slak--;
+  }
+  if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK)
+  {
+   /* wake up done : Sleep mode exited */
+    wakeupstatus = CAN_WakeUp_Ok;
+  }
+  /* return wakeup status */
+  return (uint8_t)wakeupstatus;
+}
+/**
+  * @}
+  */
+
+
+/** @defgroup CAN_Group5 CAN Bus Error management functions
+ *  @brief    CAN Bus Error management functions 
+ *
+@verbatim    
+ ===============================================================================
+                ##### CAN Bus Error management functions #####
+ ===============================================================================  
+    [..] This section provides functions allowing to 
+      (+) Return the CANx's last error code (LEC)
+      (+) Return the CANx Receive Error Counter (REC)
+      (+) Return the LSB of the 9-bit CANx Transmit Error Counter(TEC).
+   
+      -@- If TEC is greater than 255, The CAN is in bus-off state.
+      -@- if REC or TEC are greater than 96, an Error warning flag occurs.
+      -@- if REC or TEC are greater than 127, an Error Passive Flag occurs.
+                        
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Returns the CANx's last error code (LEC).
+  * @param  CANx: where x can be 1 or 2 to select the CAN peripheral.
+  * @retval Error code: 
+  *          - CAN_ERRORCODE_NoErr: No Error  
+  *          - CAN_ERRORCODE_StuffErr: Stuff Error
+  *          - CAN_ERRORCODE_FormErr: Form Error
+  *          - CAN_ERRORCODE_ACKErr : Acknowledgment Error
+  *          - CAN_ERRORCODE_BitRecessiveErr: Bit Recessive Error
+  *          - CAN_ERRORCODE_BitDominantErr: Bit Dominant Error
+  *          - CAN_ERRORCODE_CRCErr: CRC Error
+  *          - CAN_ERRORCODE_SoftwareSetErr: Software Set Error  
+  */
+uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx)
+{
+  uint8_t errorcode=0;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  
+  /* Get the error code*/
+  errorcode = (((uint8_t)CANx->ESR) & (uint8_t)CAN_ESR_LEC);
+  
+  /* Return the error code*/
+  return errorcode;
+}
+
+/**
+  * @brief  Returns the CANx Receive Error Counter (REC).
+  * @note   In case of an error during reception, this counter is incremented 
+  *         by 1 or by 8 depending on the error condition as defined by the CAN 
+  *         standard. After every successful reception, the counter is 
+  *         decremented by 1 or reset to 120 if its value was higher than 128. 
+  *         When the counter value exceeds 127, the CAN controller enters the 
+  *         error passive state.  
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.  
+  * @retval CAN Receive Error Counter. 
+  */
+uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx)
+{
+  uint8_t counter=0;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  
+  /* Get the Receive Error Counter*/
+  counter = (uint8_t)((CANx->ESR & CAN_ESR_REC)>> 24);
+  
+  /* Return the Receive Error Counter*/
+  return counter;
+}
+
+
+/**
+  * @brief  Returns the LSB of the 9-bit CANx Transmit Error Counter(TEC).
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @retval LSB of the 9-bit CAN Transmit Error Counter. 
+  */
+uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx)
+{
+  uint8_t counter=0;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  
+  /* Get the LSB of the 9-bit CANx Transmit Error Counter(TEC) */
+  counter = (uint8_t)((CANx->ESR & CAN_ESR_TEC)>> 16);
+  
+  /* Return the LSB of the 9-bit CANx Transmit Error Counter(TEC) */
+  return counter;
+}
+/**
+  * @}
+  */
+
+/** @defgroup CAN_Group6 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+              ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+     [..] This section provides functions allowing to configure the CAN Interrupts 
+          and to get the status and clear flags and Interrupts pending bits.
+  
+          The CAN provides 14 Interrupts sources and 15 Flags:
+
+   
+  *** Flags ***
+  =============
+    [..] The 15 flags can be divided on 4 groups: 
+
+      (+) Transmit Flags
+        (++) CAN_FLAG_RQCP0, 
+        (++) CAN_FLAG_RQCP1, 
+        (++) CAN_FLAG_RQCP2  : Request completed MailBoxes 0, 1 and 2  Flags
+                               Set when when the last request (transmit or abort)
+                               has been performed. 
+
+      (+) Receive Flags
+
+
+        (++) CAN_FLAG_FMP0,
+        (++) CAN_FLAG_FMP1   : FIFO 0 and 1 Message Pending Flags 
+                               set to signal that messages are pending in the receive 
+                               FIFO.
+                               These Flags are cleared only by hardware. 
+
+        (++) CAN_FLAG_FF0,
+        (++) CAN_FLAG_FF1    : FIFO 0 and 1 Full Flags
+                               set when three messages are stored in the selected 
+                               FIFO.                        
+
+        (++) CAN_FLAG_FOV0              
+        (++) CAN_FLAG_FOV1   : FIFO 0 and 1 Overrun Flags
+                               set when a new message has been received and passed 
+                               the filter while the FIFO was full.         
+
+      (+) Operating Mode Flags
+
+        (++) CAN_FLAG_WKU    : Wake up Flag
+                               set to signal that a SOF bit has been detected while 
+                               the CAN hardware was in Sleep mode. 
+        
+        (++) CAN_FLAG_SLAK   : Sleep acknowledge Flag
+                               Set to signal that the CAN has entered Sleep Mode. 
+    
+      (+) Error Flags
+
+        (++) CAN_FLAG_EWG    : Error Warning Flag
+                               Set when the warning limit has been reached (Receive 
+                               Error Counter or Transmit Error Counter greater than 96). 
+                               This Flag is cleared only by hardware.
+                            
+        (++) CAN_FLAG_EPV    : Error Passive Flag
+                               Set when the Error Passive limit has been reached 
+                               (Receive Error Counter or Transmit Error Counter 
+                               greater than 127).
+                               This Flag is cleared only by hardware.
+                             
+        (++) CAN_FLAG_BOF    : Bus-Off Flag
+                               set when CAN enters the bus-off state. The bus-off 
+                               state is entered on TEC overflow, greater than 255.
+                               This Flag is cleared only by hardware.
+                                   
+        (++) CAN_FLAG_LEC    : Last error code Flag
+                               set If a message has been transferred (reception or
+                               transmission) with error, and the error code is hold.              
+                           
+  *** Interrupts ***
+  ==================
+    [..] The 14 interrupts can be divided on 4 groups: 
+  
+      (+) Transmit interrupt
+  
+        (++) CAN_IT_TME   :  Transmit mailbox empty Interrupt
+                             if enabled, this interrupt source is pending when 
+                             no transmit request are pending for Tx mailboxes.      
+
+      (+) Receive Interrupts
+         
+        (++) CAN_IT_FMP0,
+        (++) CAN_IT_FMP1    :  FIFO 0 and FIFO1 message pending Interrupts
+                               if enabled, these interrupt sources are pending 
+                               when messages are pending in the receive FIFO.
+                               The corresponding interrupt pending bits are cleared 
+                               only by hardware.
+                
+        (++) CAN_IT_FF0,              
+        (++) CAN_IT_FF1     :  FIFO 0 and FIFO1 full Interrupts
+                               if enabled, these interrupt sources are pending 
+                               when three messages are stored in the selected FIFO.
+        
+        (++) CAN_IT_FOV0,        
+        (++) CAN_IT_FOV1    :  FIFO 0 and FIFO1 overrun Interrupts        
+                               if enabled, these interrupt sources are pending 
+                               when a new message has been received and passed 
+                               the filter while the FIFO was full.
+
+      (+) Operating Mode Interrupts
+         
+        (++) CAN_IT_WKU     :  Wake-up Interrupt
+                               if enabled, this interrupt source is pending when 
+                               a SOF bit has been detected while the CAN hardware 
+                               was in Sleep mode.
+                                  
+        (++) CAN_IT_SLK     :  Sleep acknowledge Interrupt
+                               if enabled, this interrupt source is pending when 
+                               the CAN has entered Sleep Mode.       
+
+      (+) Error Interrupts 
+        
+        (++) CAN_IT_EWG     :  Error warning Interrupt 
+                               if enabled, this interrupt source is pending when
+                               the warning limit has been reached (Receive Error 
+                               Counter or Transmit Error Counter=96). 
+                               
+        (++) CAN_IT_EPV     :  Error passive Interrupt        
+                               if enabled, this interrupt source is pending when
+                               the Error Passive limit has been reached (Receive 
+                               Error Counter or Transmit Error Counter>127).
+                          
+        (++) CAN_IT_BOF     :  Bus-off Interrupt
+                               if enabled, this interrupt source is pending when
+                               CAN enters the bus-off state. The bus-off state is 
+                               entered on TEC overflow, greater than 255.
+                               This Flag is cleared only by hardware.
+                                  
+        (++) CAN_IT_LEC     :  Last error code Interrupt        
+                               if enabled, this interrupt source is pending  when
+                               a message has been transferred (reception or
+                               transmission) with error, and the error code is hold.
+                          
+        (++) CAN_IT_ERR     :  Error Interrupt
+                               if enabled, this interrupt source is pending when 
+                               an error condition is pending.      
+                      
+    [..] Managing the CAN controller events :
+ 
+         The user should identify which mode will be used in his application to 
+         manage the CAN controller events: Polling mode or Interrupt mode.
+  
+      (#) In the Polling Mode it is advised to use the following functions:
+        (++) CAN_GetFlagStatus() : to check if flags events occur. 
+        (++) CAN_ClearFlag()     : to clear the flags events.
+  
+
+  
+      (#) In the Interrupt Mode it is advised to use the following functions:
+        (++) CAN_ITConfig()       : to enable or disable the interrupt source.
+        (++) CAN_GetITStatus()    : to check if Interrupt occurs.
+        (++) CAN_ClearITPendingBit() : to clear the Interrupt pending Bit 
+            (corresponding Flag).
+        -@@-  This function has no impact on CAN_IT_FMP0 and CAN_IT_FMP1 Interrupts 
+             pending bits since there are cleared only by hardware. 
+  
+@endverbatim
+  * @{
+  */ 
+/**
+  * @brief  Enables or disables the specified CANx interrupts.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_IT: specifies the CAN interrupt sources to be enabled or disabled.
+  *          This parameter can be: 
+  *            @arg CAN_IT_TME: Transmit mailbox empty Interrupt 
+  *            @arg CAN_IT_FMP0: FIFO 0 message pending Interrupt 
+  *            @arg CAN_IT_FF0: FIFO 0 full Interrupt
+  *            @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt
+  *            @arg CAN_IT_FMP1: FIFO 1 message pending Interrupt 
+  *            @arg CAN_IT_FF1: FIFO 1 full Interrupt
+  *            @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt
+  *            @arg CAN_IT_WKU: Wake-up Interrupt
+  *            @arg CAN_IT_SLK: Sleep acknowledge Interrupt  
+  *            @arg CAN_IT_EWG: Error warning Interrupt
+  *            @arg CAN_IT_EPV: Error passive Interrupt
+  *            @arg CAN_IT_BOF: Bus-off Interrupt  
+  *            @arg CAN_IT_LEC: Last error code Interrupt
+  *            @arg CAN_IT_ERR: Error Interrupt
+  * @param  NewState: new state of the CAN interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_IT(CAN_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected CANx interrupt */
+    CANx->IER |= CAN_IT;
+  }
+  else
+  {
+    /* Disable the selected CANx interrupt */
+    CANx->IER &= ~CAN_IT;
+  }
+}
+/**
+  * @brief  Checks whether the specified CAN flag is set or not.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg CAN_FLAG_RQCP0: Request MailBox0 Flag
+  *            @arg CAN_FLAG_RQCP1: Request MailBox1 Flag
+  *            @arg CAN_FLAG_RQCP2: Request MailBox2 Flag
+  *            @arg CAN_FLAG_FMP0: FIFO 0 Message Pending Flag   
+  *            @arg CAN_FLAG_FF0: FIFO 0 Full Flag       
+  *            @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag 
+  *            @arg CAN_FLAG_FMP1: FIFO 1 Message Pending Flag   
+  *            @arg CAN_FLAG_FF1: FIFO 1 Full Flag        
+  *            @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag     
+  *            @arg CAN_FLAG_WKU: Wake up Flag
+  *            @arg CAN_FLAG_SLAK: Sleep acknowledge Flag 
+  *            @arg CAN_FLAG_EWG: Error Warning Flag
+  *            @arg CAN_FLAG_EPV: Error Passive Flag  
+  *            @arg CAN_FLAG_BOF: Bus-Off Flag    
+  *            @arg CAN_FLAG_LEC: Last error code Flag      
+  * @retval The new state of CAN_FLAG (SET or RESET).
+  */
+FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_GET_FLAG(CAN_FLAG));
+  
+
+  if((CAN_FLAG & CAN_FLAGS_ESR) != (uint32_t)RESET)
+  { 
+    /* Check the status of the specified CAN flag */
+    if ((CANx->ESR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET)
+    { 
+      /* CAN_FLAG is set */
+      bitstatus = SET;
+    }
+    else
+    { 
+      /* CAN_FLAG is reset */
+      bitstatus = RESET;
+    }
+  }
+  else if((CAN_FLAG & CAN_FLAGS_MSR) != (uint32_t)RESET)
+  { 
+    /* Check the status of the specified CAN flag */
+    if ((CANx->MSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET)
+    { 
+      /* CAN_FLAG is set */
+      bitstatus = SET;
+    }
+    else
+    { 
+      /* CAN_FLAG is reset */
+      bitstatus = RESET;
+    }
+  }
+  else if((CAN_FLAG & CAN_FLAGS_TSR) != (uint32_t)RESET)
+  { 
+    /* Check the status of the specified CAN flag */
+    if ((CANx->TSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET)
+    { 
+      /* CAN_FLAG is set */
+      bitstatus = SET;
+    }
+    else
+    { 
+      /* CAN_FLAG is reset */
+      bitstatus = RESET;
+    }
+  }
+  else if((CAN_FLAG & CAN_FLAGS_RF0R) != (uint32_t)RESET)
+  { 
+    /* Check the status of the specified CAN flag */
+    if ((CANx->RF0R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET)
+    { 
+      /* CAN_FLAG is set */
+      bitstatus = SET;
+    }
+    else
+    { 
+      /* CAN_FLAG is reset */
+      bitstatus = RESET;
+    }
+  }
+  else /* If(CAN_FLAG & CAN_FLAGS_RF1R != (uint32_t)RESET) */
+  { 
+    /* Check the status of the specified CAN flag */
+    if ((uint32_t)(CANx->RF1R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET)
+    { 
+      /* CAN_FLAG is set */
+      bitstatus = SET;
+    }
+    else
+    { 
+      /* CAN_FLAG is reset */
+      bitstatus = RESET;
+    }
+  }
+  /* Return the CAN_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the CAN's pending flags.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_FLAG: specifies the flag to clear.
+  *          This parameter can be one of the following values:
+  *            @arg CAN_FLAG_RQCP0: Request MailBox0 Flag
+  *            @arg CAN_FLAG_RQCP1: Request MailBox1 Flag
+  *            @arg CAN_FLAG_RQCP2: Request MailBox2 Flag 
+  *            @arg CAN_FLAG_FF0: FIFO 0 Full Flag       
+  *            @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag  
+  *            @arg CAN_FLAG_FF1: FIFO 1 Full Flag        
+  *            @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag     
+  *            @arg CAN_FLAG_WKU: Wake up Flag
+  *            @arg CAN_FLAG_SLAK: Sleep acknowledge Flag    
+  *            @arg CAN_FLAG_LEC: Last error code Flag        
+  * @retval None
+  */
+void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG)
+{
+  uint32_t flagtmp=0;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_CLEAR_FLAG(CAN_FLAG));
+  
+  if (CAN_FLAG == CAN_FLAG_LEC) /* ESR register */
+  {
+    /* Clear the selected CAN flags */
+    CANx->ESR = (uint32_t)RESET;
+  }
+  else /* MSR or TSR or RF0R or RF1R */
+  {
+    flagtmp = CAN_FLAG & 0x000FFFFF;
+
+    if ((CAN_FLAG & CAN_FLAGS_RF0R)!=(uint32_t)RESET)
+    {
+      /* Receive Flags */
+      CANx->RF0R = (uint32_t)(flagtmp);
+    }
+    else if ((CAN_FLAG & CAN_FLAGS_RF1R)!=(uint32_t)RESET)
+    {
+      /* Receive Flags */
+      CANx->RF1R = (uint32_t)(flagtmp);
+    }
+    else if ((CAN_FLAG & CAN_FLAGS_TSR)!=(uint32_t)RESET)
+    {
+      /* Transmit Flags */
+      CANx->TSR = (uint32_t)(flagtmp);
+    }
+    else /* If((CAN_FLAG & CAN_FLAGS_MSR)!=(uint32_t)RESET) */
+    {
+      /* Operating mode Flags */
+      CANx->MSR = (uint32_t)(flagtmp);
+    }
+  }
+}
+
+/**
+  * @brief  Checks whether the specified CANx interrupt has occurred or not.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_IT: specifies the CAN interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg CAN_IT_TME: Transmit mailbox empty Interrupt 
+  *            @arg CAN_IT_FMP0: FIFO 0 message pending Interrupt 
+  *            @arg CAN_IT_FF0: FIFO 0 full Interrupt
+  *            @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt
+  *            @arg CAN_IT_FMP1: FIFO 1 message pending Interrupt 
+  *            @arg CAN_IT_FF1: FIFO 1 full Interrupt
+  *            @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt
+  *            @arg CAN_IT_WKU: Wake-up Interrupt
+  *            @arg CAN_IT_SLK: Sleep acknowledge Interrupt  
+  *            @arg CAN_IT_EWG: Error warning Interrupt
+  *            @arg CAN_IT_EPV: Error passive Interrupt
+  *            @arg CAN_IT_BOF: Bus-off Interrupt  
+  *            @arg CAN_IT_LEC: Last error code Interrupt
+  *            @arg CAN_IT_ERR: Error Interrupt
+  * @retval The current state of CAN_IT (SET or RESET).
+  */
+ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT)
+{
+  ITStatus itstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_IT(CAN_IT));
+  
+  /* check the interrupt enable bit */
+ if((CANx->IER & CAN_IT) != RESET)
+ {
+   /* in case the Interrupt is enabled, .... */
+    switch (CAN_IT)
+    {
+      case CAN_IT_TME:
+        /* Check CAN_TSR_RQCPx bits */
+        itstatus = CheckITStatus(CANx->TSR, CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2);  
+        break;
+      case CAN_IT_FMP0:
+        /* Check CAN_RF0R_FMP0 bit */
+        itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FMP0);  
+        break;
+      case CAN_IT_FF0:
+        /* Check CAN_RF0R_FULL0 bit */
+        itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FULL0);  
+        break;
+      case CAN_IT_FOV0:
+        /* Check CAN_RF0R_FOVR0 bit */
+        itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FOVR0);  
+        break;
+      case CAN_IT_FMP1:
+        /* Check CAN_RF1R_FMP1 bit */
+        itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FMP1);  
+        break;
+      case CAN_IT_FF1:
+        /* Check CAN_RF1R_FULL1 bit */
+        itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FULL1);  
+        break;
+      case CAN_IT_FOV1:
+        /* Check CAN_RF1R_FOVR1 bit */
+        itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FOVR1);  
+        break;
+      case CAN_IT_WKU:
+        /* Check CAN_MSR_WKUI bit */
+        itstatus = CheckITStatus(CANx->MSR, CAN_MSR_WKUI);  
+        break;
+      case CAN_IT_SLK:
+        /* Check CAN_MSR_SLAKI bit */
+        itstatus = CheckITStatus(CANx->MSR, CAN_MSR_SLAKI);  
+        break;
+      case CAN_IT_EWG:
+        /* Check CAN_ESR_EWGF bit */
+        itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF);  
+        break;
+      case CAN_IT_EPV:
+        /* Check CAN_ESR_EPVF bit */
+        itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EPVF);  
+        break;
+      case CAN_IT_BOF:
+        /* Check CAN_ESR_BOFF bit */
+        itstatus = CheckITStatus(CANx->ESR, CAN_ESR_BOFF);  
+        break;
+      case CAN_IT_LEC:
+        /* Check CAN_ESR_LEC bit */
+        itstatus = CheckITStatus(CANx->ESR, CAN_ESR_LEC);  
+        break;
+      case CAN_IT_ERR:
+        /* Check CAN_MSR_ERRI bit */ 
+        itstatus = CheckITStatus(CANx->MSR, CAN_MSR_ERRI); 
+        break;
+      default:
+        /* in case of error, return RESET */
+        itstatus = RESET;
+        break;
+    }
+  }
+  else
+  {
+   /* in case the Interrupt is not enabled, return RESET */
+    itstatus  = RESET;
+  }
+  
+  /* Return the CAN_IT status */
+  return  itstatus;
+}
+
+/**
+  * @brief  Clears the CANx's interrupt pending bits.
+  * @param  CANx: where x can be 1 or 2 to to select the CAN peripheral.
+  * @param  CAN_IT: specifies the interrupt pending bit to clear.
+  *          This parameter can be one of the following values:
+  *            @arg CAN_IT_TME: Transmit mailbox empty Interrupt
+  *            @arg CAN_IT_FF0: FIFO 0 full Interrupt
+  *            @arg CAN_IT_FOV0: FIFO 0 overrun Interrupt
+  *            @arg CAN_IT_FF1: FIFO 1 full Interrupt
+  *            @arg CAN_IT_FOV1: FIFO 1 overrun Interrupt
+  *            @arg CAN_IT_WKU: Wake-up Interrupt
+  *            @arg CAN_IT_SLK: Sleep acknowledge Interrupt  
+  *            @arg CAN_IT_EWG: Error warning Interrupt
+  *            @arg CAN_IT_EPV: Error passive Interrupt
+  *            @arg CAN_IT_BOF: Bus-off Interrupt  
+  *            @arg CAN_IT_LEC: Last error code Interrupt
+  *            @arg CAN_IT_ERR: Error Interrupt 
+  * @retval None
+  */
+void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_CAN_ALL_PERIPH(CANx));
+  assert_param(IS_CAN_CLEAR_IT(CAN_IT));
+
+  switch (CAN_IT)
+  {
+    case CAN_IT_TME:
+      /* Clear CAN_TSR_RQCPx (rc_w1)*/
+      CANx->TSR = CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2;  
+      break;
+    case CAN_IT_FF0:
+      /* Clear CAN_RF0R_FULL0 (rc_w1)*/
+      CANx->RF0R = CAN_RF0R_FULL0; 
+      break;
+    case CAN_IT_FOV0:
+      /* Clear CAN_RF0R_FOVR0 (rc_w1)*/
+      CANx->RF0R = CAN_RF0R_FOVR0; 
+      break;
+    case CAN_IT_FF1:
+      /* Clear CAN_RF1R_FULL1 (rc_w1)*/
+      CANx->RF1R = CAN_RF1R_FULL1;  
+      break;
+    case CAN_IT_FOV1:
+      /* Clear CAN_RF1R_FOVR1 (rc_w1)*/
+      CANx->RF1R = CAN_RF1R_FOVR1; 
+      break;
+    case CAN_IT_WKU:
+      /* Clear CAN_MSR_WKUI (rc_w1)*/
+      CANx->MSR = CAN_MSR_WKUI;  
+      break;
+    case CAN_IT_SLK:
+      /* Clear CAN_MSR_SLAKI (rc_w1)*/ 
+      CANx->MSR = CAN_MSR_SLAKI;   
+      break;
+    case CAN_IT_EWG:
+      /* Clear CAN_MSR_ERRI (rc_w1) */
+      CANx->MSR = CAN_MSR_ERRI;
+       /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/ 
+      break;
+    case CAN_IT_EPV:
+      /* Clear CAN_MSR_ERRI (rc_w1) */
+      CANx->MSR = CAN_MSR_ERRI; 
+       /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/
+      break;
+    case CAN_IT_BOF:
+      /* Clear CAN_MSR_ERRI (rc_w1) */ 
+      CANx->MSR = CAN_MSR_ERRI; 
+       /* @note the corresponding Flag is cleared by hardware depending on the CAN Bus status*/
+       break;
+    case CAN_IT_LEC:
+      /*  Clear LEC bits */
+      CANx->ESR = RESET; 
+      /* Clear CAN_MSR_ERRI (rc_w1) */
+      CANx->MSR = CAN_MSR_ERRI; 
+      break;
+    case CAN_IT_ERR:
+      /*Clear LEC bits */
+      CANx->ESR = RESET; 
+      /* Clear CAN_MSR_ERRI (rc_w1) */
+      CANx->MSR = CAN_MSR_ERRI; 
+       /* @note BOFF, EPVF and EWGF Flags are cleared by hardware depending on the CAN Bus status*/
+       break;
+    default:
+       break;
+   }
+}
+ /**
+  * @}
+  */
+
+/**
+  * @brief  Checks whether the CAN interrupt has occurred or not.
+  * @param  CAN_Reg: specifies the CAN interrupt register to check.
+  * @param  It_Bit: specifies the interrupt source bit to check.
+  * @retval The new state of the CAN Interrupt (SET or RESET).
+  */
+static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit)
+{
+  ITStatus pendingbitstatus = RESET;
+  
+  if ((CAN_Reg & It_Bit) != (uint32_t)RESET)
+  {
+    /* CAN_IT is set */
+    pendingbitstatus = SET;
+  }
+  else
+  {
+    /* CAN_IT is reset */
+    pendingbitstatus = RESET;
+  }
+  return pendingbitstatus;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c
new file mode 100644
index 0000000000000000000000000000000000000000..deb05ee5656b0172aeef2c7802b54ea181a82114
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_crc.c
@@ -0,0 +1,133 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_crc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides all the CRC firmware functions.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_crc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CRC 
+  * @brief CRC driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup CRC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Resets the CRC Data register (DR).
+  * @param  None
+  * @retval None
+  */
+void CRC_ResetDR(void)
+{
+  /* Reset CRC generator */
+  CRC->CR = CRC_CR_RESET;
+}
+
+/**
+  * @brief  Computes the 32-bit CRC of a given data word(32-bit).
+  * @param  Data: data word(32-bit) to compute its CRC
+  * @retval 32-bit CRC
+  */
+uint32_t CRC_CalcCRC(uint32_t Data)
+{
+  CRC->DR = Data;
+  
+  return (CRC->DR);
+}
+
+/**
+  * @brief  Computes the 32-bit CRC of a given buffer of data word(32-bit).
+  * @param  pBuffer: pointer to the buffer containing the data to be computed
+  * @param  BufferLength: length of the buffer to be computed					
+  * @retval 32-bit CRC
+  */
+uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength)
+{
+  uint32_t index = 0;
+  
+  for(index = 0; index < BufferLength; index++)
+  {
+    CRC->DR = pBuffer[index];
+  }
+  return (CRC->DR);
+}
+
+/**
+  * @brief  Returns the current CRC value.
+  * @param  None
+  * @retval 32-bit CRC
+  */
+uint32_t CRC_GetCRC(void)
+{
+  return (CRC->DR);
+}
+
+/**
+  * @brief  Stores a 8-bit data in the Independent Data(ID) register.
+  * @param  IDValue: 8-bit value to be stored in the ID register 					
+  * @retval None
+  */
+void CRC_SetIDRegister(uint8_t IDValue)
+{
+  CRC->IDR = IDValue;
+}
+
+/**
+  * @brief  Returns the 8-bit data stored in the Independent Data(ID) register
+  * @param  None
+  * @retval 8-bit value of the ID register 
+  */
+uint8_t CRC_GetIDRegister(void)
+{
+  return (CRC->IDR);
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c
new file mode 100644
index 0000000000000000000000000000000000000000..348c24167d18fd72ce2e9abd4f8ec3f7655ff66c
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp.c
@@ -0,0 +1,934 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_cryp.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the  Cryptographic processor (CRYP) peripheral:           
+  *           + Initialization and Configuration functions
+  *           + Data treatment functions 
+  *           + Context swapping functions     
+  *           + DMA interface function       
+  *           + Interrupts and flags management       
+  *
+@verbatim
+ ===================================================================      
+                 ##### How to use this driver #####
+ =================================================================== 
+ [..]
+   (#) Enable the CRYP controller clock using 
+       RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function.
+  
+   (#) Initialise the CRYP using CRYP_Init(), CRYP_KeyInit() and if needed 
+       CRYP_IVInit(). 
+  
+   (#) Flush the IN and OUT FIFOs by using CRYP_FIFOFlush() function.
+  
+   (#) Enable the CRYP controller using the CRYP_Cmd() function. 
+  
+   (#) If using DMA for Data input and output transfer, activate the needed DMA 
+       Requests using CRYP_DMACmd() function 
+  
+   (#) If DMA is not used for data transfer, use CRYP_DataIn() and  CRYP_DataOut() 
+       functions to enter data to IN FIFO and get result from OUT FIFO.
+  
+   (#) To control CRYP events you can use one of the following two methods:
+       (++) Check on CRYP flags using the CRYP_GetFlagStatus() function.  
+       (++) Use CRYP interrupts through the function CRYP_ITConfig() at 
+            initialization phase and CRYP_GetITStatus() function into interrupt 
+            routines in processing phase.
+         
+   (#) Save and restore Cryptographic processor context using CRYP_SaveContext() 
+       and CRYP_RestoreContext() functions.     
+  
+  
+ *** Procedure to perform an encryption or a decryption ***
+ ========================================================== 
+  
+ *** Initialization ***
+ ====================== 
+ [..] 
+   (#) Initialize the peripheral using CRYP_Init(), CRYP_KeyInit() and CRYP_IVInit 
+       functions:
+       (++) Configure the key size (128-, 192- or 256-bit, in the AES only) 
+       (++) Enter the symmetric key 
+       (++) Configure the data type
+       (++) In case of decryption in AES-ECB or AES-CBC, you must prepare 
+            the key: configure the key preparation mode. Then Enable the CRYP 
+            peripheral using CRYP_Cmd() function: the BUSY flag is set. 
+            Wait until BUSY flag is reset : the key is prepared for decryption
+       (++) Configure the algorithm and chaining (the DES/TDES in ECB/CBC, the 
+            AES in ECB/CBC/CTR) 
+       (++) Configure the direction (encryption/decryption).
+       (++) Write the initialization vectors (in CBC or CTR modes only)
+  
+   (#) Flush the IN and OUT FIFOs using the CRYP_FIFOFlush() function
+  
+  
+  *** Basic Processing mode (polling mode) *** 
+  ============================================  
+  [..]
+    (#) Enable the cryptographic processor using CRYP_Cmd() function.
+  
+    (#) Write the first blocks in the input FIFO (2 to 8 words) using 
+        CRYP_DataIn() function.
+  
+    (#) Repeat the following sequence until the complete message has been 
+        processed:
+  
+        (++) Wait for flag CRYP_FLAG_OFNE occurs (using CRYP_GetFlagStatus() 
+            function), then read the OUT-FIFO using CRYP_DataOut() function
+            (1 block or until the FIFO is empty)
+  
+         (++) Wait for flag CRYP_FLAG_IFNF occurs, (using CRYP_GetFlagStatus() 
+            function then write the IN FIFO using CRYP_DataIn() function 
+            (1 block or until the FIFO is full)
+  
+    (#) At the end of the processing, CRYP_FLAG_BUSY flag will be reset and 
+          both FIFOs are empty (CRYP_FLAG_IFEM is set and CRYP_FLAG_OFNE is 
+          reset). You can disable the peripheral using CRYP_Cmd() function.
+  
+ *** Interrupts Processing mode *** 
+ ==================================
+ [..] In this mode, Processing is done when the data are transferred by the 
+      CPU during interrupts.
+  
+    (#) Enable the interrupts CRYP_IT_INI and CRYP_IT_OUTI using CRYP_ITConfig()
+        function.
+  
+    (#) Enable the cryptographic processor using CRYP_Cmd() function.
+  
+    (#) In the CRYP_IT_INI interrupt handler : load the input message into the 
+         IN FIFO using CRYP_DataIn() function . You can load 2 or 4 words at a 
+         time, or load data until the IN FIFO is full. When the last word of
+         the message has been entered into the IN FIFO, disable the CRYP_IT_INI 
+         interrupt (using CRYP_ITConfig() function).
+  
+    (#) In the CRYP_IT_OUTI interrupt handler : read the output message from 
+         the OUT FIFO using CRYP_DataOut() function. You can read 1 block (2 or 
+         4 words) at a time or read data until the FIFO is empty.
+         When the last word has been read, INIM=0, BUSY=0 and both FIFOs are 
+         empty (CRYP_FLAG_IFEM is set and CRYP_FLAG_OFNE is reset). 
+         You can disable the CRYP_IT_OUTI interrupt (using CRYP_ITConfig() 
+         function) and you can disable the peripheral using CRYP_Cmd() function.
+  
+ *** DMA Processing mode *** 
+ ===========================
+ [..] In this mode, Processing is done when the DMA is used to transfer the 
+      data from/to the memory.
+  
+    (#) Configure the DMA controller to transfer the input data from the 
+         memory using DMA_Init() function. 
+         The transfer length is the length of the message. 
+         As message padding is not managed by the peripheral, the message 
+         length must be an entire number of blocks. The data are transferred 
+         in burst mode. The burst length is 4 words in the AES and 2 or 4 
+         words in the DES/TDES. The DMA should be configured to set an 
+         interrupt on transfer completion of the output data to indicate that 
+         the processing is finished. 
+         Refer to DMA peripheral driver for more details.  
+  
+     (#) Enable the cryptographic processor using CRYP_Cmd() function. 
+         Enable the DMA requests CRYP_DMAReq_DataIN and CRYP_DMAReq_DataOUT 
+         using CRYP_DMACmd() function.
+  
+     (#) All the transfers and processing are managed by the DMA and the 
+         cryptographic processor. The DMA transfer complete interrupt indicates 
+         that the processing is complete. Both FIFOs are normally empty and 
+         CRYP_FLAG_BUSY flag is reset.
+  
+    @endverbatim
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_cryp.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CRYP 
+  * @brief CRYP driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define FLAG_MASK     ((uint8_t)0x20)
+#define MAX_TIMEOUT   ((uint16_t)0xFFFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup CRYP_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup CRYP_Group1 Initialization and Configuration functions
+ *  @brief    Initialization and Configuration functions 
+ *
+@verbatim    
+ ===============================================================================
+             ##### Initialization and Configuration functions #####
+ ===============================================================================  
+ [..] This section provides functions allowing to 
+   (+) Initialize the cryptographic Processor using CRYP_Init() function 
+       (++)  Encrypt or Decrypt 
+       (++)  mode : TDES-ECB, TDES-CBC, 
+                    DES-ECB, DES-CBC, 
+                    AES-ECB, AES-CBC, AES-CTR, AES-Key, AES-GCM, AES-CCM 
+       (++) DataType :  32-bit data, 16-bit data, bit data or bit-string
+       (++) Key Size (only in AES modes)
+   (+) Configure the Encrypt or Decrypt Key using CRYP_KeyInit() function 
+   (+) Configure the Initialization Vectors(IV) for CBC and CTR modes using 
+       CRYP_IVInit() function.  
+   (+) Flushes the IN and OUT FIFOs : using CRYP_FIFOFlush() function.                         
+   (+) Enable or disable the CRYP Processor using CRYP_Cmd() function 
+       
+@endverbatim
+  * @{
+  */
+/**
+  * @brief  Deinitializes the CRYP peripheral registers to their default reset values
+  * @param  None
+  * @retval None
+  */
+void CRYP_DeInit(void)
+{
+  /* Enable CRYP reset state */
+  RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_CRYP, ENABLE);
+
+  /* Release CRYP from reset state */
+  RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_CRYP, DISABLE);
+}
+
+/**
+  * @brief  Initializes the CRYP peripheral according to the specified parameters
+  *         in the CRYP_InitStruct.
+  * @param  CRYP_InitStruct: pointer to a CRYP_InitTypeDef structure that contains
+  *         the configuration information for the CRYP peripheral.
+  * @retval None
+  */
+void CRYP_Init(CRYP_InitTypeDef* CRYP_InitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_CRYP_ALGOMODE(CRYP_InitStruct->CRYP_AlgoMode));
+  assert_param(IS_CRYP_DATATYPE(CRYP_InitStruct->CRYP_DataType));
+  assert_param(IS_CRYP_ALGODIR(CRYP_InitStruct->CRYP_AlgoDir));
+
+  /* Select Algorithm mode*/  
+  CRYP->CR &= ~CRYP_CR_ALGOMODE;
+  CRYP->CR |= CRYP_InitStruct->CRYP_AlgoMode;
+
+  /* Select dataType */ 
+  CRYP->CR &= ~CRYP_CR_DATATYPE;
+  CRYP->CR |= CRYP_InitStruct->CRYP_DataType;
+
+  /* select Key size (used only with AES algorithm) */
+  if ((CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_TDES_ECB) &&
+      (CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_TDES_CBC) &&
+      (CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_DES_ECB) &&
+      (CRYP_InitStruct->CRYP_AlgoMode != CRYP_AlgoMode_DES_CBC))
+  {
+    assert_param(IS_CRYP_KEYSIZE(CRYP_InitStruct->CRYP_KeySize));
+    CRYP->CR &= ~CRYP_CR_KEYSIZE;
+    CRYP->CR |= CRYP_InitStruct->CRYP_KeySize; /* Key size and value must be 
+                                                  configured once the key has 
+                                                  been prepared */
+  }
+
+  /* Select data Direction */ 
+  CRYP->CR &= ~CRYP_CR_ALGODIR;
+  CRYP->CR |= CRYP_InitStruct->CRYP_AlgoDir;
+}
+
+/**
+  * @brief  Fills each CRYP_InitStruct member with its default value.
+  * @param  CRYP_InitStruct: pointer to a CRYP_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void CRYP_StructInit(CRYP_InitTypeDef* CRYP_InitStruct)
+{
+  /* Initialize the CRYP_AlgoDir member */
+  CRYP_InitStruct->CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
+
+  /* initialize the CRYP_AlgoMode member */
+  CRYP_InitStruct->CRYP_AlgoMode = CRYP_AlgoMode_TDES_ECB;
+
+  /* initialize the CRYP_DataType member */
+  CRYP_InitStruct->CRYP_DataType = CRYP_DataType_32b;
+  
+  /* Initialize the CRYP_KeySize member */
+  CRYP_InitStruct->CRYP_KeySize = CRYP_KeySize_128b;
+}
+
+/**
+  * @brief  Initializes the CRYP Keys according to the specified parameters in
+  *         the CRYP_KeyInitStruct.
+  * @param  CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure that
+  *         contains the configuration information for the CRYP Keys.
+  * @retval None
+  */
+void CRYP_KeyInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct)
+{
+  /* Key Initialisation */
+  CRYP->K0LR = CRYP_KeyInitStruct->CRYP_Key0Left;
+  CRYP->K0RR = CRYP_KeyInitStruct->CRYP_Key0Right;
+  CRYP->K1LR = CRYP_KeyInitStruct->CRYP_Key1Left;
+  CRYP->K1RR = CRYP_KeyInitStruct->CRYP_Key1Right;
+  CRYP->K2LR = CRYP_KeyInitStruct->CRYP_Key2Left;
+  CRYP->K2RR = CRYP_KeyInitStruct->CRYP_Key2Right;
+  CRYP->K3LR = CRYP_KeyInitStruct->CRYP_Key3Left;
+  CRYP->K3RR = CRYP_KeyInitStruct->CRYP_Key3Right;
+}
+
+/**
+  * @brief  Fills each CRYP_KeyInitStruct member with its default value.
+  * @param  CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure 
+  *         which will be initialized.
+  * @retval None
+  */
+void CRYP_KeyStructInit(CRYP_KeyInitTypeDef* CRYP_KeyInitStruct)
+{
+  CRYP_KeyInitStruct->CRYP_Key0Left  = 0;
+  CRYP_KeyInitStruct->CRYP_Key0Right = 0;
+  CRYP_KeyInitStruct->CRYP_Key1Left  = 0;
+  CRYP_KeyInitStruct->CRYP_Key1Right = 0;
+  CRYP_KeyInitStruct->CRYP_Key2Left  = 0;
+  CRYP_KeyInitStruct->CRYP_Key2Right = 0;
+  CRYP_KeyInitStruct->CRYP_Key3Left  = 0;
+  CRYP_KeyInitStruct->CRYP_Key3Right = 0;
+}
+/**
+  * @brief  Initializes the CRYP Initialization Vectors(IV) according to the
+  *         specified parameters in the CRYP_IVInitStruct.
+  * @param  CRYP_IVInitStruct: pointer to a CRYP_IVInitTypeDef structure that contains
+  *         the configuration information for the CRYP Initialization Vectors(IV).
+  * @retval None
+  */
+void CRYP_IVInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct)
+{
+  CRYP->IV0LR = CRYP_IVInitStruct->CRYP_IV0Left;
+  CRYP->IV0RR = CRYP_IVInitStruct->CRYP_IV0Right;
+  CRYP->IV1LR = CRYP_IVInitStruct->CRYP_IV1Left;
+  CRYP->IV1RR = CRYP_IVInitStruct->CRYP_IV1Right;
+}
+
+/**
+  * @brief  Fills each CRYP_IVInitStruct member with its default value.
+  * @param  CRYP_IVInitStruct: pointer to a CRYP_IVInitTypeDef Initialization 
+  *         Vectors(IV) structure which will be initialized.
+  * @retval None
+  */
+void CRYP_IVStructInit(CRYP_IVInitTypeDef* CRYP_IVInitStruct)
+{
+  CRYP_IVInitStruct->CRYP_IV0Left  = 0;
+  CRYP_IVInitStruct->CRYP_IV0Right = 0;
+  CRYP_IVInitStruct->CRYP_IV1Left  = 0;
+  CRYP_IVInitStruct->CRYP_IV1Right = 0;
+}
+
+/**
+  * @brief  Configures the AES-CCM and AES-GCM phases
+  * @note   This function is used only with AES-CCM or AES-GCM Algorithms  
+  * @param  CRYP_Phase: specifies the CRYP AES-CCM and AES-GCM phase to be configured.
+  *           This parameter can be one of the following values:
+  *            @arg CRYP_Phase_Init: Initialization phase
+  *            @arg CRYP_Phase_Header: Header phase
+  *            @arg CRYP_Phase_Payload: Payload phase
+  *            @arg CRYP_Phase_Final: Final phase 
+  * @retval None
+  */
+void CRYP_PhaseConfig(uint32_t CRYP_Phase)
+{ uint32_t tempcr = 0;
+
+  /* Check the parameter */
+  assert_param(IS_CRYP_PHASE(CRYP_Phase));
+
+  /* Get the CR register */
+  tempcr = CRYP->CR;
+  
+  /* Reset the phase configuration bits: GCMP_CCMPH */
+  tempcr &= (uint32_t)(~CRYP_CR_GCM_CCMPH);
+  /* Set the selected phase */
+  tempcr |= (uint32_t)CRYP_Phase;
+
+  /* Set the CR register */ 
+  CRYP->CR = tempcr;    
+}
+
+/**
+  * @brief  Flushes the IN and OUT FIFOs (that is read and write pointers of the 
+  *         FIFOs are reset)
+  * @note   The FIFOs must be flushed only when BUSY flag is reset.  
+  * @param  None
+  * @retval None
+  */
+void CRYP_FIFOFlush(void)
+{
+  /* Reset the read and write pointers of the FIFOs */
+  CRYP->CR |= CRYP_CR_FFLUSH;
+}
+
+/**
+  * @brief  Enables or disables the CRYP peripheral.
+  * @param  NewState: new state of the CRYP peripheral.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void CRYP_Cmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the Cryptographic processor */
+    CRYP->CR |= CRYP_CR_CRYPEN;
+  }
+  else
+  {
+    /* Disable the Cryptographic processor */
+    CRYP->CR &= ~CRYP_CR_CRYPEN;
+  }
+}
+/**
+  * @}
+  */
+  
+/** @defgroup CRYP_Group2 CRYP Data processing functions
+ *  @brief    CRYP Data processing functions
+ *
+@verbatim    
+ ===============================================================================
+                    ##### CRYP Data processing functions #####
+ ===============================================================================  
+ [..] This section provides functions allowing the encryption and decryption 
+      operations: 
+   (+) Enter data to be treated in the IN FIFO : using CRYP_DataIn() function.
+   (+) Get the data result from the OUT FIFO : using CRYP_DataOut() function.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Writes data in the Data Input register (DIN).
+  * @note   After the DIN register has been read once or several times, 
+  *         the FIFO must be flushed (using CRYP_FIFOFlush() function).  
+  * @param  Data: data to write in Data Input register
+  * @retval None
+  */
+void CRYP_DataIn(uint32_t Data)
+{
+  CRYP->DR = Data;
+}
+
+/**
+  * @brief  Returns the last data entered into the output FIFO.
+  * @param  None
+  * @retval Last data entered into the output FIFO.
+  */
+uint32_t CRYP_DataOut(void)
+{
+  return CRYP->DOUT;
+}
+/**
+  * @}
+  */
+  
+/** @defgroup CRYP_Group3 Context swapping functions
+ *  @brief   Context swapping functions
+ *
+@verbatim   
+ ===============================================================================
+                      ##### Context swapping functions #####
+ ===============================================================================  
+ [..] This section provides functions allowing to save and store CRYP Context
+
+ [..] It is possible to interrupt an encryption/ decryption/ key generation process 
+      to perform another processing with a higher priority, and to complete the 
+      interrupted process later on, when the higher-priority task is complete. To do 
+      so, the context of the interrupted task must be saved from the CRYP registers 
+      to memory, and then be restored from memory to the CRYP registers.
+   
+   (#) To save the current context, use CRYP_SaveContext() function
+   (#) To restore the saved context, use CRYP_RestoreContext() function 
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Saves the CRYP peripheral Context. 
+  * @note   This function stops DMA transfer before to save the context. After 
+  *         restoring the context, you have to enable the DMA again (if the DMA
+  *         was previously used).
+  * @param  CRYP_ContextSave: pointer to a CRYP_Context structure that contains
+  *         the repository for current context.
+  * @param  CRYP_KeyInitStruct: pointer to a CRYP_KeyInitTypeDef structure that 
+  *         contains the configuration information for the CRYP Keys.  
+  * @retval None
+  */
+ErrorStatus CRYP_SaveContext(CRYP_Context* CRYP_ContextSave,
+                             CRYP_KeyInitTypeDef* CRYP_KeyInitStruct)
+{
+  __IO uint32_t timeout = 0;
+  uint32_t ckeckmask = 0, bitstatus;    
+  ErrorStatus status = ERROR;
+
+  /* Stop DMA transfers on the IN FIFO by clearing the DIEN bit in the CRYP_DMACR */
+  CRYP->DMACR &= ~(uint32_t)CRYP_DMACR_DIEN;
+    
+  /* Wait until both the IN and OUT FIFOs are empty  
+    (IFEM=1 and OFNE=0 in the CRYP_SR register) and the 
+     BUSY bit is cleared. */
+
+  if ((CRYP->CR & (uint32_t)(CRYP_CR_ALGOMODE_TDES_ECB | CRYP_CR_ALGOMODE_TDES_CBC)) != (uint32_t)0 )/* TDES */
+  { 
+    ckeckmask =  CRYP_SR_IFEM | CRYP_SR_BUSY ;
+  }
+  else /* AES or DES */
+  {
+    ckeckmask =  CRYP_SR_IFEM | CRYP_SR_BUSY | CRYP_SR_OFNE;
+  }           
+   
+  do 
+  {
+    bitstatus = CRYP->SR & ckeckmask;
+    timeout++;
+  }
+  while ((timeout != MAX_TIMEOUT) && (bitstatus != CRYP_SR_IFEM));
+     
+  if ((CRYP->SR & ckeckmask) != CRYP_SR_IFEM)
+  {
+    status = ERROR;
+  }
+  else
+  {      
+    /* Stop DMA transfers on the OUT FIFO by 
+       - writing the DOEN bit to 0 in the CRYP_DMACR register 
+       - and clear the CRYPEN bit. */
+
+    CRYP->DMACR &= ~(uint32_t)CRYP_DMACR_DOEN;
+    CRYP->CR &= ~(uint32_t)CRYP_CR_CRYPEN;
+
+    /* Save the current configuration (bit 19, bit[17:16] and bits [9:2] in the CRYP_CR register) */
+    CRYP_ContextSave->CR_CurrentConfig  = CRYP->CR & (CRYP_CR_GCM_CCMPH |
+                                                      CRYP_CR_KEYSIZE  |
+                                                      CRYP_CR_DATATYPE |
+                                                      CRYP_CR_ALGOMODE |
+                                                      CRYP_CR_ALGODIR);
+
+    /* and, if not in ECB mode, the initialization vectors. */
+    CRYP_ContextSave->CRYP_IV0LR = CRYP->IV0LR;
+    CRYP_ContextSave->CRYP_IV0RR = CRYP->IV0RR;
+    CRYP_ContextSave->CRYP_IV1LR = CRYP->IV1LR;
+    CRYP_ContextSave->CRYP_IV1RR = CRYP->IV1RR;
+
+    /* save The key value */
+    CRYP_ContextSave->CRYP_K0LR = CRYP_KeyInitStruct->CRYP_Key0Left; 
+    CRYP_ContextSave->CRYP_K0RR = CRYP_KeyInitStruct->CRYP_Key0Right; 
+    CRYP_ContextSave->CRYP_K1LR = CRYP_KeyInitStruct->CRYP_Key1Left; 
+    CRYP_ContextSave->CRYP_K1RR = CRYP_KeyInitStruct->CRYP_Key1Right; 
+    CRYP_ContextSave->CRYP_K2LR = CRYP_KeyInitStruct->CRYP_Key2Left; 
+    CRYP_ContextSave->CRYP_K2RR = CRYP_KeyInitStruct->CRYP_Key2Right; 
+    CRYP_ContextSave->CRYP_K3LR = CRYP_KeyInitStruct->CRYP_Key3Left; 
+    CRYP_ContextSave->CRYP_K3RR = CRYP_KeyInitStruct->CRYP_Key3Right; 
+
+    /* Save the content of context swap registers */
+    CRYP_ContextSave->CRYP_CSGCMCCMR[0] = CRYP->CSGCMCCM0R;
+    CRYP_ContextSave->CRYP_CSGCMCCMR[1] = CRYP->CSGCMCCM1R;
+    CRYP_ContextSave->CRYP_CSGCMCCMR[2] = CRYP->CSGCMCCM2R;
+    CRYP_ContextSave->CRYP_CSGCMCCMR[3] = CRYP->CSGCMCCM3R;
+    CRYP_ContextSave->CRYP_CSGCMCCMR[4] = CRYP->CSGCMCCM4R;
+    CRYP_ContextSave->CRYP_CSGCMCCMR[5] = CRYP->CSGCMCCM5R;
+    CRYP_ContextSave->CRYP_CSGCMCCMR[6] = CRYP->CSGCMCCM6R;
+    CRYP_ContextSave->CRYP_CSGCMCCMR[7] = CRYP->CSGCMCCM7R;
+    
+    CRYP_ContextSave->CRYP_CSGCMR[0] = CRYP->CSGCM0R;
+    CRYP_ContextSave->CRYP_CSGCMR[1] = CRYP->CSGCM1R;
+    CRYP_ContextSave->CRYP_CSGCMR[2] = CRYP->CSGCM2R;
+    CRYP_ContextSave->CRYP_CSGCMR[3] = CRYP->CSGCM3R;
+    CRYP_ContextSave->CRYP_CSGCMR[4] = CRYP->CSGCM4R;
+    CRYP_ContextSave->CRYP_CSGCMR[5] = CRYP->CSGCM5R;
+    CRYP_ContextSave->CRYP_CSGCMR[6] = CRYP->CSGCM6R;
+    CRYP_ContextSave->CRYP_CSGCMR[7] = CRYP->CSGCM7R;
+    
+   /* When needed, save the DMA status (pointers for IN and OUT messages, 
+      number of remaining bytes, etc.) */
+     
+    status = SUCCESS;
+  }
+
+   return status;
+}
+
+/**
+  * @brief  Restores the CRYP peripheral Context.
+  * @note   Since teh DMA transfer is stopped in CRYP_SaveContext() function,
+  *         after restoring the context, you have to enable the DMA again (if the
+  *         DMA was previously used).  
+  * @param  CRYP_ContextRestore: pointer to a CRYP_Context structure that contains
+  *         the repository for saved context.
+  * @note   The data that were saved during context saving must be rewrited into
+  *         the IN FIFO.
+  * @retval None
+  */
+void CRYP_RestoreContext(CRYP_Context* CRYP_ContextRestore)  
+{
+
+  /* Configure the processor with the saved configuration */
+  CRYP->CR = CRYP_ContextRestore->CR_CurrentConfig;
+
+  /* restore The key value */
+  CRYP->K0LR = CRYP_ContextRestore->CRYP_K0LR; 
+  CRYP->K0RR = CRYP_ContextRestore->CRYP_K0RR;
+  CRYP->K1LR = CRYP_ContextRestore->CRYP_K1LR;
+  CRYP->K1RR = CRYP_ContextRestore->CRYP_K1RR;
+  CRYP->K2LR = CRYP_ContextRestore->CRYP_K2LR;
+  CRYP->K2RR = CRYP_ContextRestore->CRYP_K2RR;
+  CRYP->K3LR = CRYP_ContextRestore->CRYP_K3LR;
+  CRYP->K3RR = CRYP_ContextRestore->CRYP_K3RR;
+
+  /* and the initialization vectors. */
+  CRYP->IV0LR = CRYP_ContextRestore->CRYP_IV0LR;
+  CRYP->IV0RR = CRYP_ContextRestore->CRYP_IV0RR;
+  CRYP->IV1LR = CRYP_ContextRestore->CRYP_IV1LR;
+  CRYP->IV1RR = CRYP_ContextRestore->CRYP_IV1RR;
+
+  /* Restore the content of context swap registers */
+  CRYP->CSGCMCCM0R = CRYP_ContextRestore->CRYP_CSGCMCCMR[0];
+  CRYP->CSGCMCCM1R = CRYP_ContextRestore->CRYP_CSGCMCCMR[1];
+  CRYP->CSGCMCCM2R = CRYP_ContextRestore->CRYP_CSGCMCCMR[2];
+  CRYP->CSGCMCCM3R = CRYP_ContextRestore->CRYP_CSGCMCCMR[3];
+  CRYP->CSGCMCCM4R = CRYP_ContextRestore->CRYP_CSGCMCCMR[4];
+  CRYP->CSGCMCCM5R = CRYP_ContextRestore->CRYP_CSGCMCCMR[5];
+  CRYP->CSGCMCCM6R = CRYP_ContextRestore->CRYP_CSGCMCCMR[6];
+  CRYP->CSGCMCCM7R = CRYP_ContextRestore->CRYP_CSGCMCCMR[7];
+  
+  CRYP->CSGCM0R = CRYP_ContextRestore->CRYP_CSGCMR[0];
+  CRYP->CSGCM1R = CRYP_ContextRestore->CRYP_CSGCMR[1];
+  CRYP->CSGCM2R = CRYP_ContextRestore->CRYP_CSGCMR[2];
+  CRYP->CSGCM3R = CRYP_ContextRestore->CRYP_CSGCMR[3];
+  CRYP->CSGCM4R = CRYP_ContextRestore->CRYP_CSGCMR[4];
+  CRYP->CSGCM5R = CRYP_ContextRestore->CRYP_CSGCMR[5];
+  CRYP->CSGCM6R = CRYP_ContextRestore->CRYP_CSGCMR[6];
+  CRYP->CSGCM7R = CRYP_ContextRestore->CRYP_CSGCMR[7];
+  
+  /* Enable the cryptographic processor */
+  CRYP->CR |= CRYP_CR_CRYPEN;
+}
+/**
+  * @}
+  */
+
+/** @defgroup CRYP_Group4 CRYP's DMA interface Configuration function
+ *  @brief   CRYP's DMA interface Configuration function 
+ *
+@verbatim   
+ ===============================================================================
+             ##### CRYP's DMA interface Configuration function #####
+ ===============================================================================  
+ [..] This section provides functions allowing to configure the DMA interface for 
+      CRYP data input and output transfer.
+   
+ [..] When the DMA mode is enabled (using the CRYP_DMACmd() function), data can be 
+      transferred:
+   (+) From memory to the CRYP IN FIFO using the DMA peripheral by enabling 
+       the CRYP_DMAReq_DataIN request.
+   (+) From the CRYP OUT FIFO to the memory using the DMA peripheral by enabling 
+       the CRYP_DMAReq_DataOUT request.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the CRYP DMA interface.
+  * @param  CRYP_DMAReq: specifies the CRYP DMA transfer request to be enabled or disabled.
+  *           This parameter can be any combination of the following values:
+  *            @arg CRYP_DMAReq_DataOUT: DMA for outgoing(Tx) data transfer
+  *            @arg CRYP_DMAReq_DataIN: DMA for incoming(Rx) data transfer
+  * @param  NewState: new state of the selected CRYP DMA transfer request.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void CRYP_DMACmd(uint8_t CRYP_DMAReq, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_CRYP_DMAREQ(CRYP_DMAReq));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected CRYP DMA request */
+    CRYP->DMACR |= CRYP_DMAReq;
+  }
+  else
+  {
+    /* Disable the selected CRYP DMA request */
+    CRYP->DMACR &= (uint8_t)~CRYP_DMAReq;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup CRYP_Group5 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+              ##### Interrupts and flags management functions #####
+ ===============================================================================  
+ 
+ [..] This section provides functions allowing to configure the CRYP Interrupts and 
+      to get the status and Interrupts pending bits.
+
+ [..] The CRYP provides 2 Interrupts sources and 7 Flags:
+
+ *** Flags : ***
+ ===============
+ [..] 
+   (#) CRYP_FLAG_IFEM :  Set when Input FIFO is empty. This Flag is cleared only
+       by hardware.
+      
+   (#) CRYP_FLAG_IFNF :  Set when Input FIFO is not full. This Flag is cleared 
+       only by hardware.
+
+
+   (#) CRYP_FLAG_INRIS  : Set when Input FIFO Raw interrupt is pending it gives 
+       the raw interrupt state prior to masking of the input FIFO service interrupt.
+       This Flag is cleared only by hardware.
+     
+   (#) CRYP_FLAG_OFNE   : Set when Output FIFO not empty. This Flag is cleared 
+       only by hardware.
+        
+   (#) CRYP_FLAG_OFFU   : Set when Output FIFO is full. This Flag is cleared only 
+       by hardware.
+                           
+   (#) CRYP_FLAG_OUTRIS : Set when Output FIFO Raw interrupt is pending it gives 
+       the raw interrupt state prior to masking of the output FIFO service interrupt.
+       This Flag is cleared only by hardware.
+                               
+   (#) CRYP_FLAG_BUSY   : Set when the CRYP core is currently processing a block 
+       of data or a key preparation (for AES decryption). This Flag is cleared 
+       only by hardware. To clear it, the CRYP core must be disabled and the last
+       processing has completed. 
+
+ *** Interrupts : ***
+ ====================
+ [..]
+   (#) CRYP_IT_INI   : The input FIFO service interrupt is asserted when there 
+      are less than 4 words in the input FIFO. This interrupt is associated to 
+      CRYP_FLAG_INRIS flag.
+
+      -@- This interrupt is cleared by performing write operations to the input FIFO 
+          until it holds 4 or more words. The input FIFO service interrupt INMIS is 
+          enabled with the CRYP enable bit. Consequently, when CRYP is disabled, the 
+          INMIS signal is low even if the input FIFO is empty.
+
+
+
+   (#) CRYP_IT_OUTI  : The output FIFO service interrupt is asserted when there 
+       is one or more (32-bit word) data items in the output FIFO. This interrupt 
+       is associated to CRYP_FLAG_OUTRIS flag.
+
+       -@- This interrupt is cleared by reading data from the output FIFO until there 
+           is no valid (32-bit) word left (that is, the interrupt follows the state 
+           of the OFNE (output FIFO not empty) flag).
+
+ *** Managing the CRYP controller events : ***
+ =============================================
+ [..] The user should identify which mode will be used in his application to manage 
+      the CRYP controller events: Polling mode or Interrupt mode.
+
+   (#) In the Polling Mode it is advised to use the following functions:
+       (++) CRYP_GetFlagStatus() : to check if flags events occur. 
+
+       -@@- The CRYPT flags do not need to be cleared since they are cleared as 
+            soon as the associated event are reset.   
+
+
+   (#) In the Interrupt Mode it is advised to use the following functions:
+       (++) CRYP_ITConfig()       : to enable or disable the interrupt source.
+       (++) CRYP_GetITStatus()    : to check if Interrupt occurs.
+
+       -@@- The CRYPT interrupts have no pending bits, the interrupt is cleared as 
+             soon as the associated event is reset. 
+
+@endverbatim
+  * @{
+  */ 
+
+/**
+  * @brief  Enables or disables the specified CRYP interrupts.
+  * @param  CRYP_IT: specifies the CRYP interrupt source to be enabled or disabled.
+  *          This parameter can be any combination of the following values:
+  *            @arg CRYP_IT_INI: Input FIFO interrupt
+  *            @arg CRYP_IT_OUTI: Output FIFO interrupt
+  * @param  NewState: new state of the specified CRYP interrupt.
+  *           This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void CRYP_ITConfig(uint8_t CRYP_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_CRYP_CONFIG_IT(CRYP_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected CRYP interrupt */
+    CRYP->IMSCR |= CRYP_IT;
+  }
+  else
+  {
+    /* Disable the selected CRYP interrupt */
+    CRYP->IMSCR &= (uint8_t)~CRYP_IT;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified CRYP interrupt has occurred or not.
+  * @note   This function checks the status of the masked interrupt (i.e the 
+  *         interrupt should be previously enabled).     
+  * @param  CRYP_IT: specifies the CRYP (masked) interrupt source to check.
+  *           This parameter can be one of the following values:
+  *            @arg CRYP_IT_INI: Input FIFO interrupt
+  *            @arg CRYP_IT_OUTI: Output FIFO interrupt
+  * @retval The new state of CRYP_IT (SET or RESET).
+  */
+ITStatus CRYP_GetITStatus(uint8_t CRYP_IT)
+{
+  ITStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_CRYP_GET_IT(CRYP_IT));
+
+  /* Check the status of the specified CRYP interrupt */
+  if ((CRYP->MISR &  CRYP_IT) != (uint8_t)RESET)
+  {
+    /* CRYP_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* CRYP_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the CRYP_IT status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Returns whether CRYP peripheral is enabled or disabled.
+  * @param  none.
+  * @retval Current state of the CRYP peripheral (ENABLE or DISABLE).
+  */
+FunctionalState CRYP_GetCmdStatus(void)
+{
+  FunctionalState state = DISABLE;
+
+  if ((CRYP->CR & CRYP_CR_CRYPEN) != 0)
+  {
+    /* CRYPEN bit is set */
+    state = ENABLE;
+  }
+  else
+  {
+    /* CRYPEN bit is reset */
+    state = DISABLE;
+  }
+  return state;
+}
+
+/**
+  * @brief  Checks whether the specified CRYP flag is set or not.
+  * @param  CRYP_FLAG: specifies the CRYP flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg CRYP_FLAG_IFEM: Input FIFO Empty flag.
+  *            @arg CRYP_FLAG_IFNF: Input FIFO Not Full flag.
+  *            @arg CRYP_FLAG_OFNE: Output FIFO Not Empty flag.
+  *            @arg CRYP_FLAG_OFFU: Output FIFO Full flag.
+  *            @arg CRYP_FLAG_BUSY: Busy flag.
+  *            @arg CRYP_FLAG_OUTRIS: Output FIFO raw interrupt flag.
+  *            @arg CRYP_FLAG_INRIS: Input FIFO raw interrupt flag.
+  * @retval The new state of CRYP_FLAG (SET or RESET).
+  */
+FlagStatus CRYP_GetFlagStatus(uint8_t CRYP_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t tempreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_CRYP_GET_FLAG(CRYP_FLAG));
+
+  /* check if the FLAG is in RISR register */
+  if ((CRYP_FLAG & FLAG_MASK) != 0x00) 
+  {
+    tempreg = CRYP->RISR;
+  }
+  else  /* The FLAG is in SR register */
+  {
+    tempreg = CRYP->SR;
+  }
+
+
+  /* Check the status of the specified CRYP flag */
+  if ((tempreg & CRYP_FLAG ) != (uint8_t)RESET)
+  {
+    /* CRYP_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* CRYP_FLAG is reset */
+    bitstatus = RESET;
+  }
+
+  /* Return the CRYP_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c
new file mode 100644
index 0000000000000000000000000000000000000000..a8e60eecafa000b54b6cb3c9cb16ae8f2be86729
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_aes.c
@@ -0,0 +1,1707 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_cryp_aes.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides high level functions to encrypt and decrypt an 
+  *          input message using AES in ECB/CBC/CTR/GCM/CCM modes.
+  *          It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
+  *          peripheral.
+  *          AES-ECB/CBC/CTR/GCM/CCM modes are available on STM32F437x Devices.
+  *          For STM32F41xx Devices, only AES-ECB/CBC/CTR modes are available.
+  *
+@verbatim
+ ===================================================================
+                  ##### How to use this driver #####
+ ===================================================================
+ [..]
+   (#) Enable The CRYP controller clock using 
+      RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function.
+  
+   (#) Encrypt and decrypt using AES in ECB Mode using CRYP_AES_ECB() function.
+  
+   (#) Encrypt and decrypt using AES in CBC Mode using CRYP_AES_CBC() function.
+  
+   (#) Encrypt and decrypt using AES in CTR Mode using CRYP_AES_CTR() function.
+
+   (#) Encrypt and decrypt using AES in GCM Mode using CRYP_AES_GCM() function.
+   
+   (#) Encrypt and decrypt using AES in CCM Mode using CRYP_AES_CCM() function.
+     
+@endverbatim
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_cryp.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CRYP 
+  * @brief CRYP driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define AESBUSY_TIMEOUT    ((uint32_t) 0x00010000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup CRYP_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup CRYP_Group6 High Level AES functions
+ *  @brief   High Level AES functions 
+ *
+@verbatim   
+ ===============================================================================
+                       ##### High Level AES functions #####
+ ===============================================================================
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Encrypt and decrypt using AES in ECB Mode
+  * @param  Mode: encryption or decryption Mode.
+  *          This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  Key: Key used for AES algorithm.
+  * @param  Keysize: length of the Key, must be a 128, 192 or 256.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Ilength: length of the Input buffer, must be a multiple of 16.
+  * @param  Output: pointer to the returned buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_AES_ECB(uint8_t Mode, uint8_t* Key, uint16_t Keysize,
+                         uint8_t* Input, uint32_t Ilength, uint8_t* Output)
+{
+  CRYP_InitTypeDef AES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef AES_CRYP_KeyInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t i = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&AES_CRYP_KeyInitStructure);
+
+  switch(Keysize)
+  {
+    case 128:
+    AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_128b;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 192:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_192b;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 256:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_256b;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    default:
+    break;
+  }
+
+  /*------------------ AES Decryption ------------------*/
+  if(Mode == MODE_DECRYPT) /* AES decryption */
+  {
+    /* Flush IN/OUT FIFOs */
+    CRYP_FIFOFlush();
+
+    /* Crypto Init for Key preparation for decryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+    AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_Key;
+    AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_32b;
+    CRYP_Init(&AES_CRYP_InitStructure);
+
+    /* Key Initialisation */
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+
+    /* wait until the Busy flag is RESET */
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+      /* Crypto Init for decryption process */  
+      AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+    }
+  }
+  /*------------------ AES Encryption ------------------*/
+  else /* AES encryption */
+  {
+
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+
+    /* Crypto Init for Encryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir  = CRYP_AlgoDir_Encrypt;
+  }
+
+  AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_ECB;
+  AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+  CRYP_Init(&AES_CRYP_InitStructure);
+
+  /* Flush IN/OUT FIFOs */
+  CRYP_FIFOFlush();
+
+  /* Enable Crypto processor */
+  CRYP_Cmd(ENABLE);
+
+  if(CRYP_GetCmdStatus() == DISABLE)
+  {
+    /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+       the CRYP peripheral (please check the device sales type. */
+    return(ERROR);
+  }
+  
+  for(i=0; ((i<Ilength) && (status != ERROR)); i+=16)
+  {
+
+    /* Write the Input block in the IN FIFO */
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+
+    /* Wait until the complete message has been processed */
+    counter = 0;
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+
+      /* Read the Output block from the Output FIFO */
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut(); 
+      outputaddr+=4;
+    }
+  }
+
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status; 
+}
+
+/**
+  * @brief  Encrypt and decrypt using AES in CBC Mode
+  * @param  Mode: encryption or decryption Mode.
+  *          This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  InitVectors: Initialisation Vectors used for AES algorithm.
+  * @param  Key: Key used for AES algorithm.
+  * @param  Keysize: length of the Key, must be a 128, 192 or 256.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Ilength: length of the Input buffer, must be a multiple of 16.
+  * @param  Output: pointer to the returned buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_AES_CBC(uint8_t Mode, uint8_t InitVectors[16], uint8_t *Key,
+                         uint16_t Keysize, uint8_t *Input, uint32_t Ilength,
+                         uint8_t *Output)
+{
+  CRYP_InitTypeDef AES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef AES_CRYP_KeyInitStructure;
+  CRYP_IVInitTypeDef AES_CRYP_IVInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t ivaddr = (uint32_t)InitVectors;
+  uint32_t i = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&AES_CRYP_KeyInitStructure);
+
+  switch(Keysize)
+  {
+    case 128:
+    AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_128b;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 192:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_192b;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 256:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_256b;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    default:
+    break;
+  }
+
+  /* CRYP Initialization Vectors */
+  AES_CRYP_IVInitStructure.CRYP_IV0Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV0Right= __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Right= __REV(*(uint32_t*)(ivaddr));
+
+
+  /*------------------ AES Decryption ------------------*/
+  if(Mode == MODE_DECRYPT) /* AES decryption */
+  {
+    /* Flush IN/OUT FIFOs */
+    CRYP_FIFOFlush();
+
+    /* Crypto Init for Key preparation for decryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+    AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_Key;
+    AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_32b;
+
+    CRYP_Init(&AES_CRYP_InitStructure);
+
+    /* Key Initialisation */
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+
+    /* wait until the Busy flag is RESET */
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+      /* Crypto Init for decryption process */  
+      AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+    }
+  }
+  /*------------------ AES Encryption ------------------*/
+  else /* AES encryption */
+  {
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+
+    /* Crypto Init for Encryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir  = CRYP_AlgoDir_Encrypt;
+  }
+  AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_CBC;
+  AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+  CRYP_Init(&AES_CRYP_InitStructure);
+
+  /* CRYP Initialization Vectors */
+  CRYP_IVInit(&AES_CRYP_IVInitStructure);
+
+  /* Flush IN/OUT FIFOs */
+  CRYP_FIFOFlush();
+
+  /* Enable Crypto processor */
+  CRYP_Cmd(ENABLE);
+
+  if(CRYP_GetCmdStatus() == DISABLE)
+  {
+    /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+       the CRYP peripheral (please check the device sales type. */
+    return(ERROR);
+  }
+  
+  for(i=0; ((i<Ilength) && (status != ERROR)); i+=16)
+  {
+
+    /* Write the Input block in the IN FIFO */
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    /* Wait until the complete message has been processed */
+    counter = 0;
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+
+      /* Read the Output block from the Output FIFO */
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+    }
+  }
+
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status;
+}
+
+/**
+  * @brief  Encrypt and decrypt using AES in CTR Mode
+  * @param  Mode: encryption or decryption Mode.
+  *           This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  InitVectors: Initialisation Vectors used for AES algorithm.
+  * @param  Key: Key used for AES algorithm.
+  * @param  Keysize: length of the Key, must be a 128, 192 or 256.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Ilength: length of the Input buffer, must be a multiple of 16.
+  * @param  Output: pointer to the returned buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_AES_CTR(uint8_t Mode, uint8_t InitVectors[16], uint8_t *Key, 
+                         uint16_t Keysize, uint8_t *Input, uint32_t Ilength,
+                         uint8_t *Output)
+{
+  CRYP_InitTypeDef AES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef AES_CRYP_KeyInitStructure;
+  CRYP_IVInitTypeDef AES_CRYP_IVInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t ivaddr     = (uint32_t)InitVectors;
+  uint32_t i = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&AES_CRYP_KeyInitStructure);
+
+  switch(Keysize)
+  {
+    case 128:
+    AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_128b;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 192:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_192b;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 256:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_256b;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    default:
+    break;
+  }
+  /* CRYP Initialization Vectors */
+  AES_CRYP_IVInitStructure.CRYP_IV0Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV0Right= __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Right= __REV(*(uint32_t*)(ivaddr));
+
+  /* Key Initialisation */
+  CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+
+  /*------------------ AES Decryption ------------------*/
+  if(Mode == MODE_DECRYPT) /* AES decryption */
+  {
+    /* Crypto Init for decryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+  }
+  /*------------------ AES Encryption ------------------*/
+  else /* AES encryption */
+  {
+    /* Crypto Init for Encryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
+  }
+  AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_CTR;
+  AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+  CRYP_Init(&AES_CRYP_InitStructure);
+
+  /* CRYP Initialization Vectors */
+  CRYP_IVInit(&AES_CRYP_IVInitStructure);
+
+  /* Flush IN/OUT FIFOs */
+  CRYP_FIFOFlush();
+
+  /* Enable Crypto processor */
+  CRYP_Cmd(ENABLE);
+
+  if(CRYP_GetCmdStatus() == DISABLE)
+  {
+    /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+       the CRYP peripheral (please check the device sales type. */
+    return(ERROR);
+  }
+  
+  for(i=0; ((i<Ilength) && (status != ERROR)); i+=16)
+  {
+
+    /* Write the Input block in the IN FIFO */
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    /* Wait until the complete message has been processed */
+    counter = 0;
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+
+      /* Read the Output block from the Output FIFO */
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+    }
+  }
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status;
+}
+
+/**
+  * @brief  Encrypt and decrypt using AES in GCM Mode. The GCM and CCM modes
+  *         are available only on STM32F437x Devices.
+  * @param  Mode: encryption or decryption Mode.
+  *          This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  InitVectors: Initialisation Vectors used for AES algorithm.
+  * @param  Key: Key used for AES algorithm.
+  * @param  Keysize: length of the Key, must be a 128, 192 or 256.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Ilength: length of the Input buffer in bytes, must be a multiple of 16.
+  * @param  Header: pointer to the header buffer.
+  * @param  Hlength: length of the header buffer in bytes, must be a multiple of 16.  
+  * @param  Output: pointer to the returned buffer.
+  * @param  AuthTAG: pointer to the authentication TAG buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_AES_GCM(uint8_t Mode, uint8_t InitVectors[16],
+                         uint8_t *Key, uint16_t Keysize,
+                         uint8_t *Input, uint32_t ILength,
+                         uint8_t *Header, uint32_t HLength,
+                         uint8_t *Output, uint8_t *AuthTAG)
+{
+  CRYP_InitTypeDef AES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef AES_CRYP_KeyInitStructure;
+  CRYP_IVInitTypeDef AES_CRYP_IVInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t ivaddr     = (uint32_t)InitVectors;
+  uint32_t headeraddr = (uint32_t)Header;
+  uint32_t tagaddr = (uint32_t)AuthTAG;
+  uint64_t headerlength = HLength * 8;/* header length in bits */
+  uint64_t inputlength = ILength * 8;/* input length in bits */
+  uint32_t loopcounter = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&AES_CRYP_KeyInitStructure);
+
+  switch(Keysize)
+  {
+    case 128:
+    AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_128b;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 192:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_192b;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 256:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_256b;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    default:
+    break;
+  }
+  
+  /* CRYP Initialization Vectors */
+  AES_CRYP_IVInitStructure.CRYP_IV0Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV0Right= __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Right= __REV(*(uint32_t*)(ivaddr));
+  
+  /*------------------ AES Encryption ------------------*/
+  if(Mode == MODE_ENCRYPT) /* AES encryption */
+  {
+    /* Flush IN/OUT FIFOs */
+    CRYP_FIFOFlush();
+    
+    /* Key Initialisation */
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+    
+    /* CRYP Initialization Vectors */
+    CRYP_IVInit(&AES_CRYP_IVInitStructure);
+    
+    /* Crypto Init for Key preparation for decryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
+    AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_GCM;
+    AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+    CRYP_Init(&AES_CRYP_InitStructure);
+    
+    /***************************** Init phase *********************************/
+    /* Select init phase */
+    CRYP_PhaseConfig(CRYP_Phase_Init);
+    
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    /* Wait for CRYPEN bit to be 0 */
+    while(CRYP_GetCmdStatus() == ENABLE)
+    {
+    }
+    
+    /***************************** header phase *******************************/
+    if(HLength != 0)
+    {
+      /* Select header phase */
+      CRYP_PhaseConfig(CRYP_Phase_Header);
+      
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+         /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+            the CRYP peripheral (please check the device sales type. */
+         return(ERROR);
+      }
+      
+      for(loopcounter = 0; (loopcounter < HLength); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+      }
+      
+      /* Wait until the complete message has been processed */
+      counter = 0;
+      do
+      {
+        busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+        counter++;
+      }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+      if (busystatus != RESET)
+      {
+        status = ERROR;
+      }
+    }
+    
+    /**************************** payload phase *******************************/
+    if(ILength != 0)
+    {
+      /* Select payload phase */
+      CRYP_PhaseConfig(CRYP_Phase_Payload);
+      
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+        /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+           the CRYP peripheral (please check the device sales type. */
+        return(ERROR);
+      }
+      
+      for(loopcounter = 0; ((loopcounter < ILength) && (status != ERROR)); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        
+        /* Wait until the complete message has been processed */
+        counter = 0;
+        do
+        {
+          busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+          counter++;
+        }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+        if (busystatus != RESET)
+        {
+          status = ERROR;
+        }
+        else
+        {
+          /* Wait until the OFNE flag is reset */
+          while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+          {
+          }
+          
+          /* Read the Output block from the Output FIFO */
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+        }
+      }
+    }
+    
+    /***************************** final phase ********************************/
+    /* Select final phase */
+    CRYP_PhaseConfig(CRYP_Phase_Final);
+    
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    if(CRYP_GetCmdStatus() == DISABLE)
+    {
+      /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+         the CRYP peripheral (please check the device sales type. */
+      return(ERROR);
+    }
+    
+    /* Write number of bits concatenated with header in the IN FIFO */
+    CRYP_DataIn(__REV(headerlength>>32));
+    CRYP_DataIn(__REV(headerlength));
+    CRYP_DataIn(__REV(inputlength>>32));
+    CRYP_DataIn(__REV(inputlength));
+    /* Wait until the OFNE flag is reset */
+    while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+    {
+    }
+    
+    tagaddr = (uint32_t)AuthTAG;
+    /* Read the Auth TAG in the IN FIFO */
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+  }
+  /*------------------ AES Decryption ------------------*/
+  else /* AES decryption */
+  {
+    /* Flush IN/OUT FIFOs */
+    CRYP_FIFOFlush();
+    
+    /* Key Initialisation */
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+    
+    /* CRYP Initialization Vectors */
+    CRYP_IVInit(&AES_CRYP_IVInitStructure);
+    
+    /* Crypto Init for Key preparation for decryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+    AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_GCM;
+    AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+    CRYP_Init(&AES_CRYP_InitStructure);
+    
+    /***************************** Init phase *********************************/
+    /* Select init phase */
+    CRYP_PhaseConfig(CRYP_Phase_Init);
+    
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    /* Wait for CRYPEN bit to be 0 */
+    while(CRYP_GetCmdStatus() == ENABLE)
+    {
+    }
+    
+    /***************************** header phase *******************************/
+    if(HLength != 0)
+    {
+      /* Select header phase */
+      CRYP_PhaseConfig(CRYP_Phase_Header);
+      
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+        /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+           the CRYP peripheral (please check the device sales type. */
+        return(ERROR);
+      }
+      
+      for(loopcounter = 0; (loopcounter < HLength); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+      }
+      
+      /* Wait until the complete message has been processed */
+      counter = 0;
+      do
+      {
+        busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+        counter++;
+      }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+      if (busystatus != RESET)
+      {
+        status = ERROR;
+      }
+    }
+    
+    /**************************** payload phase *******************************/
+    if(ILength != 0)
+    {
+      /* Select payload phase */
+      CRYP_PhaseConfig(CRYP_Phase_Payload);
+
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+        /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+           the CRYP peripheral (please check the device sales type. */
+        return(ERROR);
+      }
+      
+      for(loopcounter = 0; ((loopcounter < ILength) && (status != ERROR)); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        
+        /* Wait until the complete message has been processed */
+        counter = 0;
+        do
+        {
+          busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+          counter++;
+        }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+        if (busystatus != RESET)
+        {
+          status = ERROR;
+        }
+        else
+        {
+          /* Wait until the OFNE flag is reset */
+          while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+          {
+          }
+          
+          /* Read the Output block from the Output FIFO */
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+        }
+      }
+    }
+    
+    /***************************** final phase ********************************/
+    /* Select final phase */
+    CRYP_PhaseConfig(CRYP_Phase_Final);
+
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    if(CRYP_GetCmdStatus() == DISABLE)
+    {
+      /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+         the CRYP peripheral (please check the device sales type. */
+      return(ERROR);
+    }
+    
+    /* Write number of bits concatenated with header in the IN FIFO */
+    CRYP_DataIn(__REV(headerlength>>32));
+    CRYP_DataIn(__REV(headerlength));
+    CRYP_DataIn(__REV(inputlength>>32));
+    CRYP_DataIn(__REV(inputlength));
+    /* Wait until the OFNE flag is reset */
+    while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+    {
+    }
+    
+    tagaddr = (uint32_t)AuthTAG;
+    /* Read the Auth TAG in the IN FIFO */
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+    *(uint32_t*)(tagaddr) = CRYP_DataOut();
+    tagaddr+=4;
+  }
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status;
+}
+
+/**
+  * @brief  Encrypt and decrypt using AES in CCM Mode. The GCM and CCM modes
+  *         are available only on STM32F437x Devices.
+  * @param  Mode: encryption or decryption Mode.
+  *          This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  Nonce: the nounce used for AES algorithm. It shall be unique for each processing.
+  * @param  Key: Key used for AES algorithm.
+  * @param  Keysize: length of the Key, must be a 128, 192 or 256.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Ilength: length of the Input buffer in bytes, must be a multiple of 16.
+  * @param  Header: pointer to the header buffer.
+  * @param  Hlength: length of the header buffer in bytes.
+  * @param  HBuffer: pointer to temporary buffer used to append the header
+  *         HBuffer size must be equal to Hlength + 21
+  * @param  Output: pointer to the returned buffer.
+  * @param  AuthTAG: pointer to the authentication TAG buffer.
+  * @param  TAGSize: the size of the TAG (called also MAC).
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_AES_CCM(uint8_t Mode, 
+                         uint8_t* Nonce, uint32_t NonceSize,
+                         uint8_t *Key, uint16_t Keysize,
+                         uint8_t *Input, uint32_t ILength,
+                         uint8_t *Header, uint32_t HLength, uint8_t *HBuffer,
+                         uint8_t *Output,
+                         uint8_t *AuthTAG, uint32_t TAGSize)
+{
+  CRYP_InitTypeDef AES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef AES_CRYP_KeyInitStructure;
+  CRYP_IVInitTypeDef AES_CRYP_IVInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t headeraddr = (uint32_t)Header;
+  uint32_t tagaddr = (uint32_t)AuthTAG;
+  uint32_t headersize = HLength;
+  uint32_t loopcounter = 0;
+  uint32_t bufferidx = 0;
+  uint8_t blockb0[16] = {0};/* Block B0 */
+  uint8_t ctr[16] = {0}; /* Counter */
+  uint32_t temptag[4] = {0}; /* temporary TAG (MAC) */
+  uint32_t ctraddr = (uint32_t)ctr;
+  uint32_t b0addr = (uint32_t)blockb0;
+  
+  /************************ Formatting the header block ***********************/
+  if(headersize != 0)
+  {
+    /* Check that the associated data (or header) length is lower than 2^16 - 2^8 = 65536 - 256 = 65280 */
+    if(headersize < 65280)
+    {
+      HBuffer[bufferidx++] = (uint8_t) ((headersize >> 8) & 0xFF);
+      HBuffer[bufferidx++] = (uint8_t) ((headersize) & 0xFF);
+      headersize += 2;
+    }
+    else
+    {
+      /* header is encoded as 0xff || 0xfe || [headersize]32, i.e., six octets */
+      HBuffer[bufferidx++] = 0xFF;
+      HBuffer[bufferidx++] = 0xFE;
+      HBuffer[bufferidx++] = headersize & 0xff000000;
+      HBuffer[bufferidx++] = headersize & 0x00ff0000;
+      HBuffer[bufferidx++] = headersize & 0x0000ff00;
+      HBuffer[bufferidx++] = headersize & 0x000000ff;
+      headersize += 6;
+    }
+    /* Copy the header buffer in internal buffer "HBuffer" */
+    for(loopcounter = 0; loopcounter < headersize; loopcounter++)
+    {
+      HBuffer[bufferidx++] = Header[loopcounter];
+    }
+    /* Check if the header size is modulo 16 */
+    if ((headersize % 16) != 0)
+    {
+      /* Padd the header buffer with 0s till the HBuffer length is modulo 16 */
+      for(loopcounter = headersize; loopcounter <= ((headersize/16) + 1) * 16; loopcounter++)
+      {
+        HBuffer[loopcounter] = 0;
+      }
+      /* Set the header size to modulo 16 */
+      headersize = ((headersize/16) + 1) * 16;
+    }
+    /* set the pointer headeraddr to HBuffer */
+    headeraddr = (uint32_t)HBuffer;
+  }
+  /************************* Formatting the block B0 **************************/
+  if(headersize != 0)
+  {
+    blockb0[0] = 0x40;
+  }
+  /* Flags byte */
+  blockb0[0] |= 0u | (((( (uint8_t) TAGSize - 2) / 2) & 0x07 ) << 3 ) | ( ( (uint8_t) (15 - NonceSize) - 1) & 0x07);
+  
+  for (loopcounter = 0; loopcounter < NonceSize; loopcounter++)
+  {
+    blockb0[loopcounter+1] = Nonce[loopcounter];
+  }
+  for ( ; loopcounter < 13; loopcounter++)
+  {
+    blockb0[loopcounter+1] = 0;
+  }
+  
+  blockb0[14] = ((ILength >> 8) & 0xFF);
+  blockb0[15] = (ILength & 0xFF);
+  
+  /************************* Formatting the initial counter *******************/
+  /* Byte 0:
+     Bits 7 and 6 are reserved and shall be set to 0
+     Bits 3, 4, and 5 shall also be set to 0, to ensure that all the counter blocks
+     are distinct from B0
+     Bits 0, 1, and 2 contain the same encoding of q as in B0
+  */
+  ctr[0] = blockb0[0] & 0x07;
+  /* byte 1 to NonceSize is the IV (Nonce) */
+  for(loopcounter = 1; loopcounter < NonceSize + 1; loopcounter++)
+  {
+    ctr[loopcounter] = blockb0[loopcounter];
+  }
+  /* Set the LSB to 1 */
+  ctr[15] |= 0x01;
+  
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&AES_CRYP_KeyInitStructure);
+  
+  switch(Keysize)
+  {
+    case 128:
+    AES_CRYP_InitStructure.CRYP_KeySize = CRYP_KeySize_128b;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 192:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_192b;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    case 256:
+    AES_CRYP_InitStructure.CRYP_KeySize  = CRYP_KeySize_256b;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key0Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+    keyaddr+=4;
+    AES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+    break;
+    default:
+    break;
+  }
+  
+  /* CRYP Initialization Vectors */
+  AES_CRYP_IVInitStructure.CRYP_IV0Left = (__REV(*(uint32_t*)(ctraddr)));
+  ctraddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV0Right= (__REV(*(uint32_t*)(ctraddr)));
+  ctraddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Left = (__REV(*(uint32_t*)(ctraddr)));
+  ctraddr+=4;
+  AES_CRYP_IVInitStructure.CRYP_IV1Right= (__REV(*(uint32_t*)(ctraddr)));
+  
+  /*------------------ AES Encryption ------------------*/
+  if(Mode == MODE_ENCRYPT) /* AES encryption */
+  {
+    /* Flush IN/OUT FIFOs */
+    CRYP_FIFOFlush();
+    
+    /* Key Initialisation */
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+    
+    /* CRYP Initialization Vectors */
+    CRYP_IVInit(&AES_CRYP_IVInitStructure);
+    
+    /* Crypto Init for Key preparation for decryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
+    AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_CCM;
+    AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+    CRYP_Init(&AES_CRYP_InitStructure);
+    
+    /***************************** Init phase *********************************/
+    /* Select init phase */
+    CRYP_PhaseConfig(CRYP_Phase_Init);
+    
+    b0addr = (uint32_t)blockb0;
+    /* Write the blockb0 block in the IN FIFO */
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    b0addr+=4;
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    b0addr+=4;
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    b0addr+=4;
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    /* Wait for CRYPEN bit to be 0 */
+    while(CRYP_GetCmdStatus() == ENABLE)
+    {
+    }
+    /***************************** header phase *******************************/
+    if(headersize != 0)
+    {
+      /* Select header phase */
+      CRYP_PhaseConfig(CRYP_Phase_Header);
+      
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+         /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+            the CRYP peripheral (please check the device sales type. */
+         return(ERROR);
+      }
+      
+      for(loopcounter = 0; (loopcounter < headersize); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+      }
+      
+      /* Wait until the complete message has been processed */
+      counter = 0;
+      do
+      {
+        busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+        counter++;
+      }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+      if (busystatus != RESET)
+      {
+        status = ERROR;
+      }
+    }
+    
+    /**************************** payload phase *******************************/
+    if(ILength != 0)
+    {
+      /* Select payload phase */
+      CRYP_PhaseConfig(CRYP_Phase_Payload);
+      
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+        /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+           the CRYP peripheral (please check the device sales type. */
+        return(ERROR);
+      }
+      
+      for(loopcounter = 0; ((loopcounter < ILength) && (status != ERROR)); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        
+        /* Wait until the complete message has been processed */
+        counter = 0;
+        do
+        {
+          busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+          counter++;
+        }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+        if (busystatus != RESET)
+        {
+          status = ERROR;
+        }
+        else
+        {
+          /* Wait until the OFNE flag is reset */
+          while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+          {
+          }
+          
+          /* Read the Output block from the Output FIFO */
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+        }
+      }
+    }
+    
+    /***************************** final phase ********************************/
+    /* Select final phase */
+    CRYP_PhaseConfig(CRYP_Phase_Final);
+    
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    if(CRYP_GetCmdStatus() == DISABLE)
+    {
+      /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+         the CRYP peripheral (please check the device sales type. */
+      return(ERROR);
+    }
+    
+    ctraddr = (uint32_t)ctr;
+    /* Write the counter block in the IN FIFO */
+    CRYP_DataIn(*(uint32_t*)(ctraddr));
+    ctraddr+=4;
+    CRYP_DataIn(*(uint32_t*)(ctraddr));
+    ctraddr+=4;
+    CRYP_DataIn(*(uint32_t*)(ctraddr));
+    ctraddr+=4;
+    /* Reset bit 0 (after 8-bit swap) is equivalent to reset bit 24 (before 8-bit swap) */
+    CRYP_DataIn(*(uint32_t*)(ctraddr) & 0xfeffffff);
+    
+    /* Wait until the OFNE flag is reset */
+    while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+    {
+    }
+    
+    /* Read the Auth TAG in the IN FIFO */
+    temptag[0] = CRYP_DataOut();
+    temptag[1] = CRYP_DataOut();
+    temptag[2] = CRYP_DataOut();
+    temptag[3] = CRYP_DataOut();
+  }
+  /*------------------ AES Decryption ------------------*/
+  else /* AES decryption */
+  {
+    /* Flush IN/OUT FIFOs */
+    CRYP_FIFOFlush();
+    
+    /* Key Initialisation */
+    CRYP_KeyInit(&AES_CRYP_KeyInitStructure);
+    
+    /* CRYP Initialization Vectors */
+    CRYP_IVInit(&AES_CRYP_IVInitStructure);
+    
+    /* Crypto Init for Key preparation for decryption process */
+    AES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+    AES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_AES_CCM;
+    AES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+    CRYP_Init(&AES_CRYP_InitStructure);
+    
+    /***************************** Init phase *********************************/
+    /* Select init phase */
+    CRYP_PhaseConfig(CRYP_Phase_Init);
+    
+    b0addr = (uint32_t)blockb0;
+    /* Write the blockb0 block in the IN FIFO */
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    b0addr+=4;
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    b0addr+=4;
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    b0addr+=4;
+    CRYP_DataIn((*(uint32_t*)(b0addr)));
+    
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    /* Wait for CRYPEN bit to be 0 */
+    while(CRYP_GetCmdStatus() == ENABLE)
+    {
+    }
+    
+    /***************************** header phase *******************************/
+    if(headersize != 0)
+    {
+      /* Select header phase */
+      CRYP_PhaseConfig(CRYP_Phase_Header);
+      
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+        /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+           the CRYP peripheral (please check the device sales type. */
+        return(ERROR);
+      }
+      
+      for(loopcounter = 0; (loopcounter < headersize); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+        CRYP_DataIn(*(uint32_t*)(headeraddr));
+        headeraddr+=4;
+      }
+      
+      /* Wait until the complete message has been processed */
+      counter = 0;
+      do
+      {
+        busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+        counter++;
+      }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+      if (busystatus != RESET)
+      {
+        status = ERROR;
+      }
+    }
+    
+    /**************************** payload phase *******************************/
+    if(ILength != 0)
+    {
+      /* Select payload phase */
+      CRYP_PhaseConfig(CRYP_Phase_Payload);
+
+      /* Enable Crypto processor */
+      CRYP_Cmd(ENABLE);
+      
+      if(CRYP_GetCmdStatus() == DISABLE)
+      {
+        /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+           the CRYP peripheral (please check the device sales type. */
+        return(ERROR);
+      }
+      
+      for(loopcounter = 0; ((loopcounter < ILength) && (status != ERROR)); loopcounter+=16)
+      {
+        /* Wait until the IFEM flag is reset */
+        while(CRYP_GetFlagStatus(CRYP_FLAG_IFEM) == RESET)
+        {
+        }
+        
+        /* Write the Input block in the IN FIFO */
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        CRYP_DataIn(*(uint32_t*)(inputaddr));
+        inputaddr+=4;
+        
+        /* Wait until the complete message has been processed */
+        counter = 0;
+        do
+        {
+          busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+          counter++;
+        }while ((counter != AESBUSY_TIMEOUT) && (busystatus != RESET));
+
+        if (busystatus != RESET)
+        {
+          status = ERROR;
+        }
+        else
+        {
+          /* Wait until the OFNE flag is reset */
+          while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+          {
+          }
+          
+          /* Read the Output block from the Output FIFO */
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+          *(uint32_t*)(outputaddr) = CRYP_DataOut();
+          outputaddr+=4;
+        }
+      }
+    }
+    
+    /***************************** final phase ********************************/
+    /* Select final phase */
+    CRYP_PhaseConfig(CRYP_Phase_Final);
+    
+    /* Enable Crypto processor */
+    CRYP_Cmd(ENABLE);
+    
+    if(CRYP_GetCmdStatus() == DISABLE)
+    {
+      /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+         the CRYP peripheral (please check the device sales type. */
+      return(ERROR);
+    }
+    
+    ctraddr = (uint32_t)ctr;
+    /* Write the counter block in the IN FIFO */
+    CRYP_DataIn(*(uint32_t*)(ctraddr));
+    ctraddr+=4;
+    CRYP_DataIn(*(uint32_t*)(ctraddr));
+    ctraddr+=4;
+    CRYP_DataIn(*(uint32_t*)(ctraddr));
+    ctraddr+=4;
+    /* Reset bit 0 (after 8-bit swap) is equivalent to reset bit 24 (before 8-bit swap) */
+    CRYP_DataIn(*(uint32_t*)(ctraddr) & 0xfeffffff);
+    
+    /* Wait until the OFNE flag is reset */
+    while(CRYP_GetFlagStatus(CRYP_FLAG_OFNE) == RESET)
+    {
+    }
+    
+    /* Read the Authentaication TAG (MAC) in the IN FIFO */
+    temptag[0] = CRYP_DataOut();
+    temptag[1] = CRYP_DataOut();
+    temptag[2] = CRYP_DataOut();
+    temptag[3] = CRYP_DataOut();
+  }
+  
+  /* Copy temporary authentication TAG in user TAG buffer */
+  for(loopcounter = 0; (loopcounter < TAGSize); loopcounter++)
+  {
+    /* Set the authentication TAG buffer */
+    *((uint8_t*)tagaddr+loopcounter) = *((uint8_t*)temptag+loopcounter);
+  }
+  
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status;
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_des.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_des.c
new file mode 100644
index 0000000000000000000000000000000000000000..8089ae7abefd7b0122fd604e4921228a88bd1666
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_des.c
@@ -0,0 +1,308 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_cryp_des.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides high level functions to encrypt and decrypt an 
+  *          input message using DES in ECB/CBC modes.
+  *          It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
+  *          peripheral.
+  *
+@verbatim
+  
+ ===================================================================
+                  ##### How to use this driver #####
+ ===================================================================
+ [..] 
+   (#) Enable The CRYP controller clock using 
+       RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function.
+  
+   (#) Encrypt and decrypt using DES in ECB Mode using CRYP_DES_ECB() function.
+  
+   (#) Encrypt and decrypt using DES in CBC Mode using CRYP_DES_CBC() function.
+  
+@endverbatim
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_cryp.h"
+
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CRYP 
+  * @brief CRYP driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define DESBUSY_TIMEOUT    ((uint32_t) 0x00010000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+
+/** @defgroup CRYP_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup CRYP_Group8 High Level DES functions
+ *  @brief   High Level DES functions 
+ *
+@verbatim   
+ ===============================================================================
+                       ##### High Level DES functions #####
+ ===============================================================================
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Encrypt and decrypt using DES in ECB Mode
+  * @param  Mode: encryption or decryption Mode.
+  *           This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  Key: Key used for DES algorithm.
+  * @param  Ilength: length of the Input buffer, must be a multiple of 8.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Output: pointer to the returned buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_DES_ECB(uint8_t Mode, uint8_t Key[8], uint8_t *Input, 
+                         uint32_t Ilength, uint8_t *Output)
+{
+  CRYP_InitTypeDef DES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef DES_CRYP_KeyInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t i = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&DES_CRYP_KeyInitStructure);
+
+  /* Crypto Init for Encryption process */
+  if( Mode == MODE_ENCRYPT ) /* DES encryption */
+  {
+     DES_CRYP_InitStructure.CRYP_AlgoDir  = CRYP_AlgoDir_Encrypt;
+  }
+  else/* if( Mode == MODE_DECRYPT )*/ /* DES decryption */
+  {      
+     DES_CRYP_InitStructure.CRYP_AlgoDir  = CRYP_AlgoDir_Decrypt;
+  }
+
+  DES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_DES_ECB;
+  DES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+  CRYP_Init(&DES_CRYP_InitStructure);
+
+  /* Key Initialisation */
+  DES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  DES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+  CRYP_KeyInit(& DES_CRYP_KeyInitStructure);
+
+  /* Flush IN/OUT FIFO */
+  CRYP_FIFOFlush();
+
+  /* Enable Crypto processor */
+  CRYP_Cmd(ENABLE);
+
+  if(CRYP_GetCmdStatus() == DISABLE)
+  {
+    /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+       the CRYP peripheral (please check the device sales type. */
+    return(ERROR);
+  }
+  for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
+  {
+
+    /* Write the Input block in the Input FIFO */
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+
+/* Wait until the complete message has been processed */
+    counter = 0;
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != DESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+
+      /* Read the Output block from the Output FIFO */
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+    }
+  }
+
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status; 
+}
+
+/**
+  * @brief  Encrypt and decrypt using DES in CBC Mode
+  * @param  Mode: encryption or decryption Mode.
+  *          This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  Key: Key used for DES algorithm.
+  * @param  InitVectors: Initialisation Vectors used for DES algorithm.
+  * @param  Ilength: length of the Input buffer, must be a multiple of 8.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Output: pointer to the returned buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_DES_CBC(uint8_t Mode, uint8_t Key[8], uint8_t InitVectors[8],
+                         uint8_t *Input, uint32_t Ilength, uint8_t *Output)
+{
+  CRYP_InitTypeDef DES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef DES_CRYP_KeyInitStructure;
+  CRYP_IVInitTypeDef DES_CRYP_IVInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t ivaddr     = (uint32_t)InitVectors;
+  uint32_t i = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&DES_CRYP_KeyInitStructure);
+
+  /* Crypto Init for Encryption process */
+  if(Mode == MODE_ENCRYPT) /* DES encryption */
+  {
+     DES_CRYP_InitStructure.CRYP_AlgoDir  = CRYP_AlgoDir_Encrypt;
+  }
+  else /*if(Mode == MODE_DECRYPT)*/ /* DES decryption */
+  {
+     DES_CRYP_InitStructure.CRYP_AlgoDir  = CRYP_AlgoDir_Decrypt;
+  }
+
+  DES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_DES_CBC;
+  DES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+  CRYP_Init(&DES_CRYP_InitStructure);
+
+  /* Key Initialisation */
+  DES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  DES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+  CRYP_KeyInit(& DES_CRYP_KeyInitStructure);
+
+  /* Initialization Vectors */
+  DES_CRYP_IVInitStructure.CRYP_IV0Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  DES_CRYP_IVInitStructure.CRYP_IV0Right= __REV(*(uint32_t*)(ivaddr));
+  CRYP_IVInit(&DES_CRYP_IVInitStructure);
+
+  /* Flush IN/OUT FIFO */
+  CRYP_FIFOFlush();
+  
+  /* Enable Crypto processor */
+  CRYP_Cmd(ENABLE);
+
+  if(CRYP_GetCmdStatus() == DISABLE)
+  {
+    /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+       the CRYP peripheral (please check the device sales type. */
+    return(ERROR);
+  }
+  for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
+  {
+    /* Write the Input block in the Input FIFO */
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+
+    /* Wait until the complete message has been processed */
+    counter = 0;
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != DESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+      /* Read the Output block from the Output FIFO */
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+    }
+  }
+
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status; 
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_tdes.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_tdes.c
new file mode 100644
index 0000000000000000000000000000000000000000..41c9b1a187284f10fbad71d5ba056fcbf3c61260
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_cryp_tdes.c
@@ -0,0 +1,325 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_cryp_tdes.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides high level functions to encrypt and decrypt an 
+  *          input message using TDES in ECB/CBC modes .
+  *          It uses the stm32f4xx_cryp.c/.h drivers to access the STM32F4xx CRYP
+  *          peripheral.
+  *
+@verbatim
+
+ ===================================================================
+                  ##### How to use this driver #####
+ ===================================================================
+ [..]
+   (#) Enable The CRYP controller clock using 
+       RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_CRYP, ENABLE); function.
+  
+   (#) Encrypt and decrypt using TDES in ECB Mode using CRYP_TDES_ECB() function.
+  
+   (#) Encrypt and decrypt using TDES in CBC Mode using CRYP_TDES_CBC() function.
+  
+@endverbatim
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_cryp.h"
+
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup CRYP 
+  * @brief CRYP driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define TDESBUSY_TIMEOUT    ((uint32_t) 0x00010000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+
+/** @defgroup CRYP_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup CRYP_Group7 High Level TDES functions
+ *  @brief   High Level TDES functions 
+ *
+@verbatim   
+ ===============================================================================
+                      ##### High Level TDES functions #####
+ ===============================================================================
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Encrypt and decrypt using TDES in ECB Mode
+  * @param  Mode: encryption or decryption Mode.
+  *           This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  Key: Key used for TDES algorithm.
+  * @param  Ilength: length of the Input buffer, must be a multiple of 8.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Output: pointer to the returned buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_TDES_ECB(uint8_t Mode, uint8_t Key[24], uint8_t *Input, 
+                          uint32_t Ilength, uint8_t *Output)
+{
+  CRYP_InitTypeDef TDES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef TDES_CRYP_KeyInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t i = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&TDES_CRYP_KeyInitStructure);
+
+  /* Crypto Init for Encryption process */
+  if(Mode == MODE_ENCRYPT) /* TDES encryption */
+  {
+     TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
+  }
+  else /*if(Mode == MODE_DECRYPT)*/ /* TDES decryption */
+  {
+     TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+  }
+
+  TDES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_TDES_ECB;
+  TDES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+  CRYP_Init(&TDES_CRYP_InitStructure);
+
+  /* Key Initialisation */
+  TDES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+  CRYP_KeyInit(& TDES_CRYP_KeyInitStructure);
+
+  /* Flush IN/OUT FIFO */
+  CRYP_FIFOFlush();
+
+  /* Enable Crypto processor */
+  CRYP_Cmd(ENABLE);
+
+  if(CRYP_GetCmdStatus() == DISABLE)
+  {
+    /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+       the CRYP peripheral (please check the device sales type. */
+    return(ERROR);
+  }
+  for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
+  {
+    /* Write the Input block in the Input FIFO */
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+
+    /* Wait until the complete message has been processed */
+    counter = 0;
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != TDESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+    {
+       status = ERROR;
+    }
+    else
+    {
+
+      /* Read the Output block from the Output FIFO */
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+    }
+  }
+
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status; 
+}
+
+/**
+  * @brief  Encrypt and decrypt using TDES in CBC Mode
+  * @param  Mode: encryption or decryption Mode.
+  *           This parameter can be one of the following values:
+  *            @arg MODE_ENCRYPT: Encryption
+  *            @arg MODE_DECRYPT: Decryption
+  * @param  Key: Key used for TDES algorithm.
+  * @param  InitVectors: Initialisation Vectors used for TDES algorithm.
+  * @param  Input: pointer to the Input buffer.
+  * @param  Ilength: length of the Input buffer, must be a multiple of 8.
+  * @param  Output: pointer to the returned buffer.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: Operation done
+  *          - ERROR: Operation failed
+  */
+ErrorStatus CRYP_TDES_CBC(uint8_t Mode, uint8_t Key[24], uint8_t InitVectors[8],
+                          uint8_t *Input, uint32_t Ilength, uint8_t *Output)
+{
+  CRYP_InitTypeDef TDES_CRYP_InitStructure;
+  CRYP_KeyInitTypeDef TDES_CRYP_KeyInitStructure;
+  CRYP_IVInitTypeDef TDES_CRYP_IVInitStructure;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+  uint32_t ivaddr     = (uint32_t)InitVectors;
+  uint32_t i = 0;
+
+  /* Crypto structures initialisation*/
+  CRYP_KeyStructInit(&TDES_CRYP_KeyInitStructure);
+
+  /* Crypto Init for Encryption process */
+  if(Mode == MODE_ENCRYPT) /* TDES encryption */
+  {
+    TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Encrypt;
+  }
+  else
+  {
+    TDES_CRYP_InitStructure.CRYP_AlgoDir = CRYP_AlgoDir_Decrypt;
+  }
+  TDES_CRYP_InitStructure.CRYP_AlgoMode = CRYP_AlgoMode_TDES_CBC;
+  TDES_CRYP_InitStructure.CRYP_DataType = CRYP_DataType_8b;
+
+  CRYP_Init(&TDES_CRYP_InitStructure);
+
+  /* Key Initialisation */
+  TDES_CRYP_KeyInitStructure.CRYP_Key1Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key1Right= __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key2Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key2Right= __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key3Left = __REV(*(uint32_t*)(keyaddr));
+  keyaddr+=4;
+  TDES_CRYP_KeyInitStructure.CRYP_Key3Right= __REV(*(uint32_t*)(keyaddr));
+  CRYP_KeyInit(& TDES_CRYP_KeyInitStructure);
+
+  /* Initialization Vectors */
+  TDES_CRYP_IVInitStructure.CRYP_IV0Left = __REV(*(uint32_t*)(ivaddr));
+  ivaddr+=4;
+  TDES_CRYP_IVInitStructure.CRYP_IV0Right= __REV(*(uint32_t*)(ivaddr));
+  CRYP_IVInit(&TDES_CRYP_IVInitStructure);
+
+  /* Flush IN/OUT FIFO */
+  CRYP_FIFOFlush();
+
+  /* Enable Crypto processor */
+  CRYP_Cmd(ENABLE);
+
+  if(CRYP_GetCmdStatus() == DISABLE)
+  {
+    /* The CRYP peripheral clock is not enabled or the device doesn't embedd 
+       the CRYP peripheral (please check the device sales type. */
+    return(ERROR);
+  }
+  
+  for(i=0; ((i<Ilength) && (status != ERROR)); i+=8)
+  {
+    /* Write the Input block in the Input FIFO */
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+    CRYP_DataIn(*(uint32_t*)(inputaddr));
+    inputaddr+=4;
+
+    /* Wait until the complete message has been processed */
+    counter = 0;
+    do
+    {
+      busystatus = CRYP_GetFlagStatus(CRYP_FLAG_BUSY);
+      counter++;
+    }while ((counter != TDESBUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+   {
+       status = ERROR;
+    }
+    else
+    {
+
+      /* Read the Output block from the Output FIFO */
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+      *(uint32_t*)(outputaddr) = CRYP_DataOut();
+      outputaddr+=4;
+    }
+  }
+
+  /* Disable Crypto */
+  CRYP_Cmd(DISABLE);
+
+  return status; 
+}
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dac.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dac.c
new file mode 100644
index 0000000000000000000000000000000000000000..daff78d8835120543682a574b2076d5b0533dd72
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dac.c
@@ -0,0 +1,714 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dac.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+   * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Digital-to-Analog Converter (DAC) peripheral: 
+  *           + DAC channels configuration: trigger, output buffer, data format
+  *           + DMA management      
+  *           + Interrupts and flags management
+  *
+ @verbatim      
+ ===============================================================================
+                      ##### DAC Peripheral features #####
+ ===============================================================================
+    [..]        
+      *** DAC Channels ***
+      ====================  
+    [..]  
+    The device integrates two 12-bit Digital Analog Converters that can 
+    be used independently or simultaneously (dual mode):
+      (#) DAC channel1 with DAC_OUT1 (PA4) as output
+      (#) DAC channel2 with DAC_OUT2 (PA5) as output
+  
+      *** DAC Triggers ***
+      ====================
+    [..]
+    Digital to Analog conversion can be non-triggered using DAC_Trigger_None
+    and DAC_OUT1/DAC_OUT2 is available once writing to DHRx register 
+    using DAC_SetChannel1Data() / DAC_SetChannel2Data() functions.
+    [..] 
+    Digital to Analog conversion can be triggered by:
+      (#) External event: EXTI Line 9 (any GPIOx_Pin9) using DAC_Trigger_Ext_IT9.
+          The used pin (GPIOx_Pin9) must be configured in input mode.
+  
+      (#) Timers TRGO: TIM2, TIM4, TIM5, TIM6, TIM7 and TIM8 
+          (DAC_Trigger_T2_TRGO, DAC_Trigger_T4_TRGO...)
+          The timer TRGO event should be selected using TIM_SelectOutputTrigger()
+  
+      (#) Software using DAC_Trigger_Software
+  
+      *** DAC Buffer mode feature ***
+      =============================== 
+      [..] 
+      Each DAC channel integrates an output buffer that can be used to 
+      reduce the output impedance, and to drive external loads directly
+      without having to add an external operational amplifier.
+      To enable, the output buffer use  
+      DAC_InitStructure.DAC_OutputBuffer = DAC_OutputBuffer_Enable;
+      [..]           
+      (@) Refer to the device datasheet for more details about output 
+          impedance value with and without output buffer.
+            
+       *** DAC wave generation feature ***
+       =================================== 
+       [..]     
+       Both DAC channels can be used to generate
+         (#) Noise wave using DAC_WaveGeneration_Noise
+         (#) Triangle wave using DAC_WaveGeneration_Triangle
+          
+          -@-  Wave generation can be disabled using DAC_WaveGeneration_None
+  
+       *** DAC data format ***
+       =======================
+       [..]   
+       The DAC data format can be:
+         (#) 8-bit right alignment using DAC_Align_8b_R
+         (#) 12-bit left alignment using DAC_Align_12b_L
+         (#) 12-bit right alignment using DAC_Align_12b_R
+  
+       *** DAC data value to voltage correspondence ***  
+       ================================================ 
+       [..] 
+       The analog output voltage on each DAC channel pin is determined
+       by the following equation: 
+       DAC_OUTx = VREF+ * DOR / 4095
+       with  DOR is the Data Output Register
+          VEF+ is the input voltage reference (refer to the device datasheet)
+        e.g. To set DAC_OUT1 to 0.7V, use
+          DAC_SetChannel1Data(DAC_Align_12b_R, 868);
+          Assuming that VREF+ = 3.3V, DAC_OUT1 = (3.3 * 868) / 4095 = 0.7V
+  
+       *** DMA requests  ***
+       =====================
+       [..]    
+       A DMA1 request can be generated when an external trigger (but not
+       a software trigger) occurs if DMA1 requests are enabled using
+       DAC_DMACmd()
+       [..]
+       DMA1 requests are mapped as following:
+         (#) DAC channel1 : mapped on DMA1 Stream5 channel7 which must be 
+             already configured
+         (#) DAC channel2 : mapped on DMA1 Stream6 channel7 which must be 
+             already configured
+  
+      
+                      ##### How to use this driver #####
+ ===============================================================================
+    [..]          
+      (+) DAC APB clock must be enabled to get write access to DAC
+          registers using
+          RCC_APB1PeriphClockCmd(RCC_APB1Periph_DAC, ENABLE)
+      (+) Configure DAC_OUTx (DAC_OUT1: PA4, DAC_OUT2: PA5) in analog mode.
+      (+) Configure the DAC channel using DAC_Init() function
+      (+) Enable the DAC channel using DAC_Cmd() function
+   
+ @endverbatim    
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_dac.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DAC 
+  * @brief DAC driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* CR register Mask */
+#define CR_CLEAR_MASK              ((uint32_t)0x00000FFE)
+
+/* DAC Dual Channels SWTRIG masks */
+#define DUAL_SWTRIG_SET            ((uint32_t)0x00000003)
+#define DUAL_SWTRIG_RESET          ((uint32_t)0xFFFFFFFC)
+
+/* DHR registers offsets */
+#define DHR12R1_OFFSET             ((uint32_t)0x00000008)
+#define DHR12R2_OFFSET             ((uint32_t)0x00000014)
+#define DHR12RD_OFFSET             ((uint32_t)0x00000020)
+
+/* DOR register offset */
+#define DOR_OFFSET                 ((uint32_t)0x0000002C)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup DAC_Private_Functions
+  * @{
+  */
+
+/** @defgroup DAC_Group1 DAC channels configuration
+ *  @brief   DAC channels configuration: trigger, output buffer, data format 
+ *
+@verbatim   
+ ===============================================================================
+   ##### DAC channels configuration: trigger, output buffer, data format #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the DAC peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void DAC_DeInit(void)
+{
+  /* Enable DAC reset state */
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE);
+  /* Release DAC from reset state */
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE);
+}
+
+/**
+  * @brief  Initializes the DAC peripheral according to the specified parameters
+  *         in the DAC_InitStruct.
+  * @param  DAC_Channel: the selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_InitStruct: pointer to a DAC_InitTypeDef structure that contains
+  *         the configuration information for the  specified DAC channel.
+  * @retval None
+  */
+void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct)
+{
+  uint32_t tmpreg1 = 0, tmpreg2 = 0;
+
+  /* Check the DAC parameters */
+  assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger));
+  assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration));
+  assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude));
+  assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer));
+
+/*---------------------------- DAC CR Configuration --------------------------*/
+  /* Get the DAC CR value */
+  tmpreg1 = DAC->CR;
+  /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */
+  tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel);
+  /* Configure for the selected DAC channel: buffer output, trigger, 
+     wave generation, mask/amplitude for wave generation */
+  /* Set TSELx and TENx bits according to DAC_Trigger value */
+  /* Set WAVEx bits according to DAC_WaveGeneration value */
+  /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ 
+  /* Set BOFFx bit according to DAC_OutputBuffer value */   
+  tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration |
+             DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | \
+             DAC_InitStruct->DAC_OutputBuffer);
+  /* Calculate CR register value depending on DAC_Channel */
+  tmpreg1 |= tmpreg2 << DAC_Channel;
+  /* Write to DAC CR */
+  DAC->CR = tmpreg1;
+}
+
+/**
+  * @brief  Fills each DAC_InitStruct member with its default value.
+  * @param  DAC_InitStruct: pointer to a DAC_InitTypeDef structure which will 
+  *         be initialized.
+  * @retval None
+  */
+void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct)
+{
+/*--------------- Reset DAC init structure parameters values -----------------*/
+  /* Initialize the DAC_Trigger member */
+  DAC_InitStruct->DAC_Trigger = DAC_Trigger_None;
+  /* Initialize the DAC_WaveGeneration member */
+  DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None;
+  /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */
+  DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0;
+  /* Initialize the DAC_OutputBuffer member */
+  DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable;
+}
+
+/**
+  * @brief  Enables or disables the specified DAC channel.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  NewState: new state of the DAC channel. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @note   When the DAC channel is enabled the trigger source can no more be modified.
+  * @retval None
+  */
+void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DAC channel */
+    DAC->CR |= (DAC_CR_EN1 << DAC_Channel);
+  }
+  else
+  {
+    /* Disable the selected DAC channel */
+    DAC->CR &= (~(DAC_CR_EN1 << DAC_Channel));
+  }
+}
+
+/**
+  * @brief  Enables or disables the selected DAC channel software trigger.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  NewState: new state of the selected DAC channel software trigger.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable software trigger for the selected DAC channel */
+    DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4);
+  }
+  else
+  {
+    /* Disable software trigger for the selected DAC channel */
+    DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4));
+  }
+}
+
+/**
+  * @brief  Enables or disables simultaneously the two DAC channels software triggers.
+  * @param  NewState: new state of the DAC channels software triggers.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DAC_DualSoftwareTriggerCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable software trigger for both DAC channels */
+    DAC->SWTRIGR |= DUAL_SWTRIG_SET;
+  }
+  else
+  {
+    /* Disable software trigger for both DAC channels */
+    DAC->SWTRIGR &= DUAL_SWTRIG_RESET;
+  }
+}
+
+/**
+  * @brief  Enables or disables the selected DAC channel wave generation.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_Wave: specifies the wave type to enable or disable.
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Wave_Noise: noise wave generation
+  *            @arg DAC_Wave_Triangle: triangle wave generation
+  * @param  NewState: new state of the selected DAC channel wave generation.
+  *          This parameter can be: ENABLE or DISABLE.  
+  * @retval None
+  */
+void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_DAC_WAVE(DAC_Wave)); 
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected wave generation for the selected DAC channel */
+    DAC->CR |= DAC_Wave << DAC_Channel;
+  }
+  else
+  {
+    /* Disable the selected wave generation for the selected DAC channel */
+    DAC->CR &= ~(DAC_Wave << DAC_Channel);
+  }
+}
+
+/**
+  * @brief  Set the specified data holding register value for DAC channel1.
+  * @param  DAC_Align: Specifies the data alignment for DAC channel1.
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Align_8b_R: 8bit right data alignment selected
+  *            @arg DAC_Align_12b_L: 12bit left data alignment selected
+  *            @arg DAC_Align_12b_R: 12bit right data alignment selected
+  * @param  Data: Data to be loaded in the selected data holding register.
+  * @retval None
+  */
+void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data)
+{  
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DAC_ALIGN(DAC_Align));
+  assert_param(IS_DAC_DATA(Data));
+  
+  tmp = (uint32_t)DAC_BASE; 
+  tmp += DHR12R1_OFFSET + DAC_Align;
+
+  /* Set the DAC channel1 selected data holding register */
+  *(__IO uint32_t *) tmp = Data;
+}
+
+/**
+  * @brief  Set the specified data holding register value for DAC channel2.
+  * @param  DAC_Align: Specifies the data alignment for DAC channel2.
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Align_8b_R: 8bit right data alignment selected
+  *            @arg DAC_Align_12b_L: 12bit left data alignment selected
+  *            @arg DAC_Align_12b_R: 12bit right data alignment selected
+  * @param  Data: Data to be loaded in the selected data holding register.
+  * @retval None
+  */
+void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DAC_ALIGN(DAC_Align));
+  assert_param(IS_DAC_DATA(Data));
+  
+  tmp = (uint32_t)DAC_BASE;
+  tmp += DHR12R2_OFFSET + DAC_Align;
+
+  /* Set the DAC channel2 selected data holding register */
+  *(__IO uint32_t *)tmp = Data;
+}
+
+/**
+  * @brief  Set the specified data holding register value for dual channel DAC.
+  * @param  DAC_Align: Specifies the data alignment for dual channel DAC.
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Align_8b_R: 8bit right data alignment selected
+  *            @arg DAC_Align_12b_L: 12bit left data alignment selected
+  *            @arg DAC_Align_12b_R: 12bit right data alignment selected
+  * @param  Data2: Data for DAC Channel2 to be loaded in the selected data holding register.
+  * @param  Data1: Data for DAC Channel1 to be loaded in the selected data  holding register.
+  * @note   In dual mode, a unique register access is required to write in both
+  *          DAC channels at the same time.
+  * @retval None
+  */
+void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1)
+{
+  uint32_t data = 0, tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DAC_ALIGN(DAC_Align));
+  assert_param(IS_DAC_DATA(Data1));
+  assert_param(IS_DAC_DATA(Data2));
+  
+  /* Calculate and set dual DAC data holding register value */
+  if (DAC_Align == DAC_Align_8b_R)
+  {
+    data = ((uint32_t)Data2 << 8) | Data1; 
+  }
+  else
+  {
+    data = ((uint32_t)Data2 << 16) | Data1;
+  }
+  
+  tmp = (uint32_t)DAC_BASE;
+  tmp += DHR12RD_OFFSET + DAC_Align;
+
+  /* Set the dual DAC selected data holding register */
+  *(__IO uint32_t *)tmp = data;
+}
+
+/**
+  * @brief  Returns the last data output value of the selected DAC channel.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @retval The selected DAC channel data output value.
+  */
+uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel)
+{
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  
+  tmp = (uint32_t) DAC_BASE ;
+  tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2);
+  
+  /* Returns the DAC channel data output register value */
+  return (uint16_t) (*(__IO uint32_t*) tmp);
+}
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Group2 DMA management functions
+ *  @brief   DMA management functions
+ *
+@verbatim   
+ ===============================================================================
+                       ##### DMA management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified DAC channel DMA request.
+  * @note   When enabled DMA1 is generated when an external trigger (EXTI Line9,
+  *         TIM2, TIM4, TIM5, TIM6, TIM7 or TIM8  but not a software trigger) occurs.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  NewState: new state of the selected DAC channel DMA request.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @note   The DAC channel1 is mapped on DMA1 Stream 5 channel7 which must be
+  *          already configured.
+  * @note   The DAC channel2 is mapped on DMA1 Stream 6 channel7 which must be
+  *          already configured.    
+  * @retval None
+  */
+void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DAC channel DMA request */
+    DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel);
+  }
+  else
+  {
+    /* Disable the selected DAC channel DMA request */
+    DAC->CR &= (~(DAC_CR_DMAEN1 << DAC_Channel));
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup DAC_Group3 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+             ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified DAC interrupts.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_IT: specifies the DAC interrupt sources to be enabled or disabled. 
+  *          This parameter can be the following values:
+  *            @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
+  * @note   The DMA underrun occurs when a second external trigger arrives before the 
+  *         acknowledgement for the first external trigger is received (first request).
+  * @param  NewState: new state of the specified DAC interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */ 
+void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState)  
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_DAC_IT(DAC_IT)); 
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DAC interrupts */
+    DAC->CR |=  (DAC_IT << DAC_Channel);
+  }
+  else
+  {
+    /* Disable the selected DAC interrupts */
+    DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel));
+  }
+}
+
+/**
+  * @brief  Checks whether the specified DAC flag is set or not.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_FLAG: specifies the flag to check. 
+  *          This parameter can be only of the following value:
+  *            @arg DAC_FLAG_DMAUDR: DMA underrun flag
+  * @note   The DMA underrun occurs when a second external trigger arrives before the 
+  *         acknowledgement for the first external trigger is received (first request).
+  * @retval The new state of DAC_FLAG (SET or RESET).
+  */
+FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_DAC_FLAG(DAC_FLAG));
+
+  /* Check the status of the specified DAC flag */
+  if ((DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET)
+  {
+    /* DAC_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* DAC_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the DAC_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the DAC channel's pending flags.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_FLAG: specifies the flag to clear. 
+  *          This parameter can be of the following value:
+  *            @arg DAC_FLAG_DMAUDR: DMA underrun flag 
+  * @note   The DMA underrun occurs when a second external trigger arrives before the 
+  *         acknowledgement for the first external trigger is received (first request).                           
+  * @retval None
+  */
+void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_DAC_FLAG(DAC_FLAG));
+
+  /* Clear the selected DAC flags */
+  DAC->SR = (DAC_FLAG << DAC_Channel);
+}
+
+/**
+  * @brief  Checks whether the specified DAC interrupt has occurred or not.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_IT: specifies the DAC interrupt source to check. 
+  *          This parameter can be the following values:
+  *            @arg DAC_IT_DMAUDR: DMA underrun interrupt mask
+  * @note   The DMA underrun occurs when a second external trigger arrives before the 
+  *         acknowledgement for the first external trigger is received (first request).
+  * @retval The new state of DAC_IT (SET or RESET).
+  */
+ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t enablestatus = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_DAC_IT(DAC_IT));
+
+  /* Get the DAC_IT enable bit status */
+  enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ;
+  
+  /* Check the status of the specified DAC interrupt */
+  if (((DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus)
+  {
+    /* DAC_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* DAC_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the DAC_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the DAC channel's interrupt pending bits.
+  * @param  DAC_Channel: The selected DAC channel. 
+  *          This parameter can be one of the following values:
+  *            @arg DAC_Channel_1: DAC Channel1 selected
+  *            @arg DAC_Channel_2: DAC Channel2 selected
+  * @param  DAC_IT: specifies the DAC interrupt pending bit to clear.
+  *          This parameter can be the following values:
+  *            @arg DAC_IT_DMAUDR: DMA underrun interrupt mask                         
+  * @note   The DMA underrun occurs when a second external trigger arrives before the 
+  *         acknowledgement for the first external trigger is received (first request).                           
+  * @retval None
+  */
+void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_DAC_CHANNEL(DAC_Channel));
+  assert_param(IS_DAC_IT(DAC_IT)); 
+
+  /* Clear the selected DAC interrupt pending bits */
+  DAC->SR = (DAC_IT << DAC_Channel);
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c
new file mode 100644
index 0000000000000000000000000000000000000000..6460552372d225faf138a199bdec86a4632dc663
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dbgmcu.c
@@ -0,0 +1,180 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dbgmcu.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides all the DBGMCU firmware functions.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_dbgmcu.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DBGMCU 
+  * @brief DBGMCU driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define IDCODE_DEVID_MASK    ((uint32_t)0x00000FFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup DBGMCU_Private_Functions
+  * @{
+  */ 
+
+/**
+  * @brief  Returns the device revision identifier.
+  * @param  None
+  * @retval Device revision identifier
+  */
+uint32_t DBGMCU_GetREVID(void)
+{
+   return(DBGMCU->IDCODE >> 16);
+}
+
+/**
+  * @brief  Returns the device identifier.
+  * @param  None
+  * @retval Device identifier
+  */
+uint32_t DBGMCU_GetDEVID(void)
+{
+   return(DBGMCU->IDCODE & IDCODE_DEVID_MASK);
+}
+
+/**
+  * @brief  Configures low power mode behavior when the MCU is in Debug mode.
+  * @param  DBGMCU_Periph: specifies the low power mode.
+  *   This parameter can be any combination of the following values:
+  *     @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode              
+  *     @arg DBGMCU_STOP: Keep debugger connection during STOP mode               
+  *     @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode        
+  * @param  NewState: new state of the specified low power mode in Debug mode.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    DBGMCU->CR |= DBGMCU_Periph;
+  }
+  else
+  {
+    DBGMCU->CR &= ~DBGMCU_Periph;
+  }
+}
+
+/**
+  * @brief  Configures APB1 peripheral behavior when the MCU is in Debug mode.
+  * @param  DBGMCU_Periph: specifies the APB1 peripheral.
+  *   This parameter can be any combination of the following values:        
+  *     @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted
+  *     @arg DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted          
+  *     @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted
+  *     @arg DBGMCU_TIM12_STOP: TIM12 counter stopped when Core is halted  
+  *     @arg DBGMCU_TIM13_STOP: TIM13 counter stopped when Core is halted  
+  *     @arg DBGMCU_TIM14_STOP: TIM14 counter stopped when Core is halted 
+  *     @arg DBGMCU_RTC_STOP: RTC Calendar and Wakeup counter stopped when Core is halted.                                                                                
+  *     @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted
+  *     @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted        
+  *     @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when Core is halted
+  *     @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when Core is halted
+  *     @arg DBGMCU_I2C3_SMBUS_TIMEOUT: I2C3 SMBUS timeout mode stopped when Core is halted
+  *     @arg DBGMCU_CAN2_STOP: Debug CAN1 stopped when Core is halted           
+  *     @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted        
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DBGMCU_APB1PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DBGMCU_APB1PERIPH(DBGMCU_Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    DBGMCU->APB1FZ |= DBGMCU_Periph;
+  }
+  else
+  {
+    DBGMCU->APB1FZ &= ~DBGMCU_Periph;
+  }
+}
+
+/**
+  * @brief  Configures APB2 peripheral behavior when the MCU is in Debug mode.
+  * @param  DBGMCU_Periph: specifies the APB2 peripheral.
+  *   This parameter can be any combination of the following values:       
+  *     @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted                
+  *     @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted
+  *     @arg DBGMCU_TIM9_STOP: TIM9 counter stopped when Core is halted   
+  *     @arg DBGMCU_TIM10_STOP: TIM10 counter stopped when Core is halted   
+  *     @arg DBGMCU_TIM11_STOP: TIM11 counter stopped when Core is halted                                                                                  
+  * @param  NewState: new state of the specified peripheral in Debug mode.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DBGMCU_APB2PeriphConfig(uint32_t DBGMCU_Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DBGMCU_APB2PERIPH(DBGMCU_Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    DBGMCU->APB2FZ |= DBGMCU_Periph;
+  }
+  else
+  {
+    DBGMCU->APB2FZ &= ~DBGMCU_Periph;
+  }
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c
new file mode 100644
index 0000000000000000000000000000000000000000..e12a47e8cc66fc4155f659683ffd8603516b40ac
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c
@@ -0,0 +1,538 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dcmi.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the DCMI peripheral:           
+  *           + Initialization and Configuration
+  *           + Image capture functions  
+  *           + Interrupts and flags management
+  *
+ @verbatim          
+ ===============================================================================
+                        ##### How to use this driver #####
+ ===============================================================================  
+    [..]       
+      The sequence below describes how to use this driver to capture image
+      from a camera module connected to the DCMI Interface.
+      This sequence does not take into account the configuration of the  
+      camera module, which should be made before to configure and enable
+      the DCMI to capture images.
+             
+      (#) Enable the clock for the DCMI and associated GPIOs using the following 
+          functions:
+          RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_DCMI, ENABLE);
+          RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+  
+      (#) DCMI pins configuration 
+        (++) Connect the involved DCMI pins to AF13 using the following function 
+            GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_DCMI); 
+        (++) Configure these DCMI pins in alternate function mode by calling 
+            the function GPIO_Init();
+      
+      (#) Declare a DCMI_InitTypeDef structure, for example:
+          DCMI_InitTypeDef  DCMI_InitStructure;
+          and fill the DCMI_InitStructure variable with the allowed values
+          of the structure member.
+    
+      (#) Initialize the DCMI interface by calling the function
+          DCMI_Init(&DCMI_InitStructure); 
+    
+      (#) Configure the DMA2_Stream1 channel1 to transfer Data from DCMI DR
+          register to the destination memory buffer.
+    
+      (#) Enable DCMI interface using the function
+          DCMI_Cmd(ENABLE);
+                   
+      (#) Start the image capture using the function
+          DCMI_CaptureCmd(ENABLE);
+                   
+      (#) At this stage the DCMI interface waits for the first start of frame,
+          then a DMA request is generated continuously/once (depending on the
+          mode used, Continuous/Snapshot) to transfer the received data into
+          the destination memory. 
+     
+      -@-  If you need to capture only a rectangular window from the received
+           image, you have to use the DCMI_CROPConfig() function to configure 
+           the coordinates and size of the window to be captured, then enable 
+           the Crop feature using DCMI_CROPCmd(ENABLE);  
+           In this case, the Crop configuration should be made before to enable
+           and start the DCMI interface. 
+          
+ @endverbatim     
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_dcmi.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DCMI 
+  * @brief DCMI driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup DCMI_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup DCMI_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Initialization and Configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the DCMI registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void DCMI_DeInit(void)
+{
+  DCMI->CR = 0x0;
+  DCMI->IER = 0x0;
+  DCMI->ICR = 0x1F;
+  DCMI->ESCR = 0x0;
+  DCMI->ESUR = 0x0;
+  DCMI->CWSTRTR = 0x0;
+  DCMI->CWSIZER = 0x0;
+}
+
+/**
+  * @brief  Initializes the DCMI according to the specified parameters in the DCMI_InitStruct.
+  * @param  DCMI_InitStruct: pointer to a DCMI_InitTypeDef structure that contains 
+  *         the configuration information for the DCMI.
+  * @retval None
+  */
+void DCMI_Init(DCMI_InitTypeDef* DCMI_InitStruct)
+{
+  uint32_t temp = 0x0;
+  
+  /* Check the parameters */
+  assert_param(IS_DCMI_CAPTURE_MODE(DCMI_InitStruct->DCMI_CaptureMode));
+  assert_param(IS_DCMI_SYNCHRO(DCMI_InitStruct->DCMI_SynchroMode));
+  assert_param(IS_DCMI_PCKPOLARITY(DCMI_InitStruct->DCMI_PCKPolarity));
+  assert_param(IS_DCMI_VSPOLARITY(DCMI_InitStruct->DCMI_VSPolarity));
+  assert_param(IS_DCMI_HSPOLARITY(DCMI_InitStruct->DCMI_HSPolarity));
+  assert_param(IS_DCMI_CAPTURE_RATE(DCMI_InitStruct->DCMI_CaptureRate));
+  assert_param(IS_DCMI_EXTENDED_DATA(DCMI_InitStruct->DCMI_ExtendedDataMode));
+
+  /* The DCMI configuration registers should be programmed correctly before 
+  enabling the CR_ENABLE Bit and the CR_CAPTURE Bit */
+  DCMI->CR &= ~(DCMI_CR_ENABLE | DCMI_CR_CAPTURE);
+   
+  /* Reset the old DCMI configuration */
+  temp = DCMI->CR;
+  
+  temp &= ~((uint32_t)DCMI_CR_CM     | DCMI_CR_ESS   | DCMI_CR_PCKPOL |
+                      DCMI_CR_HSPOL  | DCMI_CR_VSPOL | DCMI_CR_FCRC_0 | 
+                      DCMI_CR_FCRC_1 | DCMI_CR_EDM_0 | DCMI_CR_EDM_1); 
+                  
+  /* Sets the new configuration of the DCMI peripheral */
+  temp |= ((uint32_t)DCMI_InitStruct->DCMI_CaptureMode |
+                     DCMI_InitStruct->DCMI_SynchroMode |
+                     DCMI_InitStruct->DCMI_PCKPolarity |
+                     DCMI_InitStruct->DCMI_VSPolarity |
+                     DCMI_InitStruct->DCMI_HSPolarity |
+                     DCMI_InitStruct->DCMI_CaptureRate |
+                     DCMI_InitStruct->DCMI_ExtendedDataMode);
+
+  DCMI->CR = temp;                              
+}
+
+/**
+  * @brief  Fills each DCMI_InitStruct member with its default value.
+  * @param  DCMI_InitStruct : pointer to a DCMI_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void DCMI_StructInit(DCMI_InitTypeDef* DCMI_InitStruct)
+{
+  /* Set the default configuration */
+  DCMI_InitStruct->DCMI_CaptureMode = DCMI_CaptureMode_Continuous;
+  DCMI_InitStruct->DCMI_SynchroMode = DCMI_SynchroMode_Hardware;
+  DCMI_InitStruct->DCMI_PCKPolarity = DCMI_PCKPolarity_Falling;
+  DCMI_InitStruct->DCMI_VSPolarity = DCMI_VSPolarity_Low;
+  DCMI_InitStruct->DCMI_HSPolarity = DCMI_HSPolarity_Low;
+  DCMI_InitStruct->DCMI_CaptureRate = DCMI_CaptureRate_All_Frame;
+  DCMI_InitStruct->DCMI_ExtendedDataMode = DCMI_ExtendedDataMode_8b;
+}
+
+/**
+  * @brief  Initializes the DCMI peripheral CROP mode according to the specified
+  *         parameters in the DCMI_CROPInitStruct.
+  * @note   This function should be called before to enable and start the DCMI interface.   
+  * @param  DCMI_CROPInitStruct:  pointer to a DCMI_CROPInitTypeDef structure that 
+  *         contains the configuration information for the DCMI peripheral CROP mode.
+  * @retval None
+  */
+void DCMI_CROPConfig(DCMI_CROPInitTypeDef* DCMI_CROPInitStruct)
+{  
+  /* Sets the CROP window coordinates */
+  DCMI->CWSTRTR = (uint32_t)((uint32_t)DCMI_CROPInitStruct->DCMI_HorizontalOffsetCount |
+                  ((uint32_t)DCMI_CROPInitStruct->DCMI_VerticalStartLine << 16));
+
+  /* Sets the CROP window size */
+  DCMI->CWSIZER = (uint32_t)(DCMI_CROPInitStruct->DCMI_CaptureCount |
+                  ((uint32_t)DCMI_CROPInitStruct->DCMI_VerticalLineCount << 16));
+}
+
+/**
+  * @brief  Enables or disables the DCMI Crop feature.
+  * @note   This function should be called before to enable and start the DCMI interface.
+  * @param  NewState: new state of the DCMI Crop feature. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DCMI_CROPCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  if (NewState != DISABLE)
+  {
+    /* Enable the DCMI Crop feature */
+    DCMI->CR |= (uint32_t)DCMI_CR_CROP;
+  }
+  else
+  {
+    /* Disable the DCMI Crop feature */
+    DCMI->CR &= ~(uint32_t)DCMI_CR_CROP;
+  }
+}
+
+/**
+  * @brief  Sets the embedded synchronization codes
+  * @param  DCMI_CodesInitTypeDef: pointer to a DCMI_CodesInitTypeDef structure that
+  *         contains the embedded synchronization codes for the DCMI peripheral.
+  * @retval None
+  */
+void DCMI_SetEmbeddedSynchroCodes(DCMI_CodesInitTypeDef* DCMI_CodesInitStruct)
+{
+  DCMI->ESCR = (uint32_t)(DCMI_CodesInitStruct->DCMI_FrameStartCode |
+                          ((uint32_t)DCMI_CodesInitStruct->DCMI_LineStartCode << 8)|
+                          ((uint32_t)DCMI_CodesInitStruct->DCMI_LineEndCode << 16)|
+                          ((uint32_t)DCMI_CodesInitStruct->DCMI_FrameEndCode << 24));
+}
+
+/**
+  * @brief  Enables or disables the DCMI JPEG format.
+  * @note   The Crop and Embedded Synchronization features cannot be used in this mode.  
+  * @param  NewState: new state of the DCMI JPEG format. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DCMI_JPEGCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+ 
+  if (NewState != DISABLE)
+  {
+    /* Enable the DCMI JPEG format */
+    DCMI->CR |= (uint32_t)DCMI_CR_JPEG;
+  }
+  else
+  {
+    /* Disable the DCMI JPEG format */
+    DCMI->CR &= ~(uint32_t)DCMI_CR_JPEG;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup DCMI_Group2 Image capture functions
+ *  @brief   Image capture functions
+ *
+@verbatim   
+ ===============================================================================
+                    ##### Image capture functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Enables or disables the DCMI interface.
+  * @param  NewState: new state of the DCMI interface. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DCMI_Cmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the DCMI by setting ENABLE bit */
+    DCMI->CR |= (uint32_t)DCMI_CR_ENABLE;
+  }
+  else
+  {
+    /* Disable the DCMI by clearing ENABLE bit */
+    DCMI->CR &= ~(uint32_t)DCMI_CR_ENABLE;
+  }
+}
+
+/**
+  * @brief  Enables or disables the DCMI Capture.
+  * @param  NewState: new state of the DCMI capture. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DCMI_CaptureCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  if (NewState != DISABLE)
+  {
+    /* Enable the DCMI Capture */
+    DCMI->CR |= (uint32_t)DCMI_CR_CAPTURE;
+  }
+  else
+  {
+    /* Disable the DCMI Capture */
+    DCMI->CR &= ~(uint32_t)DCMI_CR_CAPTURE;
+  }
+}
+
+/**
+  * @brief  Reads the data stored in the DR register.
+  * @param  None 
+  * @retval Data register value
+  */
+uint32_t DCMI_ReadData(void)
+{
+  return DCMI->DR;
+}
+/**
+  * @}
+  */
+
+/** @defgroup DCMI_Group3 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+             ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the DCMI interface interrupts.
+  * @param  DCMI_IT: specifies the DCMI interrupt sources to be enabled or disabled. 
+  *          This parameter can be any combination of the following values:
+  *            @arg DCMI_IT_FRAME: Frame capture complete interrupt mask
+  *            @arg DCMI_IT_OVF: Overflow interrupt mask
+  *            @arg DCMI_IT_ERR: Synchronization error interrupt mask
+  *            @arg DCMI_IT_VSYNC: VSYNC interrupt mask
+  *            @arg DCMI_IT_LINE: Line interrupt mask
+  * @param  NewState: new state of the specified DCMI interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DCMI_ITConfig(uint16_t DCMI_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DCMI_CONFIG_IT(DCMI_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the Interrupt sources */
+    DCMI->IER |= DCMI_IT;
+  }
+  else
+  {
+    /* Disable the Interrupt sources */
+    DCMI->IER &= (uint16_t)(~DCMI_IT);
+  }  
+}
+
+/**
+  * @brief  Checks whether the  DCMI interface flag is set or not.
+  * @param  DCMI_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg DCMI_FLAG_FRAMERI: Frame capture complete Raw flag mask
+  *            @arg DCMI_FLAG_OVFRI: Overflow Raw flag mask
+  *            @arg DCMI_FLAG_ERRRI: Synchronization error Raw flag mask
+  *            @arg DCMI_FLAG_VSYNCRI: VSYNC Raw flag mask
+  *            @arg DCMI_FLAG_LINERI: Line Raw flag mask
+  *            @arg DCMI_FLAG_FRAMEMI: Frame capture complete Masked flag mask
+  *            @arg DCMI_FLAG_OVFMI: Overflow Masked flag mask
+  *            @arg DCMI_FLAG_ERRMI: Synchronization error Masked flag mask
+  *            @arg DCMI_FLAG_VSYNCMI: VSYNC Masked flag mask
+  *            @arg DCMI_FLAG_LINEMI: Line Masked flag mask
+  *            @arg DCMI_FLAG_HSYNC: HSYNC flag mask
+  *            @arg DCMI_FLAG_VSYNC: VSYNC flag mask
+  *            @arg DCMI_FLAG_FNE: Fifo not empty flag mask
+  * @retval The new state of DCMI_FLAG (SET or RESET).
+  */
+FlagStatus DCMI_GetFlagStatus(uint16_t DCMI_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t dcmireg, tempreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DCMI_GET_FLAG(DCMI_FLAG));
+  
+  /* Get the DCMI register index */
+  dcmireg = (((uint16_t)DCMI_FLAG) >> 12);
+  
+  if (dcmireg == 0x00) /* The FLAG is in RISR register */
+  {
+    tempreg= DCMI->RISR;
+  }
+  else if (dcmireg == 0x02) /* The FLAG is in SR register */
+  {
+    tempreg = DCMI->SR;
+  }
+  else /* The FLAG is in MISR register */
+  {
+    tempreg = DCMI->MISR;
+  }
+  
+  if ((tempreg & DCMI_FLAG) != (uint16_t)RESET )
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the DCMI_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the DCMI's pending flags.
+  * @param  DCMI_FLAG: specifies the flag to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg DCMI_FLAG_FRAMERI: Frame capture complete Raw flag mask
+  *            @arg DCMI_FLAG_OVFRI: Overflow Raw flag mask
+  *            @arg DCMI_FLAG_ERRRI: Synchronization error Raw flag mask
+  *            @arg DCMI_FLAG_VSYNCRI: VSYNC Raw flag mask
+  *            @arg DCMI_FLAG_LINERI: Line Raw flag mask
+  * @retval None
+  */
+void DCMI_ClearFlag(uint16_t DCMI_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_DCMI_CLEAR_FLAG(DCMI_FLAG));
+  
+  /* Clear the flag by writing in the ICR register 1 in the corresponding 
+  Flag position*/
+  
+  DCMI->ICR = DCMI_FLAG;
+}
+
+/**
+  * @brief  Checks whether the DCMI interrupt has occurred or not.
+  * @param  DCMI_IT: specifies the DCMI interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg DCMI_IT_FRAME: Frame capture complete interrupt mask
+  *            @arg DCMI_IT_OVF: Overflow interrupt mask
+  *            @arg DCMI_IT_ERR: Synchronization error interrupt mask
+  *            @arg DCMI_IT_VSYNC: VSYNC interrupt mask
+  *            @arg DCMI_IT_LINE: Line interrupt mask
+  * @retval The new state of DCMI_IT (SET or RESET).
+  */
+ITStatus DCMI_GetITStatus(uint16_t DCMI_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t itstatus = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DCMI_GET_IT(DCMI_IT));
+  
+  itstatus = DCMI->MISR & DCMI_IT; /* Only masked interrupts are checked */
+  
+  if ((itstatus != (uint16_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the DCMI's interrupt pending bits.
+  * @param  DCMI_IT: specifies the DCMI interrupt pending bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg DCMI_IT_FRAME: Frame capture complete interrupt mask
+  *            @arg DCMI_IT_OVF: Overflow interrupt mask
+  *            @arg DCMI_IT_ERR: Synchronization error interrupt mask
+  *            @arg DCMI_IT_VSYNC: VSYNC interrupt mask
+  *            @arg DCMI_IT_LINE: Line interrupt mask
+  * @retval None
+  */
+void DCMI_ClearITPendingBit(uint16_t DCMI_IT)
+{
+  /* Clear the interrupt pending Bit by writing in the ICR register 1 in the 
+  corresponding pending Bit position*/
+  
+  DCMI->ICR = DCMI_IT;
+}
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c
new file mode 100644
index 0000000000000000000000000000000000000000..ef86764ea79f0de388e96632c5f24dbd6aeed0df
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c
@@ -0,0 +1,1301 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dma.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Direct Memory Access controller (DMA):           
+  *           + Initialization and Configuration
+  *           + Data Counter
+  *           + Double Buffer mode configuration and command  
+  *           + Interrupts and flags management
+  *           
+  @verbatim      
+ ===============================================================================      
+                       ##### How to use this driver #####
+ ===============================================================================
+    [..] 
+      (#) Enable The DMA controller clock using RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA1, ENABLE)
+          function for DMA1 or using RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA2, ENABLE)
+          function for DMA2.
+  
+      (#) Enable and configure the peripheral to be connected to the DMA Stream
+          (except for internal SRAM / FLASH memories: no initialization is 
+          necessary). 
+          
+      (#) For a given Stream, program the required configuration through following parameters:   
+          Source and Destination addresses, Transfer Direction, Transfer size, Source and Destination 
+          data formats, Circular or Normal mode, Stream Priority level, Source and Destination 
+          Incrementation mode, FIFO mode and its Threshold (if needed), Burst 
+          mode for Source and/or Destination (if needed) using the DMA_Init() function.
+          To avoid filling unneccessary fields, you can call DMA_StructInit() function
+          to initialize a given structure with default values (reset values), the modify
+          only necessary fields 
+          (ie. Source and Destination addresses, Transfer size and Data Formats).
+  
+      (#) Enable the NVIC and the corresponding interrupt(s) using the function 
+          DMA_ITConfig() if you need to use DMA interrupts. 
+  
+      (#) Optionally, if the Circular mode is enabled, you can use the Double buffer mode by configuring 
+          the second Memory address and the first Memory to be used through the function 
+          DMA_DoubleBufferModeConfig(). Then enable the Double buffer mode through the function
+          DMA_DoubleBufferModeCmd(). These operations must be done before step 6.
+      
+      (#) Enable the DMA stream using the DMA_Cmd() function. 
+                  
+      (#) Activate the needed Stream Request using PPP_DMACmd() function for
+          any PPP peripheral except internal SRAM and FLASH (ie. SPI, USART ...)
+          The function allowing this operation is provided in each PPP peripheral
+          driver (ie. SPI_DMACmd for SPI peripheral).
+          Once the Stream is enabled, it is not possible to modify its configuration
+          unless the stream is stopped and disabled.
+          After enabling the Stream, it is advised to monitor the EN bit status using
+          the function DMA_GetCmdStatus(). In case of configuration errors or bus errors
+          this bit will remain reset and all transfers on this Stream will remain on hold.      
+  
+      (#) Optionally, you can configure the number of data to be transferred
+          when the Stream is disabled (ie. after each Transfer Complete event
+          or when a Transfer Error occurs) using the function DMA_SetCurrDataCounter().
+          And you can get the number of remaining data to be transferred using 
+          the function DMA_GetCurrDataCounter() at run time (when the DMA Stream is
+          enabled and running).  
+                     
+      (#) To control DMA events you can use one of the following two methods:
+        (##) Check on DMA Stream flags using the function DMA_GetFlagStatus().  
+        (##) Use DMA interrupts through the function DMA_ITConfig() at initialization
+             phase and DMA_GetITStatus() function into interrupt routines in
+             communication phase.
+    [..]     
+          After checking on a flag you should clear it using DMA_ClearFlag()
+          function. And after checking on an interrupt event you should 
+          clear it using DMA_ClearITPendingBit() function.    
+                
+      (#) Optionally, if Circular mode and Double Buffer mode are enabled, you can modify
+          the Memory Addresses using the function DMA_MemoryTargetConfig(). Make sure that
+          the Memory Address to be modified is not the one currently in use by DMA Stream.
+          This condition can be monitored using the function DMA_GetCurrentMemoryTarget().
+                
+      (#) Optionally, Pause-Resume operations may be performed:
+          The DMA_Cmd() function may be used to perform Pause-Resume operation. 
+          When a transfer is ongoing, calling this function to disable the 
+          Stream will cause the transfer to be paused. All configuration registers 
+          and the number of remaining data will be preserved. When calling again 
+          this function to re-enable the Stream, the transfer will be resumed from 
+          the point where it was paused.          
+                   
+      -@- Memory-to-Memory transfer is possible by setting the address of the memory into
+           the Peripheral registers. In this mode, Circular mode and Double Buffer mode
+           are not allowed.
+    
+      -@- The FIFO is used mainly to reduce bus usage and to allow data 
+           packing/unpacking: it is possible to set different Data Sizes for 
+           the Peripheral and the Memory (ie. you can set Half-Word data size 
+           for the peripheral to access its data register and set Word data size
+           for the Memory to gain in access time. Each two Half-words will be 
+           packed and written in a single access to a Word in the Memory).
+      
+      -@- When FIFO is disabled, it is not allowed to configure different 
+           Data Sizes for Source and Destination. In this case the Peripheral 
+           Data Size will be applied to both Source and Destination.               
+  
+  @endverbatim                                 
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_dma.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DMA 
+  * @brief DMA driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* Masks Definition */
+#define TRANSFER_IT_ENABLE_MASK (uint32_t)(DMA_SxCR_TCIE | DMA_SxCR_HTIE | \
+                                           DMA_SxCR_TEIE | DMA_SxCR_DMEIE)
+
+#define DMA_Stream0_IT_MASK     (uint32_t)(DMA_LISR_FEIF0 | DMA_LISR_DMEIF0 | \
+                                           DMA_LISR_TEIF0 | DMA_LISR_HTIF0 | \
+                                           DMA_LISR_TCIF0)
+
+#define DMA_Stream1_IT_MASK     (uint32_t)(DMA_Stream0_IT_MASK << 6)
+#define DMA_Stream2_IT_MASK     (uint32_t)(DMA_Stream0_IT_MASK << 16)
+#define DMA_Stream3_IT_MASK     (uint32_t)(DMA_Stream0_IT_MASK << 22)
+#define DMA_Stream4_IT_MASK     (uint32_t)(DMA_Stream0_IT_MASK | (uint32_t)0x20000000)
+#define DMA_Stream5_IT_MASK     (uint32_t)(DMA_Stream1_IT_MASK | (uint32_t)0x20000000)
+#define DMA_Stream6_IT_MASK     (uint32_t)(DMA_Stream2_IT_MASK | (uint32_t)0x20000000)
+#define DMA_Stream7_IT_MASK     (uint32_t)(DMA_Stream3_IT_MASK | (uint32_t)0x20000000)
+#define TRANSFER_IT_MASK        (uint32_t)0x0F3C0F3C
+#define HIGH_ISR_MASK           (uint32_t)0x20000000
+#define RESERVED_MASK           (uint32_t)0x0F7D0F7D  
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+
+/** @defgroup DMA_Private_Functions
+  * @{
+  */
+
+/** @defgroup DMA_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions
+ *
+@verbatim   
+ ===============================================================================
+                ##### Initialization and Configuration functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides functions allowing to initialize the DMA Stream source
+    and destination addresses, incrementation and data sizes, transfer direction, 
+    buffer size, circular/normal mode selection, memory-to-memory mode selection 
+    and Stream priority value.
+    [..]
+    The DMA_Init() function follows the DMA configuration procedures as described in
+    reference manual (RM0090) except the first point: waiting on EN bit to be reset.
+    This condition should be checked by user application using the function DMA_GetCmdStatus()
+    before calling the DMA_Init() function.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitialize the DMAy Streamx registers to their default reset values.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *         to 7 to select the DMA Stream.
+  * @retval None
+  */
+void DMA_DeInit(DMA_Stream_TypeDef* DMAy_Streamx)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+
+  /* Disable the selected DMAy Streamx */
+  DMAy_Streamx->CR &= ~((uint32_t)DMA_SxCR_EN);
+
+  /* Reset DMAy Streamx control register */
+  DMAy_Streamx->CR  = 0;
+  
+  /* Reset DMAy Streamx Number of Data to Transfer register */
+  DMAy_Streamx->NDTR = 0;
+  
+  /* Reset DMAy Streamx peripheral address register */
+  DMAy_Streamx->PAR  = 0;
+  
+  /* Reset DMAy Streamx memory 0 address register */
+  DMAy_Streamx->M0AR = 0;
+
+  /* Reset DMAy Streamx memory 1 address register */
+  DMAy_Streamx->M1AR = 0;
+
+  /* Reset DMAy Streamx FIFO control register */
+  DMAy_Streamx->FCR = (uint32_t)0x00000021; 
+
+  /* Reset interrupt pending bits for the selected stream */
+  if (DMAy_Streamx == DMA1_Stream0)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream0 */
+    DMA1->LIFCR = DMA_Stream0_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA1_Stream1)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream1 */
+    DMA1->LIFCR = DMA_Stream1_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA1_Stream2)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream2 */
+    DMA1->LIFCR = DMA_Stream2_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA1_Stream3)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream3 */
+    DMA1->LIFCR = DMA_Stream3_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA1_Stream4)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream4 */
+    DMA1->HIFCR = DMA_Stream4_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA1_Stream5)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream5 */
+    DMA1->HIFCR = DMA_Stream5_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA1_Stream6)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream6 */
+    DMA1->HIFCR = (uint32_t)DMA_Stream6_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA1_Stream7)
+  {
+    /* Reset interrupt pending bits for DMA1 Stream7 */
+    DMA1->HIFCR = DMA_Stream7_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA2_Stream0)
+  {
+    /* Reset interrupt pending bits for DMA2 Stream0 */
+    DMA2->LIFCR = DMA_Stream0_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA2_Stream1)
+  {
+    /* Reset interrupt pending bits for DMA2 Stream1 */
+    DMA2->LIFCR = DMA_Stream1_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA2_Stream2)
+  {
+    /* Reset interrupt pending bits for DMA2 Stream2 */
+    DMA2->LIFCR = DMA_Stream2_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA2_Stream3)
+  {
+    /* Reset interrupt pending bits for DMA2 Stream3 */
+    DMA2->LIFCR = DMA_Stream3_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA2_Stream4)
+  {
+    /* Reset interrupt pending bits for DMA2 Stream4 */
+    DMA2->HIFCR = DMA_Stream4_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA2_Stream5)
+  {
+    /* Reset interrupt pending bits for DMA2 Stream5 */
+    DMA2->HIFCR = DMA_Stream5_IT_MASK;
+  }
+  else if (DMAy_Streamx == DMA2_Stream6)
+  {
+    /* Reset interrupt pending bits for DMA2 Stream6 */
+    DMA2->HIFCR = DMA_Stream6_IT_MASK;
+  }
+  else 
+  {
+    if (DMAy_Streamx == DMA2_Stream7)
+    {
+      /* Reset interrupt pending bits for DMA2 Stream7 */
+      DMA2->HIFCR = DMA_Stream7_IT_MASK;
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the DMAy Streamx according to the specified parameters in 
+  *         the DMA_InitStruct structure.
+  * @note   Before calling this function, it is recommended to check that the Stream 
+  *         is actually disabled using the function DMA_GetCmdStatus().  
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *         to 7 to select the DMA Stream.
+  * @param  DMA_InitStruct: pointer to a DMA_InitTypeDef structure that contains
+  *         the configuration information for the specified DMA Stream.  
+  * @retval None
+  */
+void DMA_Init(DMA_Stream_TypeDef* DMAy_Streamx, DMA_InitTypeDef* DMA_InitStruct)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_CHANNEL(DMA_InitStruct->DMA_Channel));
+  assert_param(IS_DMA_DIRECTION(DMA_InitStruct->DMA_DIR));
+  assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize));
+  assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc));
+  assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc));
+  assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize));
+  assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize));
+  assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode));
+  assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority));
+  assert_param(IS_DMA_FIFO_MODE_STATE(DMA_InitStruct->DMA_FIFOMode));
+  assert_param(IS_DMA_FIFO_THRESHOLD(DMA_InitStruct->DMA_FIFOThreshold));
+  assert_param(IS_DMA_MEMORY_BURST(DMA_InitStruct->DMA_MemoryBurst));
+  assert_param(IS_DMA_PERIPHERAL_BURST(DMA_InitStruct->DMA_PeripheralBurst));
+
+  /*------------------------- DMAy Streamx CR Configuration ------------------*/
+  /* Get the DMAy_Streamx CR value */
+  tmpreg = DMAy_Streamx->CR;
+
+  /* Clear CHSEL, MBURST, PBURST, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */
+  tmpreg &= ((uint32_t)~(DMA_SxCR_CHSEL | DMA_SxCR_MBURST | DMA_SxCR_PBURST | \
+                         DMA_SxCR_PL | DMA_SxCR_MSIZE | DMA_SxCR_PSIZE | \
+                         DMA_SxCR_MINC | DMA_SxCR_PINC | DMA_SxCR_CIRC | \
+                         DMA_SxCR_DIR));
+
+  /* Configure DMAy Streamx: */
+  /* Set CHSEL bits according to DMA_CHSEL value */
+  /* Set DIR bits according to DMA_DIR value */
+  /* Set PINC bit according to DMA_PeripheralInc value */
+  /* Set MINC bit according to DMA_MemoryInc value */
+  /* Set PSIZE bits according to DMA_PeripheralDataSize value */
+  /* Set MSIZE bits according to DMA_MemoryDataSize value */
+  /* Set CIRC bit according to DMA_Mode value */
+  /* Set PL bits according to DMA_Priority value */
+  /* Set MBURST bits according to DMA_MemoryBurst value */
+  /* Set PBURST bits according to DMA_PeripheralBurst value */
+  tmpreg |= DMA_InitStruct->DMA_Channel | DMA_InitStruct->DMA_DIR |
+            DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc |
+            DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize |
+            DMA_InitStruct->DMA_Mode | DMA_InitStruct->DMA_Priority |
+            DMA_InitStruct->DMA_MemoryBurst | DMA_InitStruct->DMA_PeripheralBurst;
+
+  /* Write to DMAy Streamx CR register */
+  DMAy_Streamx->CR = tmpreg;
+
+  /*------------------------- DMAy Streamx FCR Configuration -----------------*/
+  /* Get the DMAy_Streamx FCR value */
+  tmpreg = DMAy_Streamx->FCR;
+
+  /* Clear DMDIS and FTH bits */
+  tmpreg &= (uint32_t)~(DMA_SxFCR_DMDIS | DMA_SxFCR_FTH);
+
+  /* Configure DMAy Streamx FIFO: 
+    Set DMDIS bits according to DMA_FIFOMode value 
+    Set FTH bits according to DMA_FIFOThreshold value */
+  tmpreg |= DMA_InitStruct->DMA_FIFOMode | DMA_InitStruct->DMA_FIFOThreshold;
+
+  /* Write to DMAy Streamx CR */
+  DMAy_Streamx->FCR = tmpreg;
+
+  /*------------------------- DMAy Streamx NDTR Configuration ----------------*/
+  /* Write to DMAy Streamx NDTR register */
+  DMAy_Streamx->NDTR = DMA_InitStruct->DMA_BufferSize;
+
+  /*------------------------- DMAy Streamx PAR Configuration -----------------*/
+  /* Write to DMAy Streamx PAR */
+  DMAy_Streamx->PAR = DMA_InitStruct->DMA_PeripheralBaseAddr;
+
+  /*------------------------- DMAy Streamx M0AR Configuration ----------------*/
+  /* Write to DMAy Streamx M0AR */
+  DMAy_Streamx->M0AR = DMA_InitStruct->DMA_Memory0BaseAddr;
+}
+
+/**
+  * @brief  Fills each DMA_InitStruct member with its default value.
+  * @param  DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will 
+  *         be initialized.
+  * @retval None
+  */
+void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct)
+{
+  /*-------------- Reset DMA init structure parameters values ----------------*/
+  /* Initialize the DMA_Channel member */
+  DMA_InitStruct->DMA_Channel = 0;
+
+  /* Initialize the DMA_PeripheralBaseAddr member */
+  DMA_InitStruct->DMA_PeripheralBaseAddr = 0;
+
+  /* Initialize the DMA_Memory0BaseAddr member */
+  DMA_InitStruct->DMA_Memory0BaseAddr = 0;
+
+  /* Initialize the DMA_DIR member */
+  DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralToMemory;
+
+  /* Initialize the DMA_BufferSize member */
+  DMA_InitStruct->DMA_BufferSize = 0;
+
+  /* Initialize the DMA_PeripheralInc member */
+  DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+
+  /* Initialize the DMA_MemoryInc member */
+  DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable;
+
+  /* Initialize the DMA_PeripheralDataSize member */
+  DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+
+  /* Initialize the DMA_MemoryDataSize member */
+  DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+
+  /* Initialize the DMA_Mode member */
+  DMA_InitStruct->DMA_Mode = DMA_Mode_Normal;
+
+  /* Initialize the DMA_Priority member */
+  DMA_InitStruct->DMA_Priority = DMA_Priority_Low;
+
+  /* Initialize the DMA_FIFOMode member */
+  DMA_InitStruct->DMA_FIFOMode = DMA_FIFOMode_Disable;
+
+  /* Initialize the DMA_FIFOThreshold member */
+  DMA_InitStruct->DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
+
+  /* Initialize the DMA_MemoryBurst member */
+  DMA_InitStruct->DMA_MemoryBurst = DMA_MemoryBurst_Single;
+
+  /* Initialize the DMA_PeripheralBurst member */
+  DMA_InitStruct->DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+}
+
+/**
+  * @brief  Enables or disables the specified DMAy Streamx.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *         to 7 to select the DMA Stream.
+  * @param  NewState: new state of the DMAy Streamx. 
+  *          This parameter can be: ENABLE or DISABLE.
+  *
+  * @note  This function may be used to perform Pause-Resume operation. When a
+  *        transfer is ongoing, calling this function to disable the Stream will
+  *        cause the transfer to be paused. All configuration registers and the
+  *        number of remaining data will be preserved. When calling again this
+  *        function to re-enable the Stream, the transfer will be resumed from
+  *        the point where it was paused.          
+  *    
+  * @note  After configuring the DMA Stream (DMA_Init() function) and enabling the
+  *        stream, it is recommended to check (or wait until) the DMA Stream is
+  *        effectively enabled. A Stream may remain disabled if a configuration 
+  *        parameter is wrong.
+  *        After disabling a DMA Stream, it is also recommended to check (or wait
+  *        until) the DMA Stream is effectively disabled. If a Stream is disabled 
+  *        while a data transfer is ongoing, the current data will be transferred
+  *        and the Stream will be effectively disabled only after the transfer of
+  *        this single data is finished.            
+  *    
+  * @retval None
+  */
+void DMA_Cmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DMAy Streamx by setting EN bit */
+    DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_EN;
+  }
+  else
+  {
+    /* Disable the selected DMAy Streamx by clearing EN bit */
+    DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_EN;
+  }
+}
+
+/**
+  * @brief  Configures, when the PINC (Peripheral Increment address mode) bit is
+  *         set, if the peripheral address should be incremented with the data 
+  *         size (configured with PSIZE bits) or by a fixed offset equal to 4
+  *         (32-bit aligned addresses).
+  *   
+  * @note   This function has no effect if the Peripheral Increment mode is disabled.
+  *     
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  DMA_Pincos: specifies the Peripheral increment offset size.
+  *          This parameter can be one of the following values:
+  *            @arg DMA_PINCOS_Psize: Peripheral address increment is done  
+  *                                   accordingly to PSIZE parameter.
+  *            @arg DMA_PINCOS_WordAligned: Peripheral address increment offset is 
+  *                                         fixed to 4 (32-bit aligned addresses). 
+  * @retval None
+  */
+void DMA_PeriphIncOffsetSizeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_Pincos)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_PINCOS_SIZE(DMA_Pincos));
+
+  /* Check the needed Peripheral increment offset */
+  if(DMA_Pincos != DMA_PINCOS_Psize)
+  {
+    /* Configure DMA_SxCR_PINCOS bit with the input parameter */
+    DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_PINCOS;     
+  }
+  else
+  {
+    /* Clear the PINCOS bit: Peripheral address incremented according to PSIZE */
+    DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_PINCOS;    
+  }
+}
+
+/**
+  * @brief  Configures, when the DMAy Streamx is disabled, the flow controller for
+  *         the next transactions (Peripheral or Memory).
+  *       
+  * @note   Before enabling this feature, check if the used peripheral supports 
+  *         the Flow Controller mode or not.    
+  *  
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  DMA_FlowCtrl: specifies the DMA flow controller.
+  *          This parameter can be one of the following values:
+  *            @arg DMA_FlowCtrl_Memory: DMAy_Streamx transactions flow controller is 
+  *                                      the DMA controller.
+  *            @arg DMA_FlowCtrl_Peripheral: DMAy_Streamx transactions flow controller 
+  *                                          is the peripheral.    
+  * @retval None
+  */
+void DMA_FlowControllerConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FlowCtrl)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_FLOW_CTRL(DMA_FlowCtrl));
+
+  /* Check the needed flow controller  */
+  if(DMA_FlowCtrl != DMA_FlowCtrl_Memory)
+  {
+    /* Configure DMA_SxCR_PFCTRL bit with the input parameter */
+    DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_PFCTRL;   
+  }
+  else
+  {
+    /* Clear the PFCTRL bit: Memory is the flow controller */
+    DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_PFCTRL;    
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Group2 Data Counter functions
+ *  @brief   Data Counter functions 
+ *
+@verbatim   
+ ===============================================================================
+                      ##### Data Counter functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides function allowing to configure and read the buffer size
+    (number of data to be transferred). 
+    [..]
+    The DMA data counter can be written only when the DMA Stream is disabled 
+    (ie. after transfer complete event).
+    [..]
+    The following function can be used to write the Stream data counter value:
+      (+) void DMA_SetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx, uint16_t Counter);
+      -@- It is advised to use this function rather than DMA_Init() in situations 
+          where only the Data buffer needs to be reloaded.
+      -@- If the Source and Destination Data Sizes are different, then the value 
+          written in data counter, expressing the number of transfers, is relative 
+          to the number of transfers from the Peripheral point of view.
+          ie. If Memory data size is Word, Peripheral data size is Half-Words, 
+          then the value to be configured in the data counter is the number 
+          of Half-Words to be transferred from/to the peripheral.
+    [..]
+    The DMA data counter can be read to indicate the number of remaining transfers for
+    the relative DMA Stream. This counter is decremented at the end of each data 
+    transfer and when the transfer is complete: 
+      (+) If Normal mode is selected: the counter is set to 0.
+      (+) If Circular mode is selected: the counter is reloaded with the initial value
+          (configured before enabling the DMA Stream)
+     [..]
+     The following function can be used to read the Stream data counter value:
+       (+) uint16_t DMA_GetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx);
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Writes the number of data units to be transferred on the DMAy Streamx.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  Counter: Number of data units to be transferred (from 0 to 65535) 
+  *          Number of data items depends only on the Peripheral data format.
+  *            
+  * @note   If Peripheral data format is Bytes: number of data units is equal 
+  *         to total number of bytes to be transferred.
+  *           
+  * @note   If Peripheral data format is Half-Word: number of data units is  
+  *         equal to total number of bytes to be transferred / 2.
+  *           
+  * @note   If Peripheral data format is Word: number of data units is equal 
+  *         to total  number of bytes to be transferred / 4.
+  *      
+  * @note   In Memory-to-Memory transfer mode, the memory buffer pointed by 
+  *         DMAy_SxPAR register is considered as Peripheral.
+  *      
+  * @retval The number of remaining data units in the current DMAy Streamx transfer.
+  */
+void DMA_SetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx, uint16_t Counter)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+
+  /* Write the number of data units to be transferred */
+  DMAy_Streamx->NDTR = (uint16_t)Counter;
+}
+
+/**
+  * @brief  Returns the number of remaining data units in the current DMAy Streamx transfer.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @retval The number of remaining data units in the current DMAy Streamx transfer.
+  */
+uint16_t DMA_GetCurrDataCounter(DMA_Stream_TypeDef* DMAy_Streamx)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+
+  /* Return the number of remaining data units for DMAy Streamx */
+  return ((uint16_t)(DMAy_Streamx->NDTR));
+}
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Group3 Double Buffer mode functions
+ *  @brief   Double Buffer mode functions 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### Double Buffer mode functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides function allowing to configure and control the double 
+    buffer mode parameters.
+    
+    [..]
+    The Double Buffer mode can be used only when Circular mode is enabled.
+    The Double Buffer mode cannot be used when transferring data from Memory to Memory.
+    
+    [..]
+    The Double Buffer mode allows to set two different Memory addresses from/to which
+    the DMA controller will access alternatively (after completing transfer to/from 
+    target memory 0, it will start transfer to/from target memory 1).
+    This allows to reduce software overhead for double buffering and reduce the CPU
+    access time.
+    
+    [..]
+    Two functions must be called before calling the DMA_Init() function:
+      (+) void DMA_DoubleBufferModeConfig(DMA_Stream_TypeDef* DMAy_Streamx, 
+          uint32_t Memory1BaseAddr, uint32_t DMA_CurrentMemory);
+      (+) void DMA_DoubleBufferModeCmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState);
+      
+    [..]
+    DMA_DoubleBufferModeConfig() is called to configure the Memory 1 base address 
+    and the first Memory target from/to which the transfer will start after 
+    enabling the DMA Stream. Then DMA_DoubleBufferModeCmd() must be called 
+    to enable the Double Buffer mode (or disable it when it should not be used).
+  
+    [..]
+    Two functions can be called dynamically when the transfer is ongoing (or when the DMA Stream is 
+    stopped) to modify on of the target Memories addresses or to check wich Memory target is currently
+    used:
+      (+) void DMA_MemoryTargetConfig(DMA_Stream_TypeDef* DMAy_Streamx, 
+                uint32_t MemoryBaseAddr, uint32_t DMA_MemoryTarget);
+      (+) uint32_t DMA_GetCurrentMemoryTarget(DMA_Stream_TypeDef* DMAy_Streamx);
+      
+    [..]
+    DMA_MemoryTargetConfig() can be called to modify the base address of one of 
+    the two target Memories.
+    The Memory of which the base address will be modified must not be currently 
+    be used by the DMA Stream (ie. if the DMA Stream is currently transferring 
+    from Memory 1 then you can only modify base address of target Memory 0 and vice versa).
+    To check this condition, it is recommended to use the function DMA_GetCurrentMemoryTarget() which
+    returns the index of the Memory target currently in use by the DMA Stream.
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Configures, when the DMAy Streamx is disabled, the double buffer mode 
+  *         and the current memory target.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  Memory1BaseAddr: the base address of the second buffer (Memory 1)  
+  * @param  DMA_CurrentMemory: specifies which memory will be first buffer for
+  *         the transactions when the Stream will be enabled. 
+  *          This parameter can be one of the following values:
+  *            @arg DMA_Memory_0: Memory 0 is the current buffer.
+  *            @arg DMA_Memory_1: Memory 1 is the current buffer.  
+  *       
+  * @note   Memory0BaseAddr is set by the DMA structure configuration in DMA_Init().
+  *   
+  * @retval None
+  */
+void DMA_DoubleBufferModeConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t Memory1BaseAddr,
+                                uint32_t DMA_CurrentMemory)
+{  
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_CURRENT_MEM(DMA_CurrentMemory));
+
+  if (DMA_CurrentMemory != DMA_Memory_0)
+  {
+    /* Set Memory 1 as current memory address */
+    DMAy_Streamx->CR |= (uint32_t)(DMA_SxCR_CT);    
+  }
+  else
+  {
+    /* Set Memory 0 as current memory address */
+    DMAy_Streamx->CR &= ~(uint32_t)(DMA_SxCR_CT);    
+  }
+
+  /* Write to DMAy Streamx M1AR */
+  DMAy_Streamx->M1AR = Memory1BaseAddr;
+}
+
+/**
+  * @brief  Enables or disables the double buffer mode for the selected DMA stream.
+  * @note   This function can be called only when the DMA Stream is disabled.  
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  NewState: new state of the DMAy Streamx double buffer mode. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DMA_DoubleBufferModeCmd(DMA_Stream_TypeDef* DMAy_Streamx, FunctionalState NewState)
+{  
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Configure the Double Buffer mode */
+  if (NewState != DISABLE)
+  {
+    /* Enable the Double buffer mode */
+    DMAy_Streamx->CR |= (uint32_t)DMA_SxCR_DBM;
+  }
+  else
+  {
+    /* Disable the Double buffer mode */
+    DMAy_Streamx->CR &= ~(uint32_t)DMA_SxCR_DBM;
+  }
+}
+
+/**
+  * @brief  Configures the Memory address for the next buffer transfer in double
+  *         buffer mode (for dynamic use). This function can be called when the
+  *         DMA Stream is enabled and when the transfer is ongoing.  
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  MemoryBaseAddr: The base address of the target memory buffer
+  * @param  DMA_MemoryTarget: Next memory target to be used. 
+  *         This parameter can be one of the following values:
+  *            @arg DMA_Memory_0: To use the memory address 0
+  *            @arg DMA_Memory_1: To use the memory address 1
+  * 
+  * @note    It is not allowed to modify the Base Address of a target Memory when
+  *          this target is involved in the current transfer. ie. If the DMA Stream
+  *          is currently transferring to/from Memory 1, then it not possible to
+  *          modify Base address of Memory 1, but it is possible to modify Base
+  *          address of Memory 0.
+  *          To know which Memory is currently used, you can use the function
+  *          DMA_GetCurrentMemoryTarget().             
+  *  
+  * @retval None
+  */
+void DMA_MemoryTargetConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t MemoryBaseAddr,
+                           uint32_t DMA_MemoryTarget)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_CURRENT_MEM(DMA_MemoryTarget));
+    
+  /* Check the Memory target to be configured */
+  if (DMA_MemoryTarget != DMA_Memory_0)
+  {
+    /* Write to DMAy Streamx M1AR */
+    DMAy_Streamx->M1AR = MemoryBaseAddr;    
+  }  
+  else
+  {
+    /* Write to DMAy Streamx M0AR */
+    DMAy_Streamx->M0AR = MemoryBaseAddr;  
+  }
+}
+
+/**
+  * @brief  Returns the current memory target used by double buffer transfer.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @retval The memory target number: 0 for Memory0 or 1 for Memory1. 
+  */
+uint32_t DMA_GetCurrentMemoryTarget(DMA_Stream_TypeDef* DMAy_Streamx)
+{
+  uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+
+  /* Get the current memory target */
+  if ((DMAy_Streamx->CR & DMA_SxCR_CT) != 0)
+  {
+    /* Current memory buffer used is Memory 1 */
+    tmp = 1;
+  }  
+  else
+  {
+    /* Current memory buffer used is Memory 0 */
+    tmp = 0;    
+  }
+  return tmp;
+}
+/**
+  * @}
+  */
+
+/** @defgroup DMA_Group4 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Interrupts and flags management functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides functions allowing to
+      (+) Check the DMA enable status
+      (+) Check the FIFO status 
+      (+) Configure the DMA Interrupts sources and check or clear the flags or 
+          pending bits status.  
+           
+    [..]
+      (#) DMA Enable status:
+          After configuring the DMA Stream (DMA_Init() function) and enabling 
+          the stream, it is recommended to check (or wait until) the DMA Stream 
+          is effectively enabled. A Stream may remain disabled if a configuration 
+          parameter is wrong. After disabling a DMA Stream, it is also recommended 
+          to check (or wait until) the DMA Stream is effectively disabled. 
+          If a Stream is disabled while a data transfer is ongoing, the current 
+          data will be transferred and the Stream will be effectively disabled 
+          only after this data transfer completion.
+          To monitor this state it is possible to use the following function:
+        (++) FunctionalState DMA_GetCmdStatus(DMA_Stream_TypeDef* DMAy_Streamx); 
+ 
+      (#) FIFO Status:
+          It is possible to monitor the FIFO status when a transfer is ongoing 
+          using the following function:
+        (++) uint32_t DMA_GetFIFOStatus(DMA_Stream_TypeDef* DMAy_Streamx); 
+ 
+      (#) DMA Interrupts and Flags:
+          The user should identify which mode will be used in his application 
+          to manage the DMA controller events: Polling mode or Interrupt mode. 
+    
+    *** Polling Mode ***
+    ====================
+    [..]
+    Each DMA stream can be managed through 4 event Flags:
+    (x : DMA Stream number )
+      (#) DMA_FLAG_FEIFx  : to indicate that a FIFO Mode Transfer Error event occurred.
+      (#) DMA_FLAG_DMEIFx : to indicate that a Direct Mode Transfer Error event occurred.
+      (#) DMA_FLAG_TEIFx  : to indicate that a Transfer Error event occurred.
+      (#) DMA_FLAG_HTIFx  : to indicate that a Half-Transfer Complete event occurred.
+      (#) DMA_FLAG_TCIFx  : to indicate that a Transfer Complete event occurred .       
+    [..]
+    In this Mode it is advised to use the following functions:
+      (+) FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG);
+      (+) void DMA_ClearFlag(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG);
+
+    *** Interrupt Mode ***
+    ======================
+    [..]
+    Each DMA Stream can be managed through 4 Interrupts:
+
+    *** Interrupt Source ***
+    ========================
+    [..]
+      (#) DMA_IT_FEIFx  : specifies the interrupt source for the  FIFO Mode Transfer Error event.
+      (#) DMA_IT_DMEIFx : specifies the interrupt source for the Direct Mode Transfer Error event.
+      (#) DMA_IT_TEIFx  : specifies the interrupt source for the Transfer Error event.
+      (#) DMA_IT_HTIFx  : specifies the interrupt source for the Half-Transfer Complete event.
+      (#) DMA_IT_TCIFx  : specifies the interrupt source for the a Transfer Complete event. 
+    [..]
+    In this Mode it is advised to use the following functions:
+      (+) void DMA_ITConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState);
+      (+) ITStatus DMA_GetITStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT);
+      (+) void DMA_ClearITPendingBit(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT);
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Returns the status of EN bit for the specified DMAy Streamx.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  *   
+  * @note    After configuring the DMA Stream (DMA_Init() function) and enabling
+  *          the stream, it is recommended to check (or wait until) the DMA Stream
+  *          is effectively enabled. A Stream may remain disabled if a configuration
+  *          parameter is wrong.
+  *          After disabling a DMA Stream, it is also recommended to check (or wait 
+  *          until) the DMA Stream is effectively disabled. If a Stream is disabled
+  *          while a data transfer is ongoing, the current data will be transferred
+  *          and the Stream will be effectively disabled only after the transfer
+  *          of this single data is finished.  
+  *      
+  * @retval Current state of the DMAy Streamx (ENABLE or DISABLE).
+  */
+FunctionalState DMA_GetCmdStatus(DMA_Stream_TypeDef* DMAy_Streamx)
+{
+  FunctionalState state = DISABLE;
+
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+
+  if ((DMAy_Streamx->CR & (uint32_t)DMA_SxCR_EN) != 0)
+  {
+    /* The selected DMAy Streamx EN bit is set (DMA is still transferring) */
+    state = ENABLE;
+  }
+  else
+  {
+    /* The selected DMAy Streamx EN bit is cleared (DMA is disabled and 
+        all transfers are complete) */
+    state = DISABLE;
+  }
+  return state;
+}
+
+/**
+  * @brief  Returns the current DMAy Streamx FIFO filled level.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0 
+  *         to 7 to select the DMA Stream.
+  * @retval The FIFO filling state.
+  *           - DMA_FIFOStatus_Less1QuarterFull: when FIFO is less than 1 quarter-full 
+  *                                               and not empty.
+  *           - DMA_FIFOStatus_1QuarterFull: if more than 1 quarter-full.
+  *           - DMA_FIFOStatus_HalfFull: if more than 1 half-full.
+  *           - DMA_FIFOStatus_3QuartersFull: if more than 3 quarters-full.
+  *           - DMA_FIFOStatus_Empty: when FIFO is empty
+  *           - DMA_FIFOStatus_Full: when FIFO is full
+  */
+uint32_t DMA_GetFIFOStatus(DMA_Stream_TypeDef* DMAy_Streamx)
+{
+  uint32_t tmpreg = 0;
+ 
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  
+  /* Get the FIFO level bits */
+  tmpreg = (uint32_t)((DMAy_Streamx->FCR & DMA_SxFCR_FS));
+  
+  return tmpreg;
+}
+
+/**
+  * @brief  Checks whether the specified DMAy Streamx flag is set or not.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  DMA_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg DMA_FLAG_TCIFx:  Streamx transfer complete flag
+  *            @arg DMA_FLAG_HTIFx:  Streamx half transfer complete flag
+  *            @arg DMA_FLAG_TEIFx:  Streamx transfer error flag
+  *            @arg DMA_FLAG_DMEIFx: Streamx direct mode error flag
+  *            @arg DMA_FLAG_FEIFx:  Streamx FIFO error flag
+  *         Where x can be 0 to 7 to select the DMA Stream.
+  * @retval The new state of DMA_FLAG (SET or RESET).
+  */
+FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  DMA_TypeDef* DMAy;
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_GET_FLAG(DMA_FLAG));
+
+  /* Determine the DMA to which belongs the stream */
+  if (DMAy_Streamx < DMA2_Stream0)
+  {
+    /* DMAy_Streamx belongs to DMA1 */
+    DMAy = DMA1; 
+  } 
+  else 
+  {
+    /* DMAy_Streamx belongs to DMA2 */
+    DMAy = DMA2; 
+  }
+
+  /* Check if the flag is in HISR or LISR */
+  if ((DMA_FLAG & HIGH_ISR_MASK) != (uint32_t)RESET)
+  {
+    /* Get DMAy HISR register value */
+    tmpreg = DMAy->HISR;
+  }
+  else
+  {
+    /* Get DMAy LISR register value */
+    tmpreg = DMAy->LISR;
+  }   
+ 
+  /* Mask the reserved bits */
+  tmpreg &= (uint32_t)RESERVED_MASK;
+
+  /* Check the status of the specified DMA flag */
+  if ((tmpreg & DMA_FLAG) != (uint32_t)RESET)
+  {
+    /* DMA_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* DMA_FLAG is reset */
+    bitstatus = RESET;
+  }
+
+  /* Return the DMA_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the DMAy Streamx's pending flags.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  DMA_FLAG: specifies the flag to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg DMA_FLAG_TCIFx:  Streamx transfer complete flag
+  *            @arg DMA_FLAG_HTIFx:  Streamx half transfer complete flag
+  *            @arg DMA_FLAG_TEIFx:  Streamx transfer error flag
+  *            @arg DMA_FLAG_DMEIFx: Streamx direct mode error flag
+  *            @arg DMA_FLAG_FEIFx:  Streamx FIFO error flag
+  *         Where x can be 0 to 7 to select the DMA Stream.   
+  * @retval None
+  */
+void DMA_ClearFlag(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_FLAG)
+{
+  DMA_TypeDef* DMAy;
+
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_CLEAR_FLAG(DMA_FLAG));
+
+  /* Determine the DMA to which belongs the stream */
+  if (DMAy_Streamx < DMA2_Stream0)
+  {
+    /* DMAy_Streamx belongs to DMA1 */
+    DMAy = DMA1; 
+  } 
+  else 
+  {
+    /* DMAy_Streamx belongs to DMA2 */
+    DMAy = DMA2; 
+  }
+
+  /* Check if LIFCR or HIFCR register is targeted */
+  if ((DMA_FLAG & HIGH_ISR_MASK) != (uint32_t)RESET)
+  {
+    /* Set DMAy HIFCR register clear flag bits */
+    DMAy->HIFCR = (uint32_t)(DMA_FLAG & RESERVED_MASK);
+  }
+  else 
+  {
+    /* Set DMAy LIFCR register clear flag bits */
+    DMAy->LIFCR = (uint32_t)(DMA_FLAG & RESERVED_MASK);
+  }    
+}
+
+/**
+  * @brief  Enables or disables the specified DMAy Streamx interrupts.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param DMA_IT: specifies the DMA interrupt sources to be enabled or disabled. 
+  *          This parameter can be any combination of the following values:
+  *            @arg DMA_IT_TC:  Transfer complete interrupt mask
+  *            @arg DMA_IT_HT:  Half transfer complete interrupt mask
+  *            @arg DMA_IT_TE:  Transfer error interrupt mask
+  *            @arg DMA_IT_FE:  FIFO error interrupt mask
+  * @param  NewState: new state of the specified DMA interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DMA_ITConfig(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_CONFIG_IT(DMA_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Check if the DMA_IT parameter contains a FIFO interrupt */
+  if ((DMA_IT & DMA_IT_FE) != 0)
+  {
+    if (NewState != DISABLE)
+    {
+      /* Enable the selected DMA FIFO interrupts */
+      DMAy_Streamx->FCR |= (uint32_t)DMA_IT_FE;
+    }    
+    else 
+    {
+      /* Disable the selected DMA FIFO interrupts */
+      DMAy_Streamx->FCR &= ~(uint32_t)DMA_IT_FE;  
+    }
+  }
+
+  /* Check if the DMA_IT parameter contains a Transfer interrupt */
+  if (DMA_IT != DMA_IT_FE)
+  {
+    if (NewState != DISABLE)
+    {
+      /* Enable the selected DMA transfer interrupts */
+      DMAy_Streamx->CR |= (uint32_t)(DMA_IT  & TRANSFER_IT_ENABLE_MASK);
+    }
+    else
+    {
+      /* Disable the selected DMA transfer interrupts */
+      DMAy_Streamx->CR &= ~(uint32_t)(DMA_IT & TRANSFER_IT_ENABLE_MASK);
+    }    
+  }
+}
+
+/**
+  * @brief  Checks whether the specified DMAy Streamx interrupt has occurred or not.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  DMA_IT: specifies the DMA interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg DMA_IT_TCIFx:  Streamx transfer complete interrupt
+  *            @arg DMA_IT_HTIFx:  Streamx half transfer complete interrupt
+  *            @arg DMA_IT_TEIFx:  Streamx transfer error interrupt
+  *            @arg DMA_IT_DMEIFx: Streamx direct mode error interrupt
+  *            @arg DMA_IT_FEIFx:  Streamx FIFO error interrupt
+  *         Where x can be 0 to 7 to select the DMA Stream.
+  * @retval The new state of DMA_IT (SET or RESET).
+  */
+ITStatus DMA_GetITStatus(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT)
+{
+  ITStatus bitstatus = RESET;
+  DMA_TypeDef* DMAy;
+  uint32_t tmpreg = 0, enablestatus = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_GET_IT(DMA_IT));
+ 
+  /* Determine the DMA to which belongs the stream */
+  if (DMAy_Streamx < DMA2_Stream0)
+  {
+    /* DMAy_Streamx belongs to DMA1 */
+    DMAy = DMA1; 
+  } 
+  else 
+  {
+    /* DMAy_Streamx belongs to DMA2 */
+    DMAy = DMA2; 
+  }
+
+  /* Check if the interrupt enable bit is in the CR or FCR register */
+  if ((DMA_IT & TRANSFER_IT_MASK) != (uint32_t)RESET)
+  {
+    /* Get the interrupt enable position mask in CR register */
+    tmpreg = (uint32_t)((DMA_IT >> 11) & TRANSFER_IT_ENABLE_MASK);   
+    
+    /* Check the enable bit in CR register */
+    enablestatus = (uint32_t)(DMAy_Streamx->CR & tmpreg);
+  }
+  else 
+  {
+    /* Check the enable bit in FCR register */
+    enablestatus = (uint32_t)(DMAy_Streamx->FCR & DMA_IT_FE); 
+  }
+ 
+  /* Check if the interrupt pending flag is in LISR or HISR */
+  if ((DMA_IT & HIGH_ISR_MASK) != (uint32_t)RESET)
+  {
+    /* Get DMAy HISR register value */
+    tmpreg = DMAy->HISR ;
+  }
+  else
+  {
+    /* Get DMAy LISR register value */
+    tmpreg = DMAy->LISR ;
+  } 
+
+  /* mask all reserved bits */
+  tmpreg &= (uint32_t)RESERVED_MASK;
+
+  /* Check the status of the specified DMA interrupt */
+  if (((tmpreg & DMA_IT) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET))
+  {
+    /* DMA_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* DMA_IT is reset */
+    bitstatus = RESET;
+  }
+
+  /* Return the DMA_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the DMAy Streamx's interrupt pending bits.
+  * @param  DMAy_Streamx: where y can be 1 or 2 to select the DMA and x can be 0
+  *          to 7 to select the DMA Stream.
+  * @param  DMA_IT: specifies the DMA interrupt pending bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg DMA_IT_TCIFx:  Streamx transfer complete interrupt
+  *            @arg DMA_IT_HTIFx:  Streamx half transfer complete interrupt
+  *            @arg DMA_IT_TEIFx:  Streamx transfer error interrupt
+  *            @arg DMA_IT_DMEIFx: Streamx direct mode error interrupt
+  *            @arg DMA_IT_FEIFx:  Streamx FIFO error interrupt
+  *         Where x can be 0 to 7 to select the DMA Stream.
+  * @retval None
+  */
+void DMA_ClearITPendingBit(DMA_Stream_TypeDef* DMAy_Streamx, uint32_t DMA_IT)
+{
+  DMA_TypeDef* DMAy;
+
+  /* Check the parameters */
+  assert_param(IS_DMA_ALL_PERIPH(DMAy_Streamx));
+  assert_param(IS_DMA_CLEAR_IT(DMA_IT));
+
+  /* Determine the DMA to which belongs the stream */
+  if (DMAy_Streamx < DMA2_Stream0)
+  {
+    /* DMAy_Streamx belongs to DMA1 */
+    DMAy = DMA1; 
+  } 
+  else 
+  {
+    /* DMAy_Streamx belongs to DMA2 */
+    DMAy = DMA2; 
+  }
+
+  /* Check if LIFCR or HIFCR register is targeted */
+  if ((DMA_IT & HIGH_ISR_MASK) != (uint32_t)RESET)
+  {
+    /* Set DMAy HIFCR register clear interrupt bits */
+    DMAy->HIFCR = (uint32_t)(DMA_IT & RESERVED_MASK);
+  }
+  else 
+  {
+    /* Set DMAy LIFCR register clear interrupt bits */
+    DMAy->LIFCR = (uint32_t)(DMA_IT & RESERVED_MASK);
+  }   
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma2d.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma2d.c
new file mode 100644
index 0000000000000000000000000000000000000000..46b3d7ae8c5cc52d267a8b96e1b2d41ba11c81c6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma2d.c
@@ -0,0 +1,778 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_dma2d.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the DMA2D controller (DMA2D) peripheral:
+  *           + Initialization and configuration
+  *           + Interrupts and flags management
+  *           
+  @verbatim  
+ ===============================================================================
+                      ##### How to use this driver #####
+ ===============================================================================
+    [..]
+        (#) Enable DMA2D clock using 
+            RCC_APB2PeriphResetCmd(RCC_APB2Periph_DMA2D, ENABLE) function.
+            
+        (#) Configures DMA2D
+          (++) transfer mode 
+          (++) pixel format, line_number, pixel_per_line
+          (++) output memory address
+          (++) alpha value
+          (++) output offset
+          (++) Default color (RGB)
+           
+        (#) Configures Foreground or/and background
+          (++) memory address
+          (++) alpha value
+          (++) offset and default color
+  
+        (#) Call the DMA2D_Start() to enable the DMA2D controller.
+        
+    @endverbatim
+  
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_dma2d.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup DMA2D 
+  * @brief DMA2D driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+#define CR_MASK                     ((uint32_t)0xFFFCE0FC)  /* DMA2D CR Mask */
+#define PFCCR_MASK                  ((uint32_t)0x00FC00C0)  /* DMA2D FGPFCCR Mask */
+#define DEAD_MASK                   ((uint32_t)0xFFFF00FE)  /* DMA2D DEAD Mask */
+
+/** @defgroup DMA2D_Private_Functions
+  * @{
+  */
+
+/** @defgroup DMA2D_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim
+ ===============================================================================
+            ##### Initialization and Configuration functions #####
+ ===============================================================================
+    [..]  This section provides functions allowing to:
+      (+) Initialize and configure the DMA2D
+      (+) Start/Abort/Suspend Transfer
+      (+) Initialize, configure and set Foreground and background
+      (+) configure and enable DeadTime
+      (+) configure lineWatermark
+    
+    
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the DMA2D peripheral registers to their default reset
+  *         values.
+  * @param  None
+  * @retval None
+  */
+
+void DMA2D_DeInit(void)
+{
+  /* Enable DMA2D reset state */
+  RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA2D, ENABLE);
+  /* Release DMA2D from reset state */
+  RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_DMA2D, DISABLE);
+}
+
+
+/**
+  * @brief  Initializes the DMA2D peripheral according to the specified parameters
+  *         in the DMA2D_InitStruct.
+  * @note   This function can be used only when the DMA2D is disabled.
+  * @param  DMA2D_InitStruct: pointer to a DMA2D_InitTypeDef structure that contains
+  *         the configuration information for the specified DMA2D peripheral.
+  * @retval None
+  */
+void DMA2D_Init(DMA2D_InitTypeDef* DMA2D_InitStruct)
+{
+
+  uint32_t outgreen = 0;
+  uint32_t outred   = 0;
+  uint32_t outalpha = 0;
+  uint32_t pixline  = 0;
+
+  /* Check the parameters */
+  assert_param(IS_DMA2D_MODE(DMA2D_InitStruct->DMA2D_Mode));
+  assert_param(IS_DMA2D_CMODE(DMA2D_InitStruct->DMA2D_CMode));
+  assert_param(IS_DMA2D_OGREEN(DMA2D_InitStruct->DMA2D_OutputGreen));
+  assert_param(IS_DMA2D_ORED(DMA2D_InitStruct->DMA2D_OutputRed));
+  assert_param(IS_DMA2D_OBLUE(DMA2D_InitStruct->DMA2D_OutputBlue));
+  assert_param(IS_DMA2D_OALPHA(DMA2D_InitStruct->DMA2D_OutputAlpha));
+  assert_param(IS_DMA2D_OUTPUT_OFFSET(DMA2D_InitStruct->DMA2D_OutputOffset));
+  assert_param(IS_DMA2D_LINE(DMA2D_InitStruct->DMA2D_NumberOfLine));
+  assert_param(IS_DMA2D_PIXEL(DMA2D_InitStruct->DMA2D_PixelPerLine));
+
+  /* Configures the DMA2D operation mode */
+  DMA2D->CR &= (uint32_t)CR_MASK;
+  DMA2D->CR |= (DMA2D_InitStruct->DMA2D_Mode);
+
+  /* Configures the color mode of the output image */
+  DMA2D->OPFCCR &= ~(uint32_t)DMA2D_OPFCCR_CM;
+  DMA2D->OPFCCR |= (DMA2D_InitStruct->DMA2D_CMode);
+
+  /* Configures the output color */
+
+  if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_ARGB8888)
+  {
+    outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 8;
+    outred = DMA2D_InitStruct->DMA2D_OutputRed << 16;
+    outalpha = DMA2D_InitStruct->DMA2D_OutputAlpha << 24;
+  }
+  else
+  
+    if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_RGB888)
+    {
+      outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 8;
+      outred = DMA2D_InitStruct->DMA2D_OutputRed << 16;
+      outalpha = (uint32_t)0x00000000;
+    }
+     
+  else
+
+    if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_RGB565)
+    {
+      outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 5;
+      outred = DMA2D_InitStruct->DMA2D_OutputRed << 11;
+      outalpha = (uint32_t)0x00000000;
+    }
+
+  else
+
+    if (DMA2D_InitStruct->DMA2D_CMode == DMA2D_ARGB1555)
+    {  
+      outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 5;
+      outred = DMA2D_InitStruct->DMA2D_OutputRed << 10;
+      outalpha = DMA2D_InitStruct->DMA2D_OutputAlpha << 15;
+    }
+
+  else /* DMA2D_CMode = DMA2D_ARGB4444 */
+  {
+    outgreen = DMA2D_InitStruct->DMA2D_OutputGreen << 4;
+    outred = DMA2D_InitStruct->DMA2D_OutputRed << 8;
+    outalpha = DMA2D_InitStruct->DMA2D_OutputAlpha << 12;
+  }  
+  DMA2D->OCOLR |= ((outgreen) | (outred) | (DMA2D_InitStruct->DMA2D_OutputBlue) | (outalpha));
+
+  /* Configures the output memory address */
+  DMA2D->OMAR = (DMA2D_InitStruct->DMA2D_OutputMemoryAdd);
+
+  /* Configure  the line Offset */
+  DMA2D->OOR &= ~(uint32_t)DMA2D_OOR_LO;
+  DMA2D->OOR |= (DMA2D_InitStruct->DMA2D_OutputOffset);
+
+  /* Configure the number of line and pixel per line */
+  pixline = DMA2D_InitStruct->DMA2D_PixelPerLine << 16; 
+  DMA2D->NLR &= ~(DMA2D_NLR_NL | DMA2D_NLR_PL);
+  DMA2D->NLR |= ((DMA2D_InitStruct->DMA2D_NumberOfLine) | (pixline));
+
+/**
+  * @brief  Fills each DMA2D_InitStruct member with its default value.
+  * @param  DMA2D_InitStruct: pointer to a DMA2D_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+}
+void DMA2D_StructInit(DMA2D_InitTypeDef* DMA2D_InitStruct)
+{
+  /* Initialize the transfer mode member */
+  DMA2D_InitStruct->DMA2D_Mode = DMA2D_M2M;
+
+  /* Initialize the output color mode members */
+  DMA2D_InitStruct->DMA2D_CMode = DMA2D_ARGB8888;
+
+  /* Initialize the alpha and RGB values */
+  DMA2D_InitStruct->DMA2D_OutputGreen = 0x00;
+  DMA2D_InitStruct->DMA2D_OutputBlue = 0x00;
+  DMA2D_InitStruct->DMA2D_OutputRed = 0x00;
+  DMA2D_InitStruct->DMA2D_OutputAlpha = 0x00;
+
+  /* Initialize the output memory address */
+  DMA2D_InitStruct->DMA2D_OutputMemoryAdd = 0x00;
+
+  /* Initialize the output offset */
+  DMA2D_InitStruct->DMA2D_OutputOffset = 0x00;
+
+  /* Initialize the number of line and the number of pixel per line */
+  DMA2D_InitStruct->DMA2D_NumberOfLine = 0x00;
+  DMA2D_InitStruct->DMA2D_PixelPerLine = 0x00;
+}
+
+/**
+  * @brief  Start the DMA2D transfer.
+  * @param 
+  * @retval None
+  */
+
+void DMA2D_StartTransfer(void)
+{
+    /* Start DMA2D transfer by setting START bit */
+    DMA2D->CR |= (uint32_t)DMA2D_CR_START;
+}
+
+/**
+  * @brief  Aboart the DMA2D transfer.
+  * @param
+  * @retval None
+  */
+
+void DMA2D_AbortTransfer(void)
+{
+    /* Start DMA2D transfer by setting START bit */
+    DMA2D->CR |= (uint32_t)DMA2D_CR_ABORT;
+
+}
+
+/**
+  * @brief  Stop or continue the DMA2D transfer.
+  * @param  NewState: new state of the DMA2D peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void DMA2D_Suspend(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Suspend DMA2D transfer by setting STOP bit */
+    DMA2D->CR |= (uint32_t)DMA2D_CR_SUSP;
+  }
+  else
+  {
+    /* Continue DMA2D transfer by clearing STOP bit */
+    DMA2D->CR &= ~(uint32_t)DMA2D_CR_SUSP;
+  }
+}
+
+/**
+  * @brief  Configures the Foreground according to the specified parameters
+  *         in the DMA2D_FGStruct.
+  * @note   This function can be used only when the transfer is disabled.
+  * @param  DMA2D_FGStruct: pointer to a DMA2D_FGTypeDef structure that contains
+  *         the configuration information for the specified Background.
+  * @retval None
+  */
+void DMA2D_FGConfig(DMA2D_FG_InitTypeDef* DMA2D_FG_InitStruct)
+{
+
+  uint32_t fg_clutcolormode = 0;
+  uint32_t fg_clutsize = 0;
+  uint32_t fg_alpha_mode = 0;
+  uint32_t fg_alphavalue = 0;
+  uint32_t fg_colorgreen = 0;
+  uint32_t fg_colorred = 0;
+
+  assert_param(IS_DMA2D_FGO(DMA2D_FG_InitStruct->DMA2D_FGO));
+  assert_param(IS_DMA2D_FGCM(DMA2D_FG_InitStruct->DMA2D_FGCM));
+  assert_param(IS_DMA2D_FG_CLUT_CM(DMA2D_FG_InitStruct->DMA2D_FG_CLUT_CM));
+  assert_param(IS_DMA2D_FG_CLUT_SIZE(DMA2D_FG_InitStruct->DMA2D_FG_CLUT_SIZE));
+  assert_param(IS_DMA2D_FG_ALPHA_MODE(DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_MODE));
+  assert_param(IS_DMA2D_FG_ALPHA_VALUE(DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_VALUE));
+  assert_param(IS_DMA2D_FGC_BLUE(DMA2D_FG_InitStruct->DMA2D_FGC_BLUE));
+  assert_param(IS_DMA2D_FGC_GREEN(DMA2D_FG_InitStruct->DMA2D_FGC_GREEN));
+  assert_param(IS_DMA2D_FGC_RED(DMA2D_FG_InitStruct->DMA2D_FGC_RED));
+
+  /* Configures the FG memory address */
+  DMA2D->FGMAR = (DMA2D_FG_InitStruct->DMA2D_FGMA);
+
+  /* Configures the FG offset */
+  DMA2D->FGOR &= ~(uint32_t)DMA2D_FGOR_LO;
+  DMA2D->FGOR |= (DMA2D_FG_InitStruct->DMA2D_FGO);
+
+  /* Configures foreground Pixel Format Convertor */
+  DMA2D->FGPFCCR &= (uint32_t)PFCCR_MASK;
+  fg_clutcolormode = DMA2D_FG_InitStruct->DMA2D_FG_CLUT_CM << 4;
+  fg_clutsize = DMA2D_FG_InitStruct->DMA2D_FG_CLUT_SIZE << 8;
+  fg_alpha_mode = DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_MODE << 16;
+  fg_alphavalue = DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_VALUE << 24;
+  DMA2D->FGPFCCR |= (DMA2D_FG_InitStruct->DMA2D_FGCM | fg_clutcolormode | fg_clutsize | \
+                    fg_alpha_mode | fg_alphavalue);
+
+  /* Configures foreground color */
+  DMA2D->FGCOLR &= ~(DMA2D_FGCOLR_BLUE | DMA2D_FGCOLR_GREEN | DMA2D_FGCOLR_RED);
+  fg_colorgreen = DMA2D_FG_InitStruct->DMA2D_FGC_GREEN << 8;
+  fg_colorred = DMA2D_FG_InitStruct->DMA2D_FGC_RED << 16;
+  DMA2D->FGCOLR |= (DMA2D_FG_InitStruct->DMA2D_FGC_BLUE | fg_colorgreen | fg_colorred);
+
+  /* Configures foreground CLUT memory address */
+  DMA2D->FGCMAR = DMA2D_FG_InitStruct->DMA2D_FGCMAR;
+}
+
+/**
+  * @brief  Fills each DMA2D_FGStruct member with its default value.
+  * @param  DMA2D_FGStruct: pointer to a DMA2D_FGTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void DMA2D_FG_StructInit(DMA2D_FG_InitTypeDef* DMA2D_FG_InitStruct)
+{
+  /*!< Initialize the DMA2D foreground memory address */
+  DMA2D_FG_InitStruct->DMA2D_FGMA = 0x00;
+
+  /*!< Initialize the DMA2D foreground offset */
+  DMA2D_FG_InitStruct->DMA2D_FGO = 0x00;
+
+  /*!< Initialize the DMA2D foreground color mode */
+  DMA2D_FG_InitStruct->DMA2D_FGCM = CM_ARGB8888;
+
+  /*!< Initialize the DMA2D foreground CLUT color mode */
+  DMA2D_FG_InitStruct->DMA2D_FG_CLUT_CM = CLUT_CM_ARGB8888;
+
+  /*!< Initialize the DMA2D foreground CLUT size */
+  DMA2D_FG_InitStruct->DMA2D_FG_CLUT_SIZE = 0x00;
+
+  /*!< Initialize the DMA2D foreground alpha mode */
+  DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_MODE = NO_MODIF_ALPHA_VALUE;
+
+  /*!< Initialize the DMA2D foreground alpha value */
+  DMA2D_FG_InitStruct->DMA2D_FGPFC_ALPHA_VALUE = 0x00;
+
+  /*!< Initialize the DMA2D foreground blue value */
+  DMA2D_FG_InitStruct->DMA2D_FGC_BLUE = 0x00;
+
+  /*!< Initialize the DMA2D foreground green value */
+  DMA2D_FG_InitStruct->DMA2D_FGC_GREEN = 0x00;
+
+  /*!< Initialize the DMA2D foreground red value */
+  DMA2D_FG_InitStruct->DMA2D_FGC_RED = 0x00;
+
+  /*!< Initialize the DMA2D foreground CLUT memory address */
+  DMA2D_FG_InitStruct->DMA2D_FGCMAR = 0x00;
+}
+
+
+/**
+  * @brief  Configures the Background according to the specified parameters
+  *         in the DMA2D_BGStruct.
+  * @note   This function can be used only when the transfer is disabled.
+  * @param  DMA2D_BGStruct: pointer to a DMA2D_BGTypeDef structure that contains
+  *         the configuration information for the specified Background.
+  * @retval None
+  */
+void DMA2D_BGConfig(DMA2D_BG_InitTypeDef* DMA2D_BG_InitStruct)
+{
+
+  uint32_t bg_clutcolormode = 0;
+  uint32_t bg_clutsize = 0;
+  uint32_t bg_alpha_mode = 0;
+  uint32_t bg_alphavalue = 0;
+  uint32_t bg_colorgreen = 0;
+  uint32_t bg_colorred = 0;
+
+  assert_param(IS_DMA2D_BGO(DMA2D_BG_InitStruct->DMA2D_BGO));
+  assert_param(IS_DMA2D_BGCM(DMA2D_BG_InitStruct->DMA2D_BGCM));
+  assert_param(IS_DMA2D_BG_CLUT_CM(DMA2D_BG_InitStruct->DMA2D_BG_CLUT_CM));
+  assert_param(IS_DMA2D_BG_CLUT_SIZE(DMA2D_BG_InitStruct->DMA2D_BG_CLUT_SIZE));
+  assert_param(IS_DMA2D_BG_ALPHA_MODE(DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_MODE));
+  assert_param(IS_DMA2D_BG_ALPHA_VALUE(DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_VALUE));
+  assert_param(IS_DMA2D_BGC_BLUE(DMA2D_BG_InitStruct->DMA2D_BGC_BLUE));
+  assert_param(IS_DMA2D_BGC_GREEN(DMA2D_BG_InitStruct->DMA2D_BGC_GREEN));
+  assert_param(IS_DMA2D_BGC_RED(DMA2D_BG_InitStruct->DMA2D_BGC_RED));
+
+  /* Configures the BG memory address */
+  DMA2D->BGMAR = (DMA2D_BG_InitStruct->DMA2D_BGMA);
+
+  /* Configures the BG offset */
+  DMA2D->BGOR &= ~(uint32_t)DMA2D_BGOR_LO;
+  DMA2D->BGOR |= (DMA2D_BG_InitStruct->DMA2D_BGO);
+
+  /* Configures background Pixel Format Convertor */
+  DMA2D->BGPFCCR &= (uint32_t)PFCCR_MASK;
+  bg_clutcolormode = DMA2D_BG_InitStruct->DMA2D_BG_CLUT_CM << 4;
+  bg_clutsize = DMA2D_BG_InitStruct->DMA2D_BG_CLUT_SIZE << 8;
+  bg_alpha_mode = DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_MODE << 16;
+  bg_alphavalue = DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_VALUE << 24;
+  DMA2D->BGPFCCR |= (DMA2D_BG_InitStruct->DMA2D_BGCM | bg_clutcolormode | bg_clutsize | \
+                    bg_alpha_mode | bg_alphavalue);
+
+  /* Configures background color */
+  DMA2D->BGCOLR &= ~(DMA2D_BGCOLR_BLUE | DMA2D_BGCOLR_GREEN | DMA2D_BGCOLR_RED);
+  bg_colorgreen = DMA2D_BG_InitStruct->DMA2D_BGC_GREEN << 8;
+  bg_colorred = DMA2D_BG_InitStruct->DMA2D_BGC_RED << 16;
+  DMA2D->BGCOLR |= (DMA2D_BG_InitStruct->DMA2D_BGC_BLUE | bg_colorgreen | bg_colorred);
+  
+  /* Configures background CLUT memory address */
+  DMA2D->BGCMAR = DMA2D_BG_InitStruct->DMA2D_BGCMAR;
+
+}
+
+/**
+  * @brief  Fills each DMA2D_BGStruct member with its default value.
+  * @param  DMA2D_BGStruct: pointer to a DMA2D_BGTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void DMA2D_BG_StructInit(DMA2D_BG_InitTypeDef* DMA2D_BG_InitStruct)
+{
+  /*!< Initialize the DMA2D background memory address */
+  DMA2D_BG_InitStruct->DMA2D_BGMA = 0x00;
+
+  /*!< Initialize the DMA2D background offset */
+  DMA2D_BG_InitStruct->DMA2D_BGO = 0x00;
+
+  /*!< Initialize the DMA2D background color mode */
+  DMA2D_BG_InitStruct->DMA2D_BGCM = CM_ARGB8888;
+
+  /*!< Initialize the DMA2D background CLUT color mode */
+  DMA2D_BG_InitStruct->DMA2D_BG_CLUT_CM = CLUT_CM_ARGB8888;
+
+  /*!< Initialize the DMA2D background CLUT size */
+  DMA2D_BG_InitStruct->DMA2D_BG_CLUT_SIZE = 0x00;
+
+  /*!< Initialize the DMA2D background alpha mode */
+  DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_MODE = NO_MODIF_ALPHA_VALUE;
+
+  /*!< Initialize the DMA2D background alpha value */
+  DMA2D_BG_InitStruct->DMA2D_BGPFC_ALPHA_VALUE = 0x00;
+
+  /*!< Initialize the DMA2D background blue value */
+  DMA2D_BG_InitStruct->DMA2D_BGC_BLUE = 0x00;
+
+  /*!< Initialize the DMA2D background green value */
+  DMA2D_BG_InitStruct->DMA2D_BGC_GREEN = 0x00;
+
+  /*!< Initialize the DMA2D background red value */
+  DMA2D_BG_InitStruct->DMA2D_BGC_RED = 0x00;
+
+  /*!< Initialize the DMA2D background CLUT memory address */
+  DMA2D_BG_InitStruct->DMA2D_BGCMAR = 0x00;
+}
+
+/**
+  * @brief  Start the automatic loading of the CLUT or abort the transfer.
+  * @param  NewState: new state of the DMA2D peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+
+void DMA2D_FGStart(FunctionalState NewState) 
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Start the automatic loading of the CLUT */
+    DMA2D->FGPFCCR |= DMA2D_FGPFCCR_START;
+  }
+  else
+  {
+    /* abort the transfer */
+    DMA2D->FGPFCCR &= (uint32_t)~DMA2D_FGPFCCR_START;
+  }
+}
+
+/**
+  * @brief  Start the automatic loading of the CLUT or abort the transfer.
+  * @param  NewState: new state of the DMA2D peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+  
+void DMA2D_BGStart(FunctionalState NewState) 
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Start the automatic loading of the CLUT */
+    DMA2D->BGPFCCR |= DMA2D_BGPFCCR_START;
+  }
+  else
+  {
+    /* abort the transfer */
+    DMA2D->BGPFCCR &= (uint32_t)~DMA2D_BGPFCCR_START;
+  }
+}
+
+/**
+  * @brief  Configures the DMA2D dead time.
+  * @param  DMA2D_DeadTime: specifies the DMA2D dead time.
+  *   This parameter can be one of the following values:
+  * @retval None
+  */
+void DMA2D_DeadTimeConfig(uint32_t DMA2D_DeadTime, FunctionalState NewState)
+{
+   uint32_t DeadTime;
+
+  /* Check the parameters */
+  assert_param(IS_DMA2D_DEAD_TIME(DMA2D_DeadTime));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable and Configures the dead time */
+    DMA2D->AMTCR &= (uint32_t)DEAD_MASK;
+    DeadTime = DMA2D_DeadTime << 8;
+    DMA2D->AMTCR |= (DeadTime | DMA2D_AMTCR_EN);
+  }
+  else
+  {
+     DMA2D->AMTCR &= ~(uint32_t)DMA2D_AMTCR_EN;
+  }
+}
+
+/**
+  * @brief  Define the configuration of the line watermark .
+  * @param  DMA2D_LWatermarkConfig: Line Watermark configuration.
+  * @retval None
+  */
+
+void DMA2D_LineWatermarkConfig(uint32_t DMA2D_LWatermarkConfig)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA2D_LineWatermark(DMA2D_LWatermarkConfig));
+
+  /* Sets the Line watermark configuration */
+  DMA2D->LWR = (uint32_t)DMA2D_LWatermarkConfig;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup DMA2D_Group2 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim
+ ===============================================================================
+            ##### Interrupts and flags management functions #####
+ ===============================================================================
+
+    [..] This section provides functions allowing to configure the DMA2D 
+         Interrupts and to get the status and clear flags and Interrupts 
+         pending bits.
+    [..] The DMA2D provides 6 Interrupts sources and 6 Flags
+    
+    *** Flags ***
+    =============
+    [..]
+      (+) DMA2D_FLAG_CE : Configuration Error Interrupt flag
+      (+) DMA2D_FLAG_CAE: CLUT Access Error Interrupt flag
+      (+) DMA2D_FLAG_TW:  Transfer Watermark Interrupt flag
+      (+) DMA2D_FLAG_TC:  Transfer Complete interrupt flag
+      (+) DMA2D_FLAG_TE:  Transfer Error interrupt flag
+      (+) DMA2D_FLAG_CTC: CLUT Transfer Complete Interrupt flag
+      
+    *** Interrupts ***
+    ==================
+    [..]
+      (+) DMA2D_IT_CE: Configuration Error Interrupt is generated when a wrong 
+                       configuration is detected
+      (+) DMA2D_IT_CAE: CLUT Access Error Interrupt
+      (+) DMA2D_IT_TW: Transfer Watermark Interrupt is generated when 
+                       the programmed watermark is reached 
+      (+) DMA2D_IT_TE: Transfer Error interrupt is generated when the CPU trying 
+                       to access the CLUT while a CLUT loading or a DMA2D1 transfer 
+                       is on going       
+      (+) DMA2D_IT_CTC: CLUT Transfer Complete Interrupt 
+      (+) DMA2D_IT_TC: Transfer Complete interrupt         
+@endverbatim
+  * @{
+  */
+/**
+  * @brief  Enables or disables the specified DMA2D's interrupts.
+  * @param  DMA2D_IT: specifies the DMA2D interrupts sources to be enabled or disabled.
+  *   This parameter can be any combination of the following values:
+  *     @arg DMA2D_IT_CE:   Configuration Error Interrupt Enable.
+  *     @arg DMA2D_IT_CTC:  CLUT Transfer Complete Interrupt Enable.
+  *     @arg DMA2D_IT_CAE:  CLUT Access Error Interrupt Enable.
+  *     @arg DMA2D_IT_TW:   Transfer Watermark Interrupt Enable.
+  *     @arg DMA2D_IT_TC:   Transfer Complete interrupt enable.
+  *     @arg DMA2D_IT_TE:   Transfer Error interrupt enable.
+  * @param NewState: new state of the specified DMA2D interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+
+void DMA2D_ITConfig(uint32_t DMA2D_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA2D_IT(DMA2D_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected DMA2D interrupts */
+    DMA2D->CR |= DMA2D_IT;
+  }
+  else
+  {
+    /* Disable the selected DMA2D interrupts */
+    DMA2D->CR &= (uint32_t)~DMA2D_IT;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified DMA2D's flag is set or not.
+  * @param  DMA2D_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg DMA2D_FLAG_CE:   Configuration Error Interrupt flag.
+  *     @arg DMA2D_FLAG_CTC:  CLUT Transfer Complete Interrupt flag.
+  *     @arg DMA2D_FLAG_CAE:  CLUT Access Error Interrupt flag.
+  *     @arg DMA2D_FLAG_TW:   Transfer Watermark Interrupt flag.
+  *     @arg DMA2D_FLAG_TC:   Transfer Complete interrupt flag.
+  *     @arg DMA2D_FLAG_TE:   Transfer Error interrupt flag.
+  * @retval The new state of DMA2D_FLAG (SET or RESET).
+  */
+
+FlagStatus DMA2D_GetFlagStatus(uint32_t DMA2D_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_DMA2D_GET_FLAG(DMA2D_FLAG));
+  
+  /* Check the status of the specified DMA2D flag */
+  if (((DMA2D->ISR) & DMA2D_FLAG) != (uint32_t)RESET)
+  {
+    /* DMA2D_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* DMA2D_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the DMA2D_FLAG status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the DMA2D's pending flags.
+  * @param  DMA2D_FLAG: specifies the flag to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg DMA2D_FLAG_CE:   Configuration Error Interrupt flag.
+  *     @arg DMA2D_FLAG_CTC:  CLUT Transfer Complete Interrupt flag.
+  *     @arg DMA2D_FLAG_CAE:  CLUT Access Error Interrupt flag.
+  *     @arg DMA2D_FLAG_TW:   Transfer Watermark Interrupt flag.
+  *     @arg DMA2D_FLAG_TC:   Transfer Complete interrupt flag.
+  *     @arg DMA2D_FLAG_TE:   Transfer Error interrupt flag.
+  * @retval None
+  */
+void DMA2D_ClearFlag(uint32_t DMA2D_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA2D_GET_FLAG(DMA2D_FLAG));
+    
+  /* Clear the corresponding DMA2D flag */
+  DMA2D->IFCR = (uint32_t)DMA2D_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified DMA2D's interrupt has occurred or not.
+  * @param  DMA2D_IT: specifies the DMA2D interrupts sources to check.
+  *   This parameter can be one of the following values:
+  *     @arg DMA2D_IT_CE:   Configuration Error Interrupt Enable.
+  *     @arg DMA2D_IT_CTC:  CLUT Transfer Complete Interrupt Enable.
+  *     @arg DMA2D_IT_CAE:  CLUT Access Error Interrupt Enable.
+  *     @arg DMA2D_IT_TW:   Transfer Watermark Interrupt Enable.
+  *     @arg DMA2D_IT_TC:   Transfer Complete interrupt enable.
+  *     @arg DMA2D_IT_TE:   Transfer Error interrupt enable.
+  * @retval The new state of the DMA2D_IT (SET or RESET).
+  */
+ITStatus DMA2D_GetITStatus(uint32_t DMA2D_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t DMA2D_IT_FLAG = DMA2D_IT >> 8;
+  
+  /* Check the parameters */
+  assert_param(IS_DMA2D_IT(DMA2D_IT));
+
+  if ((DMA2D->ISR & DMA2D_IT_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  
+  if (((DMA2D->CR & DMA2D_IT) != (uint32_t)RESET) && (bitstatus != (uint32_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the DMA2D's interrupt pending bits.
+  * @param  DMA2D_IT: specifies the interrupt pending bit to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg DMA2D_IT_CE:   Configuration Error Interrupt.
+  *     @arg DMA2D_IT_CTC:  CLUT Transfer Complete Interrupt.
+  *     @arg DMA2D_IT_CAE:  CLUT Access Error Interrupt.
+  *     @arg DMA2D_IT_TW:   Transfer Watermark Interrupt.
+  *     @arg DMA2D_IT_TC:   Transfer Complete interrupt.
+  *     @arg DMA2D_IT_TE:   Transfer Error interrupt.
+  * @retval None
+  */
+void DMA2D_ClearITPendingBit(uint32_t DMA2D_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_DMA2D_IT(DMA2D_IT));
+  DMA2D_IT = DMA2D_IT >> 8;
+    
+  /* Clear the corresponding DMA2D Interrupt */
+  DMA2D->IFCR = (uint32_t)DMA2D_IT;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c
new file mode 100644
index 0000000000000000000000000000000000000000..4eb676417ebf74948ec312e7b307890fb0848794
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_exti.c
@@ -0,0 +1,312 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_exti.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the EXTI peripheral:           
+  *           + Initialization and Configuration
+  *           + Interrupts and flags management
+  *
+@verbatim  
+
+ ===================================================================
+                       ##### EXTI features #####
+ ===================================================================
+
+ [..] External interrupt/event lines are mapped as following:
+   (#) All available GPIO pins are connected to the 16 external 
+       interrupt/event lines from EXTI0 to EXTI15.
+   (#) EXTI line 16 is connected to the PVD Output
+   (#) EXTI line 17 is connected to the RTC Alarm event
+   (#) EXTI line 18 is connected to the USB OTG FS Wakeup from suspend event                                    
+   (#) EXTI line 19 is connected to the Ethernet Wakeup event
+   (#) EXTI line 20 is connected to the USB OTG HS (configured in FS) Wakeup event 
+   (#) EXTI line 21 is connected to the RTC Tamper and Time Stamp events                                               
+   (#) EXTI line 22 is connected to the RTC Wakeup event
+          
+          
+                ##### How to use this driver #####
+ ===================================================================  
+ 
+ [..] In order to use an I/O pin as an external interrupt source, follow steps 
+      below:
+   (#) Configure the I/O in input mode using GPIO_Init()
+   (#) Select the input source pin for the EXTI line using SYSCFG_EXTILineConfig()
+   (#) Select the mode(interrupt, event) and configure the trigger 
+       selection (Rising, falling or both) using EXTI_Init()
+   (#) Configure NVIC IRQ channel mapped to the EXTI line using NVIC_Init()
+
+ [..]     
+   (@) SYSCFG APB clock must be enabled to get write access to SYSCFG_EXTICRx
+       registers using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
+            
+@endverbatim                  
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_exti.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup EXTI 
+  * @brief EXTI driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+#define EXTI_LINENONE    ((uint32_t)0x00000)  /* No interrupt selected */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup EXTI_Private_Functions
+  * @{
+  */
+
+/** @defgroup EXTI_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+             ##### Initialization and Configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the EXTI peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void EXTI_DeInit(void)
+{
+  EXTI->IMR = 0x00000000;
+  EXTI->EMR = 0x00000000;
+  EXTI->RTSR = 0x00000000;
+  EXTI->FTSR = 0x00000000;
+  EXTI->PR = 0x007FFFFF;
+}
+
+/**
+  * @brief  Initializes the EXTI peripheral according to the specified
+  *         parameters in the EXTI_InitStruct.
+  * @param  EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure
+  *         that contains the configuration information for the EXTI peripheral.
+  * @retval None
+  */
+void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+  uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode));
+  assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger));
+  assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line));  
+  assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd));
+
+  tmp = (uint32_t)EXTI_BASE;
+     
+  if (EXTI_InitStruct->EXTI_LineCmd != DISABLE)
+  {
+    /* Clear EXTI line configuration */
+    EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line;
+    EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line;
+    
+    tmp += EXTI_InitStruct->EXTI_Mode;
+
+    *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
+
+    /* Clear Rising Falling edge configuration */
+    EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line;
+    EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line;
+    
+    /* Select the trigger for the selected external interrupts */
+    if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling)
+    {
+      /* Rising Falling edge */
+      EXTI->RTSR |= EXTI_InitStruct->EXTI_Line;
+      EXTI->FTSR |= EXTI_InitStruct->EXTI_Line;
+    }
+    else
+    {
+      tmp = (uint32_t)EXTI_BASE;
+      tmp += EXTI_InitStruct->EXTI_Trigger;
+
+      *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line;
+    }
+  }
+  else
+  {
+    tmp += EXTI_InitStruct->EXTI_Mode;
+
+    /* Disable the selected external lines */
+    *(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line;
+  }
+}
+
+/**
+  * @brief  Fills each EXTI_InitStruct member with its reset value.
+  * @param  EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct)
+{
+  EXTI_InitStruct->EXTI_Line = EXTI_LINENONE;
+  EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt;
+  EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling;
+  EXTI_InitStruct->EXTI_LineCmd = DISABLE;
+}
+
+/**
+  * @brief  Generates a Software interrupt on selected EXTI line.
+  * @param  EXTI_Line: specifies the EXTI line on which the software interrupt
+  *         will be generated.
+  *         This parameter can be any combination of EXTI_Linex where x can be (0..22)
+  * @retval None
+  */
+void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line)
+{
+  /* Check the parameters */
+  assert_param(IS_EXTI_LINE(EXTI_Line));
+  
+  EXTI->SWIER |= EXTI_Line;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup EXTI_Group2 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions 
+ *
+@verbatim   
+ ===============================================================================
+             ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Checks whether the specified EXTI line flag is set or not.
+  * @param  EXTI_Line: specifies the EXTI line flag to check.
+  *          This parameter can be EXTI_Linex where x can be(0..22)
+  * @retval The new state of EXTI_Line (SET or RESET).
+  */
+FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+  
+  if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the EXTI's line pending flags.
+  * @param  EXTI_Line: specifies the EXTI lines flags to clear.
+  *          This parameter can be any combination of EXTI_Linex where x can be (0..22)
+  * @retval None
+  */
+void EXTI_ClearFlag(uint32_t EXTI_Line)
+{
+  /* Check the parameters */
+  assert_param(IS_EXTI_LINE(EXTI_Line));
+  
+  EXTI->PR = EXTI_Line;
+}
+
+/**
+  * @brief  Checks whether the specified EXTI line is asserted or not.
+  * @param  EXTI_Line: specifies the EXTI line to check.
+  *          This parameter can be EXTI_Linex where x can be(0..22)
+  * @retval The new state of EXTI_Line (SET or RESET).
+  */
+ITStatus EXTI_GetITStatus(uint32_t EXTI_Line)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_GET_EXTI_LINE(EXTI_Line));
+  
+  if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+  
+}
+
+/**
+  * @brief  Clears the EXTI's line pending bits.
+  * @param  EXTI_Line: specifies the EXTI lines to clear.
+  *          This parameter can be any combination of EXTI_Linex where x can be (0..22)
+  * @retval None
+  */
+void EXTI_ClearITPendingBit(uint32_t EXTI_Line)
+{
+  /* Check the parameters */
+  assert_param(IS_EXTI_LINE(EXTI_Line));
+  
+  EXTI->PR = EXTI_Line;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c
new file mode 100644
index 0000000000000000000000000000000000000000..f3551b116e79dd9119720e8f5b35927802620ae2
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_flash.c
@@ -0,0 +1,1580 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_flash.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the FLASH peripheral:
+  *            + FLASH Interface configuration
+  *            + FLASH Memory Programming
+  *            + Option Bytes Programming
+  *            + Interrupts and flags management
+  *  
+ @verbatim    
+ ===============================================================================
+                        ##### How to use this driver #####
+ ===============================================================================
+    [..]                             
+      This driver provides functions to configure and program the FLASH memory 
+      of all STM32F4xx devices. These functions are split in 4 groups:
+   
+      (#) FLASH Interface configuration functions: this group includes the
+          management of the following features:
+        (++) Set the latency
+        (++) Enable/Disable the prefetch buffer
+        (++) Enable/Disable the Instruction cache and the Data cache
+        (++) Reset the Instruction cache and the Data cache
+    
+      (#) FLASH Memory Programming functions: this group includes all needed
+          functions to erase and program the main memory:
+        (++) Lock and Unlock the FLASH interface
+        (++) Erase function: Erase sector, erase all sectors
+        (++) Program functions: byte, half word, word and double word
+    
+      (#) Option Bytes Programming functions: this group includes all needed
+          functions to manage the Option Bytes:
+        (++) Set/Reset the write protection
+        (++) Set the Read protection Level
+        (++) Set the BOR level
+        (++) Program the user Option Bytes
+        (++) Launch the Option Bytes loader
+    
+      (#) Interrupts and flags management functions: this group 
+          includes all needed functions to:
+        (++) Enable/Disable the FLASH interrupt sources
+        (++) Get flags status
+        (++) Clear flags
+        (++) Get FLASH operation status
+        (++) Wait for last FLASH operation   
+ @endverbatim                      
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_flash.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup FLASH 
+  * @brief FLASH driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/ 
+#define SECTOR_MASK               ((uint32_t)0xFFFFFF07)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup FLASH_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup FLASH_Group1 FLASH Interface configuration functions
+  *  @brief   FLASH Interface configuration functions 
+ *
+
+@verbatim   
+ ===============================================================================
+              ##### FLASH Interface configuration functions #####
+ ===============================================================================
+    [..]
+      This group includes the following functions:
+      (+) void FLASH_SetLatency(uint32_t FLASH_Latency)
+          To correctly read data from FLASH memory, the number of wait states (LATENCY) 
+          must be correctly programmed according to the frequency of the CPU clock 
+          (HCLK) and the supply voltage of the device.
+    [..]      
+      For STM32F405xx/07xx and STM32F415xx/17xx devices
+ +-------------------------------------------------------------------------------------+     
+ | Latency       |                HCLK clock frequency (MHz)                           |
+ |               |---------------------------------------------------------------------|     
+ |               | voltage range  | voltage range  | voltage range   | voltage range   |
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   |
+ |---------------|----------------|----------------|-----------------|-----------------|              
+ |0WS(1CPU cycle)|0 < HCLK <= 30  |0 < HCLK <= 24  |0 < HCLK <= 22   |0 < HCLK <= 20   |
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44  |20 < HCLK <= 40  | 
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |44 < HCLK <= 66  |40 < HCLK <= 60  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |66 < HCLK <= 88  |60 < HCLK <= 80  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|88 < HCLK <= 110 |80 < HCLK <= 100 |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |5WS(6CPU cycle)|150< HCLK <= 168|120< HCLK <= 144|110 < HCLK <= 132|100 < HCLK <= 120| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |6WS(7CPU cycle)|      NA        |144< HCLK <= 168|132 < HCLK <= 154|120 < HCLK <= 140| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |7WS(8CPU cycle)|      NA        |      NA        |154 < HCLK <= 168|140 < HCLK <= 160|
+ +---------------|----------------|----------------|-----------------|-----------------+ 
+
+    [..]      
+      For STM32F42xxx/43xxx devices
+ +-------------------------------------------------------------------------------------+     
+ | Latency       |                HCLK clock frequency (MHz)                           |
+ |               |---------------------------------------------------------------------|     
+ |               | voltage range  | voltage range  | voltage range   | voltage range   |
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   |
+ |---------------|----------------|----------------|-----------------|-----------------|              
+ |0WS(1CPU cycle)|0 < HCLK <= 30  |0 < HCLK <= 24  |0 < HCLK <= 22   |0 < HCLK <= 20   |
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44  |20 < HCLK <= 40  | 
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |44 < HCLK <= 66  |40 < HCLK <= 60  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |66 < HCLK <= 88  |60 < HCLK <= 80  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|88 < HCLK <= 110 |80 < HCLK <= 100 |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |5WS(6CPU cycle)|120< HCLK <= 180|120< HCLK <= 144|110 < HCLK <= 132|100 < HCLK <= 120| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |6WS(7CPU cycle)|      NA        |144< HCLK <= 168|132 < HCLK <= 154|120 < HCLK <= 140| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |7WS(8CPU cycle)|      NA        |168< HCLK <= 180|154 < HCLK <= 176|140 < HCLK <= 160|
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |8WS(9CPU cycle)|      NA        |      NA        |176 < HCLK <= 180|160 < HCLK <= 168|
+ +-------------------------------------------------------------------------------------+
+   
+    [..]
+    For STM32F401x devices
+ +-------------------------------------------------------------------------------------+     
+ | Latency       |                HCLK clock frequency (MHz)                           |
+ |               |---------------------------------------------------------------------|     
+ |               | voltage range  | voltage range  | voltage range   | voltage range   |
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   |
+ |---------------|----------------|----------------|-----------------|-----------------|              
+ |0WS(1CPU cycle)|0 < HCLK <= 30  |0 < HCLK <= 24  |0 < HCLK <= 22   |0 < HCLK <= 20   |
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44  |20 < HCLK <= 40  | 
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |2WS(3CPU cycle)|60 < HCLK <= 84 |48 < HCLK <= 72 |44 < HCLK <= 66  |40 < HCLK <= 60  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |3WS(4CPU cycle)|      NA        |72 < HCLK <= 84 |66 < HCLK <= 84  |60 < HCLK <= 80  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |4WS(5CPU cycle)|      NA        |      NA        |      NA         |80 < HCLK <= 84  | 
+ +-------------------------------------------------------------------------------------+ 
+ 
+ [..]
+ +-------------------------------------------------------------------------------------------------------------------+
+ |               | voltage range  | voltage range  | voltage range   | voltage range   | voltage range 2.7 V - 3.6 V |
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   | with External Vpp = 9V      |
+ |---------------|----------------|----------------|-----------------|-----------------|-----------------------------| 
+ |Max Parallelism|      x32       |               x16                |       x8        |          x64                |              
+ |---------------|----------------|----------------|-----------------|-----------------|-----------------------------|   
+ |PSIZE[1:0]     |      10        |               01                 |       00        |           11                |
+ +-------------------------------------------------------------------------------------------------------------------+  
+
+      -@- On STM32F405xx/407xx and STM32F415xx/417xx devices: 
+           (++) when VOS = '0' Scale 2 mode, the maximum value of fHCLK = 144MHz. 
+           (++) when VOS = '1' Scale 1 mode, the maximum value of fHCLK = 168MHz. 
+          [..] 
+          On STM32F42xxx/43xxx devices:
+           (++) when VOS[1:0] = '0x01' Scale 3 mode, the maximum value of fHCLK is 120MHz.
+           (++) when VOS[1:0] = '0x10' Scale 2 mode, the maximum value of fHCLK is 144MHz if OverDrive OFF and 168MHz if OverDrive ON.
+           (++) when VOS[1:0] = '0x11' Scale 1 mode, the maximum value of fHCLK is 168MHz if OverDrive OFF and 180MHz if OverDrive ON. 
+          [..]  
+          On STM32F401x devices:
+           (++) when VOS[1:0] = '0x01' Scale 3 mode, the maximum value of fHCLK is 60MHz.
+           (++) when VOS[1:0] = '0x10' Scale 2 mode, the maximum value of fHCLK is 84MHz.
+           For more details please refer product DataSheet 
+           You can use PWR_MainRegulatorModeConfig() function to control VOS bits.
+                 
+      (+) void FLASH_PrefetchBufferCmd(FunctionalState NewState)
+      (+) void FLASH_InstructionCacheCmd(FunctionalState NewState)
+      (+) void FLASH_DataCacheCmd(FunctionalState NewState)
+      (+) void FLASH_InstructionCacheReset(void)
+      (+) void FLASH_DataCacheReset(void)
+      
+    [..]   
+      The unlock sequence is not needed for these functions.
+ 
+@endverbatim
+  * @{
+  */
+ 
+/**
+  * @brief  Sets the code latency value.  
+  * @param  FLASH_Latency: specifies the FLASH Latency value.
+  *          This parameter can be one of the following values:
+  *            @arg FLASH_Latency_0: FLASH Zero Latency cycle
+  *            @arg FLASH_Latency_1: FLASH One Latency cycle
+  *            @arg FLASH_Latency_2: FLASH Two Latency cycles
+  *            @arg FLASH_Latency_3: FLASH Three Latency cycles
+  *            @arg FLASH_Latency_4: FLASH Four Latency cycles 
+  *            @arg FLASH_Latency_5: FLASH Five Latency cycles 
+  *            @arg FLASH_Latency_6: FLASH Six Latency cycles
+  *            @arg FLASH_Latency_7: FLASH Seven Latency cycles 
+  *            @arg FLASH_Latency_8: FLASH Eight Latency cycles
+  *            @arg FLASH_Latency_9: FLASH Nine Latency cycles
+  *            @arg FLASH_Latency_10: FLASH Teen Latency cycles 
+  *            @arg FLASH_Latency_11: FLASH Eleven Latency cycles 
+  *            @arg FLASH_Latency_12: FLASH Twelve Latency cycles
+  *            @arg FLASH_Latency_13: FLASH Thirteen Latency cycles        
+  *            @arg FLASH_Latency_14: FLASH Fourteen Latency cycles
+  *            @arg FLASH_Latency_15: FLASH Fifteen Latency cycles 
+  *              
+  * @note For STM32F405xx/407xx, STM32F415xx/417xx and STM32F401xx devices this parameter    
+  *       can be a value between FLASH_Latency_0 and FLASH_Latency_7.
+  *         
+  * @note For STM32F42xxx/43xxx devices this parameter can be a value between 
+  *       FLASH_Latency_0 and FLASH_Latency_15. 
+  *         
+  * @retval None
+  */
+void FLASH_SetLatency(uint32_t FLASH_Latency)
+{
+  /* Check the parameters */
+  assert_param(IS_FLASH_LATENCY(FLASH_Latency));
+  
+  /* Perform Byte access to FLASH_ACR[8:0] to set the Latency value */
+  *(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)FLASH_Latency;
+}
+
+/**
+  * @brief  Enables or disables the Prefetch Buffer.
+  * @param  NewState: new state of the Prefetch Buffer.
+  *          This parameter  can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FLASH_PrefetchBufferCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  /* Enable or disable the Prefetch Buffer */
+  if(NewState != DISABLE)
+  {
+    FLASH->ACR |= FLASH_ACR_PRFTEN;
+  }
+  else
+  {
+    FLASH->ACR &= (~FLASH_ACR_PRFTEN);
+  }
+}
+
+/**
+  * @brief  Enables or disables the Instruction Cache feature.
+  * @param  NewState: new state of the Instruction Cache.
+  *          This parameter  can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FLASH_InstructionCacheCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if(NewState != DISABLE)
+  {
+    FLASH->ACR |= FLASH_ACR_ICEN;
+  }
+  else
+  {
+    FLASH->ACR &= (~FLASH_ACR_ICEN);
+  }
+}
+
+/**
+  * @brief  Enables or disables the Data Cache feature.
+  * @param  NewState: new state of the Data Cache.
+  *          This parameter  can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FLASH_DataCacheCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if(NewState != DISABLE)
+  {
+    FLASH->ACR |= FLASH_ACR_DCEN;
+  }
+  else
+  {
+    FLASH->ACR &= (~FLASH_ACR_DCEN);
+  }
+}
+
+/**
+  * @brief  Resets the Instruction Cache.
+  * @note   This function must be used only when the Instruction Cache is disabled.  
+  * @param  None
+  * @retval None
+  */
+void FLASH_InstructionCacheReset(void)
+{
+  FLASH->ACR |= FLASH_ACR_ICRST;
+}
+
+/**
+  * @brief  Resets the Data Cache.
+  * @note   This function must be used only when the Data Cache is disabled.  
+  * @param  None
+  * @retval None
+  */
+void FLASH_DataCacheReset(void)
+{
+  FLASH->ACR |= FLASH_ACR_DCRST;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Group2 FLASH Memory Programming functions
+ *  @brief   FLASH Memory Programming functions
+ *
+@verbatim   
+ ===============================================================================
+                ##### FLASH Memory Programming functions #####
+ ===============================================================================   
+    [..]
+      This group includes the following functions:
+      (+) void FLASH_Unlock(void)
+      (+) void FLASH_Lock(void)
+      (+) FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange)
+      (+) FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange)       
+      (+) FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data)
+      (+) FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data)
+      (+) FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data)
+      (+) FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data)
+          The following functions can be used only for STM32F42xxx/43xxx devices. 
+      (+) FLASH_Status FLASH_EraseAllBank1Sectors(uint8_t VoltageRange)
+      (+) FLASH_Status FLASH_EraseAllBank2Sectors(uint8_t VoltageRange)    
+    [..]   
+      Any operation of erase or program should follow these steps:
+      (#) Call the FLASH_Unlock() function to enable the FLASH control register access
+
+      (#) Call the desired function to erase sector(s) or program data
+
+      (#) Call the FLASH_Lock() function to disable the FLASH control register access
+          (recommended to protect the FLASH memory against possible unwanted operation)
+    
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Unlocks the FLASH control register access
+  * @param  None
+  * @retval None
+  */
+void FLASH_Unlock(void)
+{
+  if((FLASH->CR & FLASH_CR_LOCK) != RESET)
+  {
+    /* Authorize the FLASH Registers access */
+    FLASH->KEYR = FLASH_KEY1;
+    FLASH->KEYR = FLASH_KEY2;
+  }  
+}
+
+/**
+  * @brief  Locks the FLASH control register access
+  * @param  None
+  * @retval None
+  */
+void FLASH_Lock(void)
+{
+  /* Set the LOCK Bit to lock the FLASH Registers access */
+  FLASH->CR |= FLASH_CR_LOCK;
+}
+
+/**
+  * @brief  Erases a specified FLASH Sector.
+  *
+  * @note   If an erase and a program operations are requested simustaneously,    
+  *         the erase operation is performed before the program one.
+  *   
+  * @param  FLASH_Sector: The Sector number to be erased.
+  *
+  *  @note  For STM32F405xx/407xx and STM32F415xx/417xx devices this parameter can 
+  *         be a value between FLASH_Sector_0 and FLASH_Sector_11.
+  *           
+  *         For STM32F42xxx/43xxx devices this parameter can be a value between 
+  *         FLASH_Sector_0 and FLASH_Sector_23.
+  *           
+  *         For STM32F401xx devices this parameter can be a value between 
+  *         FLASH_Sector_0 and FLASH_Sector_5.             
+  *    
+  * @param  VoltageRange: The device voltage range which defines the erase parallelism.  
+  *          This parameter can be one of the following values:
+  *            @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V, 
+  *                                  the operation will be done by byte (8-bit) 
+  *            @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+  *                                  the operation will be done by half word (16-bit)
+  *            @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+  *                                  the operation will be done by word (32-bit)
+  *            @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp, 
+  *                                  the operation will be done by double word (64-bit)
+  *       
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_EraseSector(uint32_t FLASH_Sector, uint8_t VoltageRange)
+{
+  uint32_t tmp_psize = 0x0;
+  FLASH_Status status = FLASH_COMPLETE;
+
+  /* Check the parameters */
+  assert_param(IS_FLASH_SECTOR(FLASH_Sector));
+  assert_param(IS_VOLTAGERANGE(VoltageRange));
+  
+  if(VoltageRange == VoltageRange_1)
+  {
+     tmp_psize = FLASH_PSIZE_BYTE;
+  }
+  else if(VoltageRange == VoltageRange_2)
+  {
+    tmp_psize = FLASH_PSIZE_HALF_WORD;
+  }
+  else if(VoltageRange == VoltageRange_3)
+  {
+    tmp_psize = FLASH_PSIZE_WORD;
+  }
+  else
+  {
+    tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+  }
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  
+  if(status == FLASH_COMPLETE)
+  { 
+    /* if the previous operation is completed, proceed to erase the sector */
+    FLASH->CR &= CR_PSIZE_MASK;
+    FLASH->CR |= tmp_psize;
+    FLASH->CR &= SECTOR_MASK;
+    FLASH->CR |= FLASH_CR_SER | FLASH_Sector;
+    FLASH->CR |= FLASH_CR_STRT;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+    
+    /* if the erase operation is completed, disable the SER Bit */
+    FLASH->CR &= (~FLASH_CR_SER);
+    FLASH->CR &= SECTOR_MASK; 
+  }
+  /* Return the Erase Status */
+  return status;
+}
+
+/**
+  * @brief  Erases all FLASH Sectors.
+  *
+  * @note   If an erase and a program operations are requested simustaneously,    
+  *         the erase operation is performed before the program one.
+  *  
+  * @param  VoltageRange: The device voltage range which defines the erase parallelism.  
+  *          This parameter can be one of the following values:
+  *            @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V, 
+  *                                  the operation will be done by byte (8-bit) 
+  *            @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+  *                                  the operation will be done by half word (16-bit)
+  *            @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+  *                                  the operation will be done by word (32-bit)
+  *            @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp, 
+  *                                  the operation will be done by double word (64-bit)
+  *       
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_EraseAllSectors(uint8_t VoltageRange)
+{
+  uint32_t tmp_psize = 0x0;
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  assert_param(IS_VOLTAGERANGE(VoltageRange));
+  
+  if(VoltageRange == VoltageRange_1)
+  {
+     tmp_psize = FLASH_PSIZE_BYTE;
+  }
+  else if(VoltageRange == VoltageRange_2)
+  {
+    tmp_psize = FLASH_PSIZE_HALF_WORD;
+  }
+  else if(VoltageRange == VoltageRange_3)
+  {
+    tmp_psize = FLASH_PSIZE_WORD;
+  }
+  else
+  {
+    tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+  }  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to erase all sectors */
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)    
+    FLASH->CR &= CR_PSIZE_MASK;
+    FLASH->CR |= tmp_psize;
+    FLASH->CR |= (FLASH_CR_MER1 | FLASH_CR_MER2);
+    FLASH->CR |= FLASH_CR_STRT;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the erase operation is completed, disable the MER Bit */
+    FLASH->CR &= ~(FLASH_CR_MER1 | FLASH_CR_MER2);
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#if defined (STM32F40_41xxx) || defined (STM32F401xx) 
+    FLASH->CR &= CR_PSIZE_MASK;
+    FLASH->CR |= tmp_psize;
+    FLASH->CR |= FLASH_CR_MER;
+    FLASH->CR |= FLASH_CR_STRT;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the erase operation is completed, disable the MER Bit */
+    FLASH->CR &= (~FLASH_CR_MER);
+#endif /* STM32F40_41xxx || STM32F401xx */
+
+  }   
+  /* Return the Erase Status */
+  return status;
+}
+
+/**
+  * @brief  Erases all FLASH Sectors in Bank 1.
+  *
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *      
+  * @note   If an erase and a program operations are requested simultaneously,    
+  *         the erase operation is performed before the program one. 
+  *  
+  * @param  VoltageRange: The device voltage range which defines the erase parallelism.  
+  *          This parameter can be one of the following values:
+  *            @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V, 
+  *                                  the operation will be done by byte (8-bit) 
+  *            @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+  *                                  the operation will be done by half word (16-bit)
+  *            @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+  *                                  the operation will be done by word (32-bit)
+  *            @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp, 
+  *                                  the operation will be done by double word (64-bit)
+  *       
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_EraseAllBank1Sectors(uint8_t VoltageRange)
+{
+  uint32_t tmp_psize = 0x0;
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  assert_param(IS_VOLTAGERANGE(VoltageRange));
+  
+  if(VoltageRange == VoltageRange_1)
+  {
+     tmp_psize = FLASH_PSIZE_BYTE;
+  }
+  else if(VoltageRange == VoltageRange_2)
+  {
+    tmp_psize = FLASH_PSIZE_HALF_WORD;
+  }
+  else if(VoltageRange == VoltageRange_3)
+  {
+    tmp_psize = FLASH_PSIZE_WORD;
+  }
+  else
+  {
+    tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+  }  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to erase all sectors */
+     FLASH->CR &= CR_PSIZE_MASK;
+     FLASH->CR |= tmp_psize;
+     FLASH->CR |= FLASH_CR_MER1;
+     FLASH->CR |= FLASH_CR_STRT;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the erase operation is completed, disable the MER Bit */
+    FLASH->CR &= (~FLASH_CR_MER1);
+
+  }   
+  /* Return the Erase Status */
+  return status;
+}
+
+
+/**
+  * @brief  Erases all FLASH Sectors in Bank 2.
+  *
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *     
+  * @note   If an erase and a program operations are requested simultaneously,    
+  *         the erase operation is performed before the program one.
+  *     
+  * @param  VoltageRange: The device voltage range which defines the erase parallelism.  
+  *          This parameter can be one of the following values:
+  *            @arg VoltageRange_1: when the device voltage range is 1.8V to 2.1V, 
+  *                                  the operation will be done by byte (8-bit) 
+  *            @arg VoltageRange_2: when the device voltage range is 2.1V to 2.7V,
+  *                                  the operation will be done by half word (16-bit)
+  *            @arg VoltageRange_3: when the device voltage range is 2.7V to 3.6V,
+  *                                  the operation will be done by word (32-bit)
+  *            @arg VoltageRange_4: when the device voltage range is 2.7V to 3.6V + External Vpp, 
+  *                                  the operation will be done by double word (64-bit)
+  *       
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_EraseAllBank2Sectors(uint8_t VoltageRange)
+{
+  uint32_t tmp_psize = 0x0;
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  assert_param(IS_VOLTAGERANGE(VoltageRange));
+  
+  if(VoltageRange == VoltageRange_1)
+  {
+     tmp_psize = FLASH_PSIZE_BYTE;
+  }
+  else if(VoltageRange == VoltageRange_2)
+  {
+    tmp_psize = FLASH_PSIZE_HALF_WORD;
+  }
+  else if(VoltageRange == VoltageRange_3)
+  {
+    tmp_psize = FLASH_PSIZE_WORD;
+  }
+  else
+  {
+    tmp_psize = FLASH_PSIZE_DOUBLE_WORD;
+  }  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to erase all sectors */
+     FLASH->CR &= CR_PSIZE_MASK;
+     FLASH->CR |= tmp_psize;
+     FLASH->CR |= FLASH_CR_MER2;
+     FLASH->CR |= FLASH_CR_STRT;
+    
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the erase operation is completed, disable the MER Bit */
+    FLASH->CR &= (~FLASH_CR_MER2);
+
+  }   
+  /* Return the Erase Status */
+  return status;
+}
+
+/**
+  * @brief  Programs a double word (64-bit) at a specified address.
+  * @note   This function must be used when the device voltage range is from
+  *         2.7V to 3.6V and an External Vpp is present.
+  *
+  * @note   If an erase and a program operations are requested simustaneously,    
+  *         the erase operation is performed before the program one.
+  *  
+  * @param  Address: specifies the address to be programmed.
+  * @param  Data: specifies the data to be programmed.
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_ProgramDoubleWord(uint32_t Address, uint64_t Data)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+
+  /* Check the parameters */
+  assert_param(IS_FLASH_ADDRESS(Address));
+
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to program the new data */
+    FLASH->CR &= CR_PSIZE_MASK;
+    FLASH->CR |= FLASH_PSIZE_DOUBLE_WORD;
+    FLASH->CR |= FLASH_CR_PG;
+  
+    *(__IO uint64_t*)Address = Data;
+        
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the program operation is completed, disable the PG Bit */
+    FLASH->CR &= (~FLASH_CR_PG);
+  } 
+  /* Return the Program Status */
+  return status;
+}
+
+/**
+  * @brief  Programs a word (32-bit) at a specified address.
+  *
+  * @note   This function must be used when the device voltage range is from 2.7V to 3.6V. 
+  *
+  * @note   If an erase and a program operations are requested simustaneously,    
+  *         the erase operation is performed before the program one.
+  *  
+  * @param  Address: specifies the address to be programmed.
+  *         This parameter can be any address in Program memory zone or in OTP zone.  
+  * @param  Data: specifies the data to be programmed.
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+
+  /* Check the parameters */
+  assert_param(IS_FLASH_ADDRESS(Address));
+
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to program the new data */
+    FLASH->CR &= CR_PSIZE_MASK;
+    FLASH->CR |= FLASH_PSIZE_WORD;
+    FLASH->CR |= FLASH_CR_PG;
+  
+    *(__IO uint32_t*)Address = Data;
+        
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the program operation is completed, disable the PG Bit */
+    FLASH->CR &= (~FLASH_CR_PG);
+  } 
+  /* Return the Program Status */
+  return status;
+}
+
+/**
+  * @brief  Programs a half word (16-bit) at a specified address. 
+  * @note   This function must be used when the device voltage range is from 2.1V to 3.6V. 
+  *
+  * @note   If an erase and a program operations are requested simustaneously,    
+  *         the erase operation is performed before the program one.
+  * 
+  * @param  Address: specifies the address to be programmed.
+  *         This parameter can be any address in Program memory zone or in OTP zone.  
+  * @param  Data: specifies the data to be programmed.
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+
+  /* Check the parameters */
+  assert_param(IS_FLASH_ADDRESS(Address));
+
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to program the new data */
+    FLASH->CR &= CR_PSIZE_MASK;
+    FLASH->CR |= FLASH_PSIZE_HALF_WORD;
+    FLASH->CR |= FLASH_CR_PG;
+  
+    *(__IO uint16_t*)Address = Data;
+        
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the program operation is completed, disable the PG Bit */
+    FLASH->CR &= (~FLASH_CR_PG);
+  } 
+  /* Return the Program Status */
+  return status;
+}
+
+/**
+  * @brief  Programs a byte (8-bit) at a specified address.
+  * @note   This function can be used within all the device supply voltage ranges.  
+  *
+  * @note   If an erase and a program operations are requested simustaneously,    
+  *         the erase operation is performed before the program one.
+  * 
+  * @param  Address: specifies the address to be programmed.
+  *         This parameter can be any address in Program memory zone or in OTP zone.  
+  * @param  Data: specifies the data to be programmed.
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_ProgramByte(uint32_t Address, uint8_t Data)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+
+  /* Check the parameters */
+  assert_param(IS_FLASH_ADDRESS(Address));
+
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  
+  if(status == FLASH_COMPLETE)
+  {
+    /* if the previous operation is completed, proceed to program the new data */
+    FLASH->CR &= CR_PSIZE_MASK;
+    FLASH->CR |= FLASH_PSIZE_BYTE;
+    FLASH->CR |= FLASH_CR_PG;
+  
+    *(__IO uint8_t*)Address = Data;
+        
+    /* Wait for last operation to be completed */
+    status = FLASH_WaitForLastOperation();
+
+    /* if the program operation is completed, disable the PG Bit */
+    FLASH->CR &= (~FLASH_CR_PG);
+  } 
+
+  /* Return the Program Status */
+  return status;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Group3 Option Bytes Programming functions
+ *  @brief   Option Bytes Programming functions 
+ *
+@verbatim   
+ ===============================================================================
+                ##### Option Bytes Programming functions #####
+ ===============================================================================  
+    [..]
+      This group includes the following functions:
+      (+) void FLASH_OB_Unlock(void)
+      (+) void FLASH_OB_Lock(void)
+      (+) void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
+      (+) void FLASH_OB_WRP1Config(uint32_t OB_WRP, FunctionalState NewState)  
+      (+) void FLASH_OB_PCROPSelectionConfig(uint8_t OB_PCROPSelect)
+      (+) void FLASH_OB_PCROPConfig(uint32_t OB_PCROP, FunctionalState NewState)
+      (+) void FLASH_OB_PCROP1Config(uint32_t OB_PCROP, FunctionalState NewState) 
+      (+) void FLASH_OB_RDPConfig(uint8_t OB_RDP)
+      (+) void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY)
+      (+) void FLASH_OB_BORConfig(uint8_t OB_BOR)
+      (+) FLASH_Status FLASH_ProgramOTP(uint32_t Address, uint32_t Data)							
+      (+) FLASH_Status FLASH_OB_Launch(void)
+      (+) uint32_t FLASH_OB_GetUser(void)						
+      (+) uint8_t FLASH_OB_GetWRP(void)
+      (+) uint8_t FLASH_OB_GetWRP1(void)
+      (+) uint8_t FLASH_OB_GetPCROP(void)
+      (+) uint8_t FLASH_OB_GetPCROP1(void)    						
+      (+) uint8_t FLASH_OB_GetRDP(void)							
+      (+) uint8_t FLASH_OB_GetBOR(void)
+    [..]  
+      The following function can be used only for STM32F42xxx/43xxx devices. 
+      (+) void FLASH_OB_BootConfig(uint8_t OB_BOOT)
+    [..]   
+     Any operation of erase or program should follow these steps:
+      (#) Call the FLASH_OB_Unlock() function to enable the FLASH option control 
+          register access
+
+      (#) Call one or several functions to program the desired Option Bytes:
+        (++) void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState) 
+             => to Enable/Disable the desired sector write protection
+        (++) void FLASH_OB_RDPConfig(uint8_t OB_RDP) => to set the desired read 
+             Protection Level
+        (++) void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY) 
+             => to configure the user Option Bytes.
+        (++) void FLASH_OB_BORConfig(uint8_t OB_BOR) => to set the BOR Level 			 
+
+      (#) Once all needed Option Bytes to be programmed are correctly written, 
+          call the FLASH_OB_Launch() function to launch the Option Bytes 
+          programming process.
+     
+      -@- When changing the IWDG mode from HW to SW or from SW to HW, a system 
+          reset is needed to make the change effective.  
+
+      (#) Call the FLASH_OB_Lock() function to disable the FLASH option control 
+          register access (recommended to protect the Option Bytes against 
+          possible unwanted operations)
+    
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Unlocks the FLASH Option Control Registers access.
+  * @param  None
+  * @retval None
+  */
+void FLASH_OB_Unlock(void)
+{
+  if((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != RESET)
+  {
+    /* Authorizes the Option Byte register programming */
+    FLASH->OPTKEYR = FLASH_OPT_KEY1;
+    FLASH->OPTKEYR = FLASH_OPT_KEY2;
+  }  
+}
+
+/**
+  * @brief  Locks the FLASH Option Control Registers access.
+  * @param  None
+  * @retval None
+  */
+void FLASH_OB_Lock(void)
+{
+  /* Set the OPTLOCK Bit to lock the FLASH Option Byte Registers access */
+  FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK;
+}
+
+/**
+  * @brief  Enables or disables the write protection of the desired sectors, for the first
+  *         1 Mb of the Flash  
+  *
+  * @note   When the memory read protection level is selected (RDP level = 1), 
+  *         it is not possible to program or erase the flash sector i if CortexM4  
+  *         debug features are connected or boot code is executed in RAM, even if nWRPi = 1 
+  * @note   Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1).   
+  * 
+  * @param  OB_WRP: specifies the sector(s) to be write protected or unprotected.
+  *          This parameter can be one of the following values:
+  *            @arg OB_WRP: A value between OB_WRP_Sector0 and OB_WRP_Sector11                      
+  *            @arg OB_WRP_Sector_All
+  * @param  Newstate: new state of the Write Protection.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None  
+  */
+void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
+{ 
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Check the parameters */
+  assert_param(IS_OB_WRP(OB_WRP));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  status = FLASH_WaitForLastOperation();
+
+  if(status == FLASH_COMPLETE)
+  { 
+    if(NewState != DISABLE)
+    {
+      *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS &= (~OB_WRP);
+    }
+    else
+    {
+      *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS |= (uint16_t)OB_WRP;
+    }
+  }
+}
+
+/**
+  * @brief  Enables or disables the write protection of the desired sectors, for the second
+  *         1 Mb of the Flash  
+  *           
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *   
+  * @note   When the memory read out protection is selected (RDP level = 1), 
+  *         it is not possible to program or erase the flash sector i if CortexM4  
+  *         debug features are connected or boot code is executed in RAM, even if nWRPi = 1 
+  * @note   Active value of nWRPi bits is inverted when PCROP mode is active (SPRMOD =1).      
+  * 
+  * @param  OB_WRP: specifies the sector(s) to be write protected or unprotected.
+  *          This parameter can be one of the following values:
+  *            @arg OB_WRP: A value between OB_WRP_Sector12 and OB_WRP_Sector23
+  *            @arg OB_WRP_Sector_All                        
+  * @param  Newstate: new state of the Write Protection.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None  
+  */
+void FLASH_OB_WRP1Config(uint32_t OB_WRP, FunctionalState NewState)
+{ 
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Check the parameters */
+  assert_param(IS_OB_WRP(OB_WRP));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  status = FLASH_WaitForLastOperation();
+
+  if(status == FLASH_COMPLETE)
+  { 
+    if(NewState != DISABLE)
+    {
+      *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS &= (~OB_WRP);
+    }
+    else
+    {
+      *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS |= (uint16_t)OB_WRP;
+    }
+  }
+}
+
+/**
+  * @brief  Select the Protection Mode (SPRMOD). 
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx and STM32F401xx devices.       
+  * 
+  * @note   After PCROP activation, Option Byte modification is not possible. 
+  *         Exception made for the global Read Out Protection modification level (level1 to level0) 
+  * @note   Once SPRMOD bit is active unprotection of a protected sector is not possible 
+  *   
+  * @note   Read a protected sector will set RDERR Flag and write a protected sector will set WRPERR Flag
+  *   
+  * @note   Some Precautions should be taken when activating the PCROP feature :
+  *         The active value of nWRPi bits is inverted when PCROP mode is active, this means if SPRMOD = 1
+  *         and WRPi = 1 (default value), then the user sector i is read/write protected.
+  *         In order to avoid activation of PCROP Mode for undesired sectors, please follow the
+  *         below safety sequence :       
+  *         - Disable PCROP for all Sectors using FLASH_OB_PCROPConfig(OB_PCROP_Sector_All, DISABLE) function 
+  *           for Bank1 or FLASH_OB_PCROP1Config(OB_PCROP_Sector_All, DISABLE) function for Bank2   
+  *         - Enable PCROP for the desired Sector i using FLASH_OB_PCROPConfig(Sector i, ENABLE) function
+  *         - Activate the PCROP Mode FLASH_OB_PCROPSelectionConfig() function. 
+  * 
+  * @param  OB_PCROP:  Select the Protection Mode of nWPRi bits 
+  *          This parameter can be one of the following values:
+  *            @arg OB_PcROP_Disable: nWRPi control the write protection of respective user sectors.
+  *            @arg OB_PcROP_Enable: nWRPi control the  read&write protection (PCROP) of respective user sectors.
+  * @retval None
+  */
+void FLASH_OB_PCROPSelectionConfig(uint8_t OB_PcROP)
+{  
+  uint8_t optiontmp = 0xFF;
+      
+  /* Check the parameters */
+  assert_param(IS_OB_PCROP_SELECT(OB_PcROP));
+  
+  /* Mask SPRMOD bit */
+  optiontmp =  (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE3_ADDRESS) & (uint8_t)0x7F); 
+  /* Update Option Byte */
+  *(__IO uint8_t *)OPTCR_BYTE3_ADDRESS = (uint8_t)(OB_PcROP | optiontmp); 
+    
+}
+
+/**
+  * @brief  Enables or disables the read/write protection (PCROP) of the desired 
+  *         sectors, for the first 1 MB of the Flash.
+  *           
+  * @note   This function can be used only for STM32F42xxx/43xxx and STM32F401xx devices. 
+  *   
+  * @param  OB_PCROP: specifies the sector(s) to be read/write protected or unprotected.
+  *          This parameter can be one of the following values:
+  *            @arg OB_PCROP: A value between OB_PCROP_Sector0 and OB_PCROP_Sector11 for 
+  *                           STM32F42xxx/43xxx devices and between OB_PCROP_Sector0 and 
+  *                           OB_PCROP_Sector5 for STM32F401xx devices.
+  *            @arg OB_PCROP_Sector_All                         
+  * @param  Newstate: new state of the Write Protection.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None  
+  */
+void FLASH_OB_PCROPConfig(uint32_t OB_PCROP, FunctionalState NewState)
+{ 
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Check the parameters */
+  assert_param(IS_OB_PCROP(OB_PCROP));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  status = FLASH_WaitForLastOperation();
+
+  if(status == FLASH_COMPLETE)
+  { 
+    if(NewState != DISABLE)
+    {
+      *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS |= (uint16_t)OB_PCROP;    
+    }
+    else
+    {
+      *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS &= (~OB_PCROP);
+    }
+  }
+}
+
+/**
+   * @brief Enables or disables the read/write protection (PCROP) of the desired 
+  *         sectors
+  *           
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *   
+  * @param  OB_PCROP: specifies the sector(s) to be read/write protected or unprotected.
+  *          This parameter can be one of the following values:
+  *            @arg OB_PCROP: A value between OB_PCROP_Sector12 and OB_PCROP_Sector23 
+  *            @arg OB_PCROP_Sector_All                    
+  * @param  Newstate: new state of the Write Protection.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None  
+  */
+void FLASH_OB_PCROP1Config(uint32_t OB_PCROP, FunctionalState NewState)
+{ 
+  FLASH_Status status = FLASH_COMPLETE;
+  
+  /* Check the parameters */
+  assert_param(IS_OB_PCROP(OB_PCROP));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  status = FLASH_WaitForLastOperation();
+
+  if(status == FLASH_COMPLETE)
+  { 
+    if(NewState != DISABLE)
+    {
+      *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS |= (uint16_t)OB_PCROP;
+    }
+    else
+    {
+      *(__IO uint16_t*)OPTCR1_BYTE2_ADDRESS &= (~OB_PCROP);
+    }
+  }
+}
+
+
+/**
+  * @brief  Sets the read protection level.
+  * @param  OB_RDP: specifies the read protection level.
+  *          This parameter can be one of the following values:
+  *            @arg OB_RDP_Level_0: No protection
+  *            @arg OB_RDP_Level_1: Read protection of the memory
+  *            @arg OB_RDP_Level_2: Full chip protection
+  *   
+  * /!\ Warning /!\ When enabling OB_RDP level 2 it's no more possible to go back to level 1 or 0
+  *    
+  * @retval None
+  */
+void FLASH_OB_RDPConfig(uint8_t OB_RDP)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+
+  /* Check the parameters */
+  assert_param(IS_OB_RDP(OB_RDP));
+
+  status = FLASH_WaitForLastOperation();
+
+  if(status == FLASH_COMPLETE)
+  {
+    *(__IO uint8_t*)OPTCR_BYTE1_ADDRESS = OB_RDP;
+
+  }
+}
+
+/**
+  * @brief  Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY.    
+  * @param  OB_IWDG: Selects the IWDG mode
+  *          This parameter can be one of the following values:
+  *            @arg OB_IWDG_SW: Software IWDG selected
+  *            @arg OB_IWDG_HW: Hardware IWDG selected
+  * @param  OB_STOP: Reset event when entering STOP mode.
+  *          This parameter  can be one of the following values:
+  *            @arg OB_STOP_NoRST: No reset generated when entering in STOP
+  *            @arg OB_STOP_RST: Reset generated when entering in STOP
+  * @param  OB_STDBY: Reset event when entering Standby mode.
+  *          This parameter  can be one of the following values:
+  *            @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY
+  *            @arg OB_STDBY_RST: Reset generated when entering in STANDBY
+  * @retval None
+  */
+void FLASH_OB_UserConfig(uint8_t OB_IWDG, uint8_t OB_STOP, uint8_t OB_STDBY)
+{
+  uint8_t optiontmp = 0xFF;
+  FLASH_Status status = FLASH_COMPLETE; 
+
+  /* Check the parameters */
+  assert_param(IS_OB_IWDG_SOURCE(OB_IWDG));
+  assert_param(IS_OB_STOP_SOURCE(OB_STOP));
+  assert_param(IS_OB_STDBY_SOURCE(OB_STDBY));
+
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+  
+  if(status == FLASH_COMPLETE)
+  { 
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)     
+    /* Mask OPTLOCK, OPTSTRT, BOR_LEV and BFB2 bits */
+    optiontmp =  (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x1F);
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#if defined (STM32F40_41xxx) || defined (STM32F401xx) 
+    /* Mask OPTLOCK, OPTSTRT and BOR_LEV bits */
+    optiontmp =  (uint8_t)((*(__IO uint8_t *)OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0F); 
+#endif /* STM32F40_41xxx || STM32F401xx */ 
+
+    /* Update User Option Byte */
+    *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS = OB_IWDG | (uint8_t)(OB_STDBY | (uint8_t)(OB_STOP | ((uint8_t)optiontmp))); 
+  }  
+}
+
+/**
+  * @brief  Configure the Dual Bank Boot.
+  *   
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *      
+  * @param  OB_BOOT: specifies the Dual Bank Boot Option byte.
+  *          This parameter can be one of the following values:
+  *            @arg OB_Dual_BootEnabled: Dual Bank Boot Enable
+  *            @arg OB_Dual_BootDisabled: Dual Bank Boot Disabled
+  * @retval None
+  */
+void FLASH_OB_BootConfig(uint8_t OB_BOOT)
+{
+  /* Check the parameters */
+  assert_param(IS_OB_BOOT(OB_BOOT));
+
+  /* Set Dual Bank Boot */
+  *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BFB2);
+  *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= OB_BOOT;
+
+}
+
+/**
+  * @brief  Sets the BOR Level. 
+  * @param  OB_BOR: specifies the Option Bytes BOR Reset Level.
+  *          This parameter can be one of the following values:
+  *            @arg OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V
+  *            @arg OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V
+  *            @arg OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V
+  *            @arg OB_BOR_OFF: Supply voltage ranges from 1.62 to 2.1 V
+  * @retval None
+  */
+void FLASH_OB_BORConfig(uint8_t OB_BOR)
+{
+  /* Check the parameters */
+  assert_param(IS_OB_BOR(OB_BOR));
+
+  /* Set the BOR Level */
+  *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS &= (~FLASH_OPTCR_BOR_LEV);
+  *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= OB_BOR;
+
+}
+
+/**
+  * @brief  Launch the option byte loading.
+  * @param  None
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_OB_Launch(void)
+{
+  FLASH_Status status = FLASH_COMPLETE;
+
+  /* Set the OPTSTRT bit in OPTCR register */
+  *(__IO uint8_t *)OPTCR_BYTE0_ADDRESS |= FLASH_OPTCR_OPTSTRT;
+
+  /* Wait for last operation to be completed */
+  status = FLASH_WaitForLastOperation();
+
+  return status;
+}
+
+/**
+  * @brief  Returns the FLASH User Option Bytes values.
+  * @param  None
+  * @retval The FLASH User Option Bytes values: IWDG_SW(Bit0), RST_STOP(Bit1)
+  *         and RST_STDBY(Bit2).
+  */
+uint8_t FLASH_OB_GetUser(void)
+{
+  /* Return the User Option Byte */
+  return (uint8_t)(FLASH->OPTCR >> 5);
+}
+
+/**
+  * @brief  Returns the FLASH Write Protection Option Bytes value.
+  * @param  None
+  * @retval The FLASH Write Protection  Option Bytes value
+  */
+uint16_t FLASH_OB_GetWRP(void)
+{
+  /* Return the FLASH write protection Register value */
+  return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS));
+}
+
+/**
+  * @brief  Returns the FLASH Write Protection Option Bytes value.
+  *   
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *   
+  * @param  None
+  * @retval The FLASH Write Protection  Option Bytes value
+  */
+uint16_t FLASH_OB_GetWRP1(void)
+{
+  /* Return the FLASH write protection Register value */
+  return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS));
+}
+
+/**
+  * @brief  Returns the FLASH PC Read/Write Protection Option Bytes value.
+  *   
+  * @note   This function can be used only for STM32F42xxx/43xxx devices and STM32F401xx devices.
+  *   
+  * @param  None
+  * @retval The FLASH PC Read/Write Protection Option Bytes value
+  */
+uint16_t FLASH_OB_GetPCROP(void)
+{
+  /* Return the FLASH PC Read/write protection Register value */
+  return (*(__IO uint16_t *)(OPTCR_BYTE2_ADDRESS));
+}
+
+/**
+  * @brief  Returns the FLASH PC Read/Write Protection Option Bytes value.
+  *   
+  * @note   This function can be used only for STM32F42xxx/43xxx devices. 
+  *     
+  * @param  None
+  * @retval The FLASH PC Read/Write Protection Option Bytes value
+  */
+uint16_t FLASH_OB_GetPCROP1(void)
+{
+  /* Return the FLASH write protection Register value */
+  return (*(__IO uint16_t *)(OPTCR1_BYTE2_ADDRESS));
+}
+
+/**
+  * @brief  Returns the FLASH Read Protection level.
+  * @param  None
+  * @retval FLASH ReadOut Protection Status:
+  *           - SET, when OB_RDP_Level_1 or OB_RDP_Level_2 is set
+  *           - RESET, when OB_RDP_Level_0 is set
+  */
+FlagStatus FLASH_OB_GetRDP(void)
+{
+  FlagStatus readstatus = RESET;
+
+  if ((*(__IO uint8_t*)(OPTCR_BYTE1_ADDRESS) != (uint8_t)OB_RDP_Level_0))
+  {
+    readstatus = SET;
+  }
+  else
+  {
+    readstatus = RESET;
+  }
+  return readstatus;
+}
+
+/**
+  * @brief  Returns the FLASH BOR level.
+  * @param  None
+  * @retval The FLASH BOR level:
+  *           - OB_BOR_LEVEL3: Supply voltage ranges from 2.7 to 3.6 V
+  *           - OB_BOR_LEVEL2: Supply voltage ranges from 2.4 to 2.7 V
+  *           - OB_BOR_LEVEL1: Supply voltage ranges from 2.1 to 2.4 V
+  *           - OB_BOR_OFF   : Supply voltage ranges from 1.62 to 2.1 V  
+  */
+uint8_t FLASH_OB_GetBOR(void)
+{
+  /* Return the FLASH BOR level */
+  return (uint8_t)(*(__IO uint8_t *)(OPTCR_BYTE0_ADDRESS) & (uint8_t)0x0C);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup FLASH_Group4 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+              ##### Interrupts and flags management functions #####
+ ===============================================================================  
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified FLASH interrupts.
+  * @param  FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled.
+  *          This parameter can be any combination of the following values:
+  *            @arg FLASH_IT_ERR: FLASH Error Interrupt
+  *            @arg FLASH_IT_EOP: FLASH end of operation Interrupt
+  * @retval None 
+  */
+void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FLASH_IT(FLASH_IT)); 
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if(NewState != DISABLE)
+  {
+    /* Enable the interrupt sources */
+    FLASH->CR |= FLASH_IT;
+  }
+  else
+  {
+    /* Disable the interrupt sources */
+    FLASH->CR &= ~(uint32_t)FLASH_IT;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified FLASH flag is set or not.
+  * @param  FLASH_FLAG: specifies the FLASH flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg FLASH_FLAG_EOP: FLASH End of Operation flag 
+  *            @arg FLASH_FLAG_OPERR: FLASH operation Error flag 
+  *            @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag 
+  *            @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag
+  *            @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
+  *            @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag
+  *            @arg FLASH_FLAG_RDERR: FLASH (PCROP) Read Protection error flag (STM32F42/43xxx and STM32F401xx devices) 
+  *            @arg FLASH_FLAG_BSY: FLASH Busy flag
+  * @retval The new state of FLASH_FLAG (SET or RESET).
+  */
+FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG));
+
+  if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the new state of FLASH_FLAG (SET or RESET) */
+  return bitstatus; 
+}
+
+/**
+  * @brief  Clears the FLASH's pending flags.
+  * @param  FLASH_FLAG: specifies the FLASH flags to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg FLASH_FLAG_EOP: FLASH End of Operation flag 
+  *            @arg FLASH_FLAG_OPERR: FLASH operation Error flag 
+  *            @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag 
+  *            @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag 
+  *            @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag
+  *            @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag
+  *            @arg FLASH_FLAG_RDERR: FLASH Read Protection error flag (STM32F42/43xxx and STM32F401xx devices)   
+  * @retval None
+  */
+void FLASH_ClearFlag(uint32_t FLASH_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG));
+  
+  /* Clear the flags */
+  FLASH->SR = FLASH_FLAG;
+}
+
+/**
+  * @brief  Returns the FLASH Status.
+  * @param  None
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_RD, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_GetStatus(void)
+{
+  FLASH_Status flashstatus = FLASH_COMPLETE;
+  
+  if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) 
+  {
+    flashstatus = FLASH_BUSY;
+  }
+  else 
+  {  
+    if((FLASH->SR & FLASH_FLAG_WRPERR) != (uint32_t)0x00)
+    { 
+      flashstatus = FLASH_ERROR_WRP;
+    }
+    else
+    {
+      if((FLASH->SR & FLASH_FLAG_RDERR) != (uint32_t)0x00)
+      { 
+        flashstatus = FLASH_ERROR_RD;
+      } 
+      else 
+      {
+        if((FLASH->SR & (uint32_t)0xEF) != (uint32_t)0x00)
+        {
+          flashstatus = FLASH_ERROR_PROGRAM; 
+        }
+        else
+        {
+          if((FLASH->SR & FLASH_FLAG_OPERR) != (uint32_t)0x00)
+          {
+            flashstatus = FLASH_ERROR_OPERATION;
+          }
+          else
+          {
+            flashstatus = FLASH_COMPLETE;
+          }
+        }
+      }
+    }
+  }
+  /* Return the FLASH Status */
+  return flashstatus;
+}
+
+/**
+  * @brief  Waits for a FLASH operation to complete.
+  * @param  None
+  * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PROGRAM,
+  *                       FLASH_ERROR_WRP, FLASH_ERROR_OPERATION or FLASH_COMPLETE.
+  */
+FLASH_Status FLASH_WaitForLastOperation(void)
+{ 
+  __IO FLASH_Status status = FLASH_COMPLETE;
+   
+  /* Check for the FLASH Status */
+  status = FLASH_GetStatus();
+
+  /* Wait for the FLASH operation to complete by polling on BUSY flag to be reset.
+     Even if the FLASH operation fails, the BUSY flag will be reset and an error
+     flag will be set */
+  while(status == FLASH_BUSY)
+  {
+    status = FLASH_GetStatus();
+  }
+  /* Return the operation status */
+  return status;
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmc.c
new file mode 100644
index 0000000000000000000000000000000000000000..865419a76073ff36378779538eb92b17b3d2adea
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fmc.c
@@ -0,0 +1,1373 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_fmc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the FMC peripheral:           
+  *           + Interface with SRAM, PSRAM, NOR and OneNAND memories
+  *           + Interface with NAND memories
+  *           + Interface with 16-bit PC Card compatible memories 
+  *           + Interface with SDRAM memories    
+  *           + Interrupts and flags management   
+  *           
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_fmc.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup FMC 
+  * @brief FMC driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* --------------------- FMC registers bit mask ---------------------------- */
+/* FMC BCRx Mask */
+#define BCR_MBKEN_SET              ((uint32_t)0x00000001)
+#define BCR_MBKEN_RESET            ((uint32_t)0x000FFFFE)
+#define BCR_FACCEN_SET             ((uint32_t)0x00000040)
+
+/* FMC PCRx Mask */
+#define PCR_PBKEN_SET              ((uint32_t)0x00000004)
+#define PCR_PBKEN_RESET            ((uint32_t)0x000FFFFB)
+#define PCR_ECCEN_SET              ((uint32_t)0x00000040)
+#define PCR_ECCEN_RESET            ((uint32_t)0x000FFFBF)
+#define PCR_MEMORYTYPE_NAND        ((uint32_t)0x00000008)
+
+/* FMC SDCRx write protection Mask*/
+#define SDCR_WriteProtection_RESET ((uint32_t)0x00007DFF) 
+
+/* FMC SDCMR Mask*/
+#define SDCMR_CTB1_RESET           ((uint32_t)0x003FFFEF)
+#define SDCMR_CTB2_RESET           ((uint32_t)0x003FFFF7)
+#define SDCMR_CTB1_2_RESET         ((uint32_t)0x003FFFE7)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup FMC_Private_Functions
+  * @{
+  */
+
+/** @defgroup FMC_Group1 NOR/SRAM Controller functions
+  * @brief    NOR/SRAM Controller functions 
+  *
+@verbatim   
+ ===============================================================================
+                    ##### NOR and SRAM Controller functions #####
+ ===============================================================================  
+
+ [..] The following sequence should be followed to configure the FMC to interface
+      with SRAM, PSRAM, NOR or OneNAND memory connected to the NOR/SRAM Bank:
+ 
+   (#) Enable the clock for the FMC and associated GPIOs using the following functions:
+          RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FMC, ENABLE);
+          RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+
+   (#) FMC pins configuration 
+       (++) Connect the involved FMC pins to AF12 using the following function 
+            GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FMC); 
+       (++) Configure these FMC pins in alternate function mode by calling the function
+            GPIO_Init();    
+       
+   (#) Declare a FMC_NORSRAMInitTypeDef structure, for example:
+          FMC_NORSRAMInitTypeDef  FMC_NORSRAMInitStructure;
+      and fill the FMC_NORSRAMInitStructure variable with the allowed values of
+      the structure member.
+      
+   (#) Initialize the NOR/SRAM Controller by calling the function
+          FMC_NORSRAMInit(&FMC_NORSRAMInitStructure); 
+
+   (#) Then enable the NOR/SRAM Bank, for example:
+          FMC_NORSRAMCmd(FMC_Bank1_NORSRAM2, ENABLE);  
+
+   (#) At this stage you can read/write from/to the memory connected to the NOR/SRAM Bank. 
+   
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initializes the FMC NOR/SRAM Banks registers to their default 
+  *   reset values.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank1_NORSRAM1: FMC Bank1 NOR/SRAM1  
+  *            @arg FMC_Bank1_NORSRAM2: FMC Bank1 NOR/SRAM2 
+  *            @arg FMC_Bank1_NORSRAM3: FMC Bank1 NOR/SRAM3 
+  *            @arg FMC_Bank1_NORSRAM4: FMC Bank1 NOR/SRAM4 
+  * @retval None
+  */
+void FMC_NORSRAMDeInit(uint32_t FMC_Bank)
+{
+  /* Check the parameter */
+  assert_param(IS_FMC_NORSRAM_BANK(FMC_Bank));
+  
+  /* FMC_Bank1_NORSRAM1 */
+  if(FMC_Bank == FMC_Bank1_NORSRAM1)
+  {
+    FMC_Bank1->BTCR[FMC_Bank] = 0x000030DB;    
+  }
+  /* FMC_Bank1_NORSRAM2,  FMC_Bank1_NORSRAM3 or FMC_Bank1_NORSRAM4 */
+  else
+  {   
+    FMC_Bank1->BTCR[FMC_Bank] = 0x000030D2; 
+  }
+  FMC_Bank1->BTCR[FMC_Bank + 1] = 0x0FFFFFFF;
+  FMC_Bank1E->BWTR[FMC_Bank] = 0x0FFFFFFF;  
+}
+
+/**
+  * @brief  Initializes the FMC NOR/SRAM Banks according to the specified
+  *         parameters in the FMC_NORSRAMInitStruct.
+  * @param  FMC_NORSRAMInitStruct : pointer to a FMC_NORSRAMInitTypeDef structure
+  *         that contains the configuration information for the FMC NOR/SRAM 
+  *         specified Banks.                       
+  * @retval None
+  */
+void FMC_NORSRAMInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct)
+{
+  uint32_t tmpr = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_FMC_NORSRAM_BANK(FMC_NORSRAMInitStruct->FMC_Bank));
+  assert_param(IS_FMC_MUX(FMC_NORSRAMInitStruct->FMC_DataAddressMux));
+  assert_param(IS_FMC_MEMORY(FMC_NORSRAMInitStruct->FMC_MemoryType));
+  assert_param(IS_FMC_NORSRAM_MEMORY_WIDTH(FMC_NORSRAMInitStruct->FMC_MemoryDataWidth));
+  assert_param(IS_FMC_BURSTMODE(FMC_NORSRAMInitStruct->FMC_BurstAccessMode));
+  assert_param(IS_FMC_WAIT_POLARITY(FMC_NORSRAMInitStruct->FMC_WaitSignalPolarity));
+  assert_param(IS_FMC_WRAP_MODE(FMC_NORSRAMInitStruct->FMC_WrapMode));
+  assert_param(IS_FMC_WAIT_SIGNAL_ACTIVE(FMC_NORSRAMInitStruct->FMC_WaitSignalActive));
+  assert_param(IS_FMC_WRITE_OPERATION(FMC_NORSRAMInitStruct->FMC_WriteOperation));
+  assert_param(IS_FMC_WAITE_SIGNAL(FMC_NORSRAMInitStruct->FMC_WaitSignal));
+  assert_param(IS_FMC_EXTENDED_MODE(FMC_NORSRAMInitStruct->FMC_ExtendedMode));
+  assert_param(IS_FMC_ASYNWAIT(FMC_NORSRAMInitStruct->FMC_AsynchronousWait));
+  assert_param(IS_FMC_WRITE_BURST(FMC_NORSRAMInitStruct->FMC_WriteBurst));
+  assert_param(IS_FMC_CONTINOUS_CLOCK(FMC_NORSRAMInitStruct->FMC_ContinousClock));  
+  assert_param(IS_FMC_ADDRESS_SETUP_TIME(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressSetupTime));
+  assert_param(IS_FMC_ADDRESS_HOLD_TIME(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressHoldTime));
+  assert_param(IS_FMC_DATASETUP_TIME(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataSetupTime));
+  assert_param(IS_FMC_TURNAROUND_TIME(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_BusTurnAroundDuration));
+  assert_param(IS_FMC_CLK_DIV(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_CLKDivision));
+  assert_param(IS_FMC_DATA_LATENCY(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataLatency));
+  assert_param(IS_FMC_ACCESS_MODE(FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AccessMode)); 
+  
+  /* NOR/SRAM Bank control register configuration */ 
+  FMC_Bank1->BTCR[FMC_NORSRAMInitStruct->FMC_Bank] =   
+            (uint32_t)FMC_NORSRAMInitStruct->FMC_DataAddressMux |
+            FMC_NORSRAMInitStruct->FMC_MemoryType |
+            FMC_NORSRAMInitStruct->FMC_MemoryDataWidth |
+            FMC_NORSRAMInitStruct->FMC_BurstAccessMode |
+            FMC_NORSRAMInitStruct->FMC_WaitSignalPolarity |
+            FMC_NORSRAMInitStruct->FMC_WrapMode |
+            FMC_NORSRAMInitStruct->FMC_WaitSignalActive |
+            FMC_NORSRAMInitStruct->FMC_WriteOperation |
+            FMC_NORSRAMInitStruct->FMC_WaitSignal |
+            FMC_NORSRAMInitStruct->FMC_ExtendedMode |
+            FMC_NORSRAMInitStruct->FMC_AsynchronousWait |
+            FMC_NORSRAMInitStruct->FMC_WriteBurst |
+            FMC_NORSRAMInitStruct->FMC_ContinousClock;
+
+            
+  if(FMC_NORSRAMInitStruct->FMC_MemoryType == FMC_MemoryType_NOR)
+  {
+    FMC_Bank1->BTCR[FMC_NORSRAMInitStruct->FMC_Bank] |= (uint32_t)BCR_FACCEN_SET;
+  }
+
+  /* Configure Continuous clock feature when bank2..4 is used */
+  if((FMC_NORSRAMInitStruct->FMC_ContinousClock == FMC_CClock_SyncAsync) && (FMC_NORSRAMInitStruct->FMC_Bank != FMC_Bank1_NORSRAM1))
+  {
+    tmpr = (uint32_t)((FMC_Bank1->BTCR[FMC_Bank1_NORSRAM1+1]) & ~(((uint32_t)0x0F) << 20));    
+    
+    FMC_Bank1->BTCR[FMC_Bank1_NORSRAM1]  |= FMC_NORSRAMInitStruct->FMC_ContinousClock;
+    FMC_Bank1->BTCR[FMC_Bank1_NORSRAM1]  |= FMC_BurstAccessMode_Enable;
+    FMC_Bank1->BTCR[FMC_Bank1_NORSRAM1+1] = (uint32_t)(tmpr | (((FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_CLKDivision)-1) << 20));
+  }
+  
+  /* NOR/SRAM Bank timing register configuration */
+  FMC_Bank1->BTCR[FMC_NORSRAMInitStruct->FMC_Bank+1] =   
+            (uint32_t)FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressSetupTime |
+            (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressHoldTime << 4) |
+            (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataSetupTime << 8) |
+            (FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_BusTurnAroundDuration << 16) |
+            ((FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_CLKDivision) << 20) |
+            ((FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataLatency) << 24) |
+             FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AccessMode;
+     
+  /* NOR/SRAM Bank timing register for write configuration, if extended mode is used */
+  if(FMC_NORSRAMInitStruct->FMC_ExtendedMode == FMC_ExtendedMode_Enable)
+  {
+    assert_param(IS_FMC_ADDRESS_SETUP_TIME(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AddressSetupTime));
+    assert_param(IS_FMC_ADDRESS_HOLD_TIME(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AddressHoldTime));
+    assert_param(IS_FMC_DATASETUP_TIME(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataSetupTime));
+    assert_param(IS_FMC_CLK_DIV(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_CLKDivision));
+    assert_param(IS_FMC_DATA_LATENCY(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataLatency));
+    assert_param(IS_FMC_ACCESS_MODE(FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AccessMode));
+    
+    FMC_Bank1E->BWTR[FMC_NORSRAMInitStruct->FMC_Bank] =   
+               (uint32_t)FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AddressSetupTime |
+               (FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AddressHoldTime << 4 )|
+               (FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataSetupTime << 8) |
+               ((FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_CLKDivision) << 20) |
+               ((FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataLatency) << 24) |
+               FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AccessMode;
+  }
+  else
+  {
+    FMC_Bank1E->BWTR[FMC_NORSRAMInitStruct->FMC_Bank] = 0x0FFFFFFF;
+  }
+  
+}
+
+/**
+  * @brief  Fills each FMC_NORSRAMInitStruct member with its default value.
+  * @param  FMC_NORSRAMInitStruct: pointer to a FMC_NORSRAMInitTypeDef structure 
+  *         which will be initialized.
+  * @retval None
+  */
+void FMC_NORSRAMStructInit(FMC_NORSRAMInitTypeDef* FMC_NORSRAMInitStruct)
+{  
+  /* Reset NOR/SRAM Init structure parameters values */
+  FMC_NORSRAMInitStruct->FMC_Bank = FMC_Bank1_NORSRAM1;
+  FMC_NORSRAMInitStruct->FMC_DataAddressMux = FMC_DataAddressMux_Enable;
+  FMC_NORSRAMInitStruct->FMC_MemoryType = FMC_MemoryType_SRAM;
+  FMC_NORSRAMInitStruct->FMC_MemoryDataWidth = FMC_NORSRAM_MemoryDataWidth_16b;
+  FMC_NORSRAMInitStruct->FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
+  FMC_NORSRAMInitStruct->FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
+  FMC_NORSRAMInitStruct->FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
+  FMC_NORSRAMInitStruct->FMC_WrapMode = FMC_WrapMode_Disable;
+  FMC_NORSRAMInitStruct->FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
+  FMC_NORSRAMInitStruct->FMC_WriteOperation = FMC_WriteOperation_Enable;
+  FMC_NORSRAMInitStruct->FMC_WaitSignal = FMC_WaitSignal_Enable;
+  FMC_NORSRAMInitStruct->FMC_ExtendedMode = FMC_ExtendedMode_Disable;
+  FMC_NORSRAMInitStruct->FMC_WriteBurst = FMC_WriteBurst_Disable;
+  FMC_NORSRAMInitStruct->FMC_ContinousClock = FMC_CClock_SyncOnly;
+  
+  FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressSetupTime = 15;
+  FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AddressHoldTime = 15;
+  FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataSetupTime = 255;
+  FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_BusTurnAroundDuration = 15;
+  FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_CLKDivision = 15;
+  FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_DataLatency = 15;
+  FMC_NORSRAMInitStruct->FMC_ReadWriteTimingStruct->FMC_AccessMode = FMC_AccessMode_A; 
+  FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AddressSetupTime = 15;
+  FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AddressHoldTime = 15;
+  FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataSetupTime = 255;
+  FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_BusTurnAroundDuration = 15;
+  FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_CLKDivision = 15;
+  FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_DataLatency = 15;
+  FMC_NORSRAMInitStruct->FMC_WriteTimingStruct->FMC_AccessMode = FMC_AccessMode_A;
+}
+
+/**
+  * @brief  Enables or disables the specified NOR/SRAM Memory Bank.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank1_NORSRAM1: FMC Bank1 NOR/SRAM1  
+  *            @arg FMC_Bank1_NORSRAM2: FMC Bank1 NOR/SRAM2 
+  *            @arg FMC_Bank1_NORSRAM3: FMC Bank1 NOR/SRAM3 
+  *            @arg FMC_Bank1_NORSRAM4: FMC Bank1 NOR/SRAM4 
+  * @param  NewState: new state of the FMC_Bank. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FMC_NORSRAMCmd(uint32_t FMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FMC_NORSRAM_BANK(FMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */
+    FMC_Bank1->BTCR[FMC_Bank] |= BCR_MBKEN_SET;
+  }
+  else
+  {
+    /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */
+    FMC_Bank1->BTCR[FMC_Bank] &= BCR_MBKEN_RESET;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Group2 NAND Controller functions
+  * @brief    NAND Controller functions 
+  *
+@verbatim   
+ ===============================================================================
+                    ##### NAND Controller functions #####
+ ===============================================================================  
+
+ [..]  The following sequence should be followed to configure the FMC to interface 
+       with 8-bit or 16-bit NAND memory connected to the NAND Bank:
+ 
+  (#) Enable the clock for the FMC and associated GPIOs using the following functions:
+      (++)  RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FMC, ENABLE);
+      (++)  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+
+  (#) FMC pins configuration 
+      (++) Connect the involved FMC pins to AF12 using the following function 
+           GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FMC); 
+      (++) Configure these FMC pins in alternate function mode by calling the function
+           GPIO_Init();    
+       
+  (#) Declare a FMC_NANDInitTypeDef structure, for example:
+      FMC_NANDInitTypeDef  FMC_NANDInitStructure;
+      and fill the FMC_NANDInitStructure variable with the allowed values of
+      the structure member.
+      
+  (#) Initialize the NAND Controller by calling the function
+      FMC_NANDInit(&FMC_NANDInitStructure); 
+
+  (#) Then enable the NAND Bank, for example:
+      FMC_NANDCmd(FMC_Bank3_NAND, ENABLE);  
+
+  (#) At this stage you can read/write from/to the memory connected to the NAND Bank. 
+   
+ [..]
+  (@) To enable the Error Correction Code (ECC), you have to use the function
+      FMC_NANDECCCmd(FMC_Bank3_NAND, ENABLE);  
+ [..]
+  (@) and to get the current ECC value you have to use the function
+      ECCval = FMC_GetECC(FMC_Bank3_NAND); 
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  De-initializes the FMC NAND Banks registers to their default reset values.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND 
+  * @retval None
+  */
+void FMC_NANDDeInit(uint32_t FMC_Bank)
+{
+  /* Check the parameter */
+  assert_param(IS_FMC_NAND_BANK(FMC_Bank));
+  
+  if(FMC_Bank == FMC_Bank2_NAND)
+  {
+    /* Set the FMC_Bank2 registers to their reset values */
+    FMC_Bank2->PCR2 = 0x00000018;
+    FMC_Bank2->SR2 = 0x00000040;
+    FMC_Bank2->PMEM2 = 0xFCFCFCFC;
+    FMC_Bank2->PATT2 = 0xFCFCFCFC;  
+  }
+  /* FMC_Bank3_NAND */  
+  else
+  {
+    /* Set the FMC_Bank3 registers to their reset values */
+    FMC_Bank3->PCR3 = 0x00000018;
+    FMC_Bank3->SR3 = 0x00000040;
+    FMC_Bank3->PMEM3 = 0xFCFCFCFC;
+    FMC_Bank3->PATT3 = 0xFCFCFCFC; 
+  }  
+}
+
+/**
+  * @brief  Initializes the FMC NAND Banks according to the specified parameters
+  *         in the FMC_NANDInitStruct.
+  * @param  FMC_NANDInitStruct : pointer to a FMC_NANDInitTypeDef structure that
+  *         contains the configuration information for the FMC NAND specified Banks.                       
+  * @retval None
+  */
+void FMC_NANDInit(FMC_NANDInitTypeDef* FMC_NANDInitStruct)
+{
+  uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; 
+    
+  /* Check the parameters */
+  assert_param(IS_FMC_NAND_BANK(FMC_NANDInitStruct->FMC_Bank));
+  assert_param(IS_FMC_WAIT_FEATURE(FMC_NANDInitStruct->FMC_Waitfeature));
+  assert_param(IS_FMC_NAND_MEMORY_WIDTH(FMC_NANDInitStruct->FMC_MemoryDataWidth));
+  assert_param(IS_FMC_ECC_STATE(FMC_NANDInitStruct->FMC_ECC));
+  assert_param(IS_FMC_ECCPAGE_SIZE(FMC_NANDInitStruct->FMC_ECCPageSize));
+  assert_param(IS_FMC_TCLR_TIME(FMC_NANDInitStruct->FMC_TCLRSetupTime));
+  assert_param(IS_FMC_TAR_TIME(FMC_NANDInitStruct->FMC_TARSetupTime));
+  assert_param(IS_FMC_SETUP_TIME(FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_SetupTime));
+  assert_param(IS_FMC_WAIT_TIME(FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_WaitSetupTime));
+  assert_param(IS_FMC_HOLD_TIME(FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HoldSetupTime));
+  assert_param(IS_FMC_HIZ_TIME(FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HiZSetupTime));
+  assert_param(IS_FMC_SETUP_TIME(FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_SetupTime));
+  assert_param(IS_FMC_WAIT_TIME(FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_WaitSetupTime));
+  assert_param(IS_FMC_HOLD_TIME(FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HoldSetupTime));
+  assert_param(IS_FMC_HIZ_TIME(FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HiZSetupTime));
+  
+  /* Set the tmppcr value according to FMC_NANDInitStruct parameters */
+  tmppcr = (uint32_t)FMC_NANDInitStruct->FMC_Waitfeature |
+            PCR_MEMORYTYPE_NAND |
+            FMC_NANDInitStruct->FMC_MemoryDataWidth |
+            FMC_NANDInitStruct->FMC_ECC |
+            FMC_NANDInitStruct->FMC_ECCPageSize |
+            (FMC_NANDInitStruct->FMC_TCLRSetupTime << 9 )|
+            (FMC_NANDInitStruct->FMC_TARSetupTime << 13);
+            
+  /* Set tmppmem value according to FMC_CommonSpaceTimingStructure parameters */
+  tmppmem = (uint32_t)FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_SetupTime |
+            (FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_WaitSetupTime << 8) |
+            (FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HoldSetupTime << 16)|
+            (FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HiZSetupTime << 24); 
+            
+  /* Set tmppatt value according to FMC_AttributeSpaceTimingStructure parameters */
+  tmppatt = (uint32_t)FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_SetupTime |
+            (FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_WaitSetupTime << 8) |
+            (FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HoldSetupTime << 16)|
+            (FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HiZSetupTime << 24);
+  
+  if(FMC_NANDInitStruct->FMC_Bank == FMC_Bank2_NAND)
+  {
+    /* FMC_Bank2_NAND registers configuration */
+    FMC_Bank2->PCR2 = tmppcr;
+    FMC_Bank2->PMEM2 = tmppmem;
+    FMC_Bank2->PATT2 = tmppatt;
+  }
+  else
+  {
+    /* FMC_Bank3_NAND registers configuration */
+    FMC_Bank3->PCR3 = tmppcr;
+    FMC_Bank3->PMEM3 = tmppmem;
+    FMC_Bank3->PATT3 = tmppatt;
+  }
+}
+
+
+/**
+  * @brief  Fills each FMC_NANDInitStruct member with its default value.
+  * @param  FMC_NANDInitStruct: pointer to a FMC_NANDInitTypeDef structure which
+  *         will be initialized.
+  * @retval None
+  */
+void FMC_NANDStructInit(FMC_NANDInitTypeDef* FMC_NANDInitStruct)
+{ 
+  /* Reset NAND Init structure parameters values */
+  FMC_NANDInitStruct->FMC_Bank = FMC_Bank2_NAND;
+  FMC_NANDInitStruct->FMC_Waitfeature = FMC_Waitfeature_Disable;
+  FMC_NANDInitStruct->FMC_MemoryDataWidth = FMC_NAND_MemoryDataWidth_16b;
+  FMC_NANDInitStruct->FMC_ECC = FMC_ECC_Disable;
+  FMC_NANDInitStruct->FMC_ECCPageSize = FMC_ECCPageSize_256Bytes;
+  FMC_NANDInitStruct->FMC_TCLRSetupTime = 0x0;
+  FMC_NANDInitStruct->FMC_TARSetupTime = 0x0;
+  FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_SetupTime = 252;
+  FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_WaitSetupTime = 252;
+  FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HoldSetupTime = 252;
+  FMC_NANDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HiZSetupTime = 252;
+  FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_SetupTime = 252;
+  FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_WaitSetupTime = 252;
+  FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HoldSetupTime = 252;
+  FMC_NANDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HiZSetupTime = 252;	  
+}
+
+/**
+  * @brief  Enables or disables the specified NAND Memory Bank.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  * @param  NewState: new state of the FMC_Bank. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FMC_NANDCmd(uint32_t FMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FMC_NAND_BANK(FMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */
+    if(FMC_Bank == FMC_Bank2_NAND)
+    {
+      FMC_Bank2->PCR2 |= PCR_PBKEN_SET;
+    }
+    else
+    {
+      FMC_Bank3->PCR3 |= PCR_PBKEN_SET;
+    }
+  }
+  else
+  {
+    /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */
+    if(FMC_Bank == FMC_Bank2_NAND)
+    {
+      FMC_Bank2->PCR2 &= PCR_PBKEN_RESET;
+    }
+    else
+    {
+      FMC_Bank3->PCR3 &= PCR_PBKEN_RESET;
+    }
+  }
+}
+/**
+  * @brief  Enables or disables the FMC NAND ECC feature.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  * @param  NewState: new state of the FMC NAND ECC feature.  
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FMC_NANDECCCmd(uint32_t FMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FMC_NAND_BANK(FMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */
+    if(FMC_Bank == FMC_Bank2_NAND)
+    {
+      FMC_Bank2->PCR2 |= PCR_ECCEN_SET;
+    }
+    else
+    {
+      FMC_Bank3->PCR3 |= PCR_ECCEN_SET;
+    }
+  }
+  else
+  {
+    /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */
+    if(FMC_Bank == FMC_Bank2_NAND)
+    {
+      FMC_Bank2->PCR2 &= PCR_ECCEN_RESET;
+    }
+    else
+    {
+      FMC_Bank3->PCR3 &= PCR_ECCEN_RESET;
+    }
+  }
+}
+
+/**
+  * @brief  Returns the error correction code register value.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  * @retval The Error Correction Code (ECC) value.
+  */
+uint32_t FMC_GetECC(uint32_t FMC_Bank)
+{
+  uint32_t eccval = 0x00000000;
+  
+  if(FMC_Bank == FMC_Bank2_NAND)
+  {
+    /* Get the ECCR2 register value */
+    eccval = FMC_Bank2->ECCR2;
+  }
+  else
+  {
+    /* Get the ECCR3 register value */
+    eccval = FMC_Bank3->ECCR3;
+  }
+  /* Return the error correction code value */
+  return(eccval);
+}
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Group3 PCCARD Controller functions
+  * @brief    PCCARD Controller functions 
+  *
+@verbatim   
+ ===============================================================================
+                    ##### PCCARD Controller functions #####
+ ===============================================================================  
+
+ [..]  he following sequence should be followed to configure the FMC to interface 
+       with 16-bit PC Card compatible memory connected to the PCCARD Bank:
+ 
+  (#)  Enable the clock for the FMC and associated GPIOs using the following functions:
+       (++)  RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FMC, ENABLE);
+       (++)  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+
+  (#) FMC pins configuration 
+       (++) Connect the involved FMC pins to AF12 using the following function 
+            GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FMC); 
+       (++) Configure these FMC pins in alternate function mode by calling the function
+            GPIO_Init();    
+       
+  (#) Declare a FMC_PCCARDInitTypeDef structure, for example:
+      FMC_PCCARDInitTypeDef  FMC_PCCARDInitStructure;
+      and fill the FMC_PCCARDInitStructure variable with the allowed values of
+      the structure member.
+      
+  (#) Initialize the PCCARD Controller by calling the function
+      FMC_PCCARDInit(&FMC_PCCARDInitStructure); 
+
+  (#) Then enable the PCCARD Bank:
+      FMC_PCCARDCmd(ENABLE);  
+
+  (#) At this stage you can read/write from/to the memory connected to the PCCARD Bank. 
+ 
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initializes the FMC PCCARD Bank registers to their default reset values.
+  * @param  None                       
+  * @retval None
+  */
+void FMC_PCCARDDeInit(void)
+{
+  /* Set the FMC_Bank4 registers to their reset values */
+  FMC_Bank4->PCR4 = 0x00000018; 
+  FMC_Bank4->SR4 = 0x00000000;	
+  FMC_Bank4->PMEM4 = 0xFCFCFCFC;
+  FMC_Bank4->PATT4 = 0xFCFCFCFC;
+  FMC_Bank4->PIO4 = 0xFCFCFCFC;
+}
+
+/**
+  * @brief  Initializes the FMC PCCARD Bank according to the specified parameters
+  *         in the FMC_PCCARDInitStruct.
+  * @param  FMC_PCCARDInitStruct : pointer to a FMC_PCCARDInitTypeDef structure
+  *         that contains the configuration information for the FMC PCCARD Bank.                       
+  * @retval None
+  */
+void FMC_PCCARDInit(FMC_PCCARDInitTypeDef* FMC_PCCARDInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_FMC_WAIT_FEATURE(FMC_PCCARDInitStruct->FMC_Waitfeature));
+  assert_param(IS_FMC_TCLR_TIME(FMC_PCCARDInitStruct->FMC_TCLRSetupTime));
+  assert_param(IS_FMC_TAR_TIME(FMC_PCCARDInitStruct->FMC_TARSetupTime));
+ 
+  assert_param(IS_FMC_SETUP_TIME(FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_SetupTime));
+  assert_param(IS_FMC_WAIT_TIME(FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_WaitSetupTime));
+  assert_param(IS_FMC_HOLD_TIME(FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HoldSetupTime));
+  assert_param(IS_FMC_HIZ_TIME(FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HiZSetupTime));
+  
+  assert_param(IS_FMC_SETUP_TIME(FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_SetupTime));
+  assert_param(IS_FMC_WAIT_TIME(FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_WaitSetupTime));
+  assert_param(IS_FMC_HOLD_TIME(FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HoldSetupTime));
+  assert_param(IS_FMC_HIZ_TIME(FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HiZSetupTime));
+  assert_param(IS_FMC_SETUP_TIME(FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_SetupTime));
+  assert_param(IS_FMC_WAIT_TIME(FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_WaitSetupTime));
+  assert_param(IS_FMC_HOLD_TIME(FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_HoldSetupTime));
+  assert_param(IS_FMC_HIZ_TIME(FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_HiZSetupTime));
+  
+  /* Set the PCR4 register value according to FMC_PCCARDInitStruct parameters */
+  FMC_Bank4->PCR4 = (uint32_t)FMC_PCCARDInitStruct->FMC_Waitfeature |
+                     FMC_NAND_MemoryDataWidth_16b |  
+                     (FMC_PCCARDInitStruct->FMC_TCLRSetupTime << 9) |
+                     (FMC_PCCARDInitStruct->FMC_TARSetupTime << 13);
+            
+  /* Set PMEM4 register value according to FMC_CommonSpaceTimingStructure parameters */
+  FMC_Bank4->PMEM4 = (uint32_t)FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_SetupTime |
+                      (FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_WaitSetupTime << 8) |
+                      (FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HoldSetupTime << 16)|
+                      (FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HiZSetupTime << 24); 
+            
+  /* Set PATT4 register value according to FMC_AttributeSpaceTimingStructure parameters */
+  FMC_Bank4->PATT4 = (uint32_t)FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_SetupTime |
+                      (FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_WaitSetupTime << 8) |
+                      (FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HoldSetupTime << 16)|
+                      (FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HiZSetupTime << 24);	
+            
+  /* Set PIO4 register value according to FMC_IOSpaceTimingStructure parameters */
+  FMC_Bank4->PIO4 = (uint32_t)FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_SetupTime |
+                     (FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_WaitSetupTime << 8) |
+                     (FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_HoldSetupTime << 16)|
+                     (FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_HiZSetupTime << 24);             
+}
+
+/**
+  * @brief  Fills each FMC_PCCARDInitStruct member with its default value.
+  * @param  FMC_PCCARDInitStruct: pointer to a FMC_PCCARDInitTypeDef structure
+  *         which will be initialized.
+  * @retval None
+  */
+void FMC_PCCARDStructInit(FMC_PCCARDInitTypeDef* FMC_PCCARDInitStruct)
+{
+  /* Reset PCCARD Init structure parameters values */
+  FMC_PCCARDInitStruct->FMC_Waitfeature = FMC_Waitfeature_Disable;
+  FMC_PCCARDInitStruct->FMC_TCLRSetupTime = 0;
+  FMC_PCCARDInitStruct->FMC_TARSetupTime = 0;
+  FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_SetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_WaitSetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HoldSetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_CommonSpaceTimingStruct->FMC_HiZSetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_SetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_WaitSetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HoldSetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_AttributeSpaceTimingStruct->FMC_HiZSetupTime = 252;	
+  FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_SetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_WaitSetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_HoldSetupTime = 252;
+  FMC_PCCARDInitStruct->FMC_IOSpaceTimingStruct->FMC_HiZSetupTime = 252;
+}
+
+/**
+  * @brief  Enables or disables the PCCARD Memory Bank.
+  * @param  NewState: new state of the PCCARD Memory Bank.  
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FMC_PCCARDCmd(FunctionalState NewState)
+{
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */
+    FMC_Bank4->PCR4 |= PCR_PBKEN_SET;
+  }
+  else
+  {
+    /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */
+    FMC_Bank4->PCR4 &= PCR_PBKEN_RESET;
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Group4  SDRAM Controller functions
+  * @brief    SDRAM Controller functions
+  *
+@verbatim   
+ ===============================================================================
+                     ##### SDRAM Controller functions ##### 
+ ===============================================================================  
+  
+ [..]  The following sequence should be followed to configure the FMC to interface
+       with SDRAM memory connected to the SDRAM Bank 1 or SDRAM bank 2:
+ 
+  (#) Enable the clock for the FMC and associated GPIOs using the following functions:
+      (++) RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FMC, ENABLE);
+      (++) RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+
+  (#) FMC pins configuration 
+      (++) Connect the involved FMC pins to AF12 using the following function 
+           GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FMC); 
+      (++) Configure these FMC pins in alternate function mode by calling the function
+           GPIO_Init();    
+       
+  (#) Declare a FMC_SDRAMInitTypeDef structure, for example:
+       FMC_SDRAMInitTypeDef  FMC_SDRAMInitStructure;
+      and fill the FMC_SDRAMInitStructure variable with the allowed values of
+      the structure member.  
+      
+  (#) Initialize the SDRAM Controller by calling the function
+          FMC_SDRAMInit(&FMC_SDRAMInitStructure);
+          
+  (#) Declare a FMC_SDRAMCommandTypeDef structure, for example:
+        FMC_SDRAMCommandTypeDef  FMC_SDRAMCommandStructure;
+      and fill the FMC_SDRAMCommandStructure variable with the allowed values of
+      the structure member.        
+
+  (#) Configure the SDCMR register with the desired command parameters by calling 
+      the function FMC_SDRAMCmdConfig(&FMC_SDRAMCommandStructure);  
+
+  (#) At this stage, the SDRAM memory is ready for any valid command.
+   
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initializes the FMC SDRAM Banks registers to their default 
+  *         reset values.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank1_SDRAM: FMC Bank1 SDRAM 
+  *            @arg FMC_Bank2_SDRAM: FMC Bank2 SDRAM 
+  * @retval None
+  */
+void FMC_SDRAMDeInit(uint32_t FMC_Bank)
+{
+  /* Check the parameter */
+  assert_param(IS_FMC_SDRAM_BANK(FMC_Bank));
+  
+  FMC_Bank5_6->SDCR[FMC_Bank] = 0x000002D0;
+  FMC_Bank5_6->SDTR[FMC_Bank] = 0x0FFFFFFF;    
+  FMC_Bank5_6->SDCMR = 0x00000000;
+  FMC_Bank5_6->SDRTR = 0x00000000;
+  FMC_Bank5_6->SDSR = 0x00000000; 
+}  
+
+/**
+  * @brief  Initializes the FMC SDRAM Banks according to the specified
+  *         parameters in the FMC_SDRAMInitStruct.
+  * @param  FMC_SDRAMInitStruct : pointer to a FMC_SDRAMInitTypeDef structure
+  *         that contains the configuration information for the FMC SDRAM 
+  *         specified Banks.                       
+  * @retval None
+  */
+void FMC_SDRAMInit(FMC_SDRAMInitTypeDef* FMC_SDRAMInitStruct)
+{ 
+  /* temporary registers */
+  uint32_t tmpr1 = 0;
+  uint32_t tmpr2 = 0;
+  uint32_t tmpr3 = 0;
+  uint32_t tmpr4 = 0;
+  
+  /* Check the parameters */
+  
+  /* Control parameters */
+  assert_param(IS_FMC_SDRAM_BANK(FMC_SDRAMInitStruct->FMC_Bank));
+  assert_param(IS_FMC_COLUMNBITS_NUMBER(FMC_SDRAMInitStruct->FMC_ColumnBitsNumber)); 
+  assert_param(IS_FMC_ROWBITS_NUMBER(FMC_SDRAMInitStruct->FMC_RowBitsNumber));
+  assert_param(IS_FMC_SDMEMORY_WIDTH(FMC_SDRAMInitStruct->FMC_SDMemoryDataWidth));
+  assert_param(IS_FMC_INTERNALBANK_NUMBER(FMC_SDRAMInitStruct->FMC_InternalBankNumber)); 
+  assert_param(IS_FMC_CAS_LATENCY(FMC_SDRAMInitStruct->FMC_CASLatency));
+  assert_param(IS_FMC_WRITE_PROTECTION(FMC_SDRAMInitStruct->FMC_WriteProtection));
+  assert_param(IS_FMC_SDCLOCK_PERIOD(FMC_SDRAMInitStruct->FMC_SDClockPeriod));
+  assert_param(IS_FMC_READ_BURST(FMC_SDRAMInitStruct->FMC_ReadBurst));
+  assert_param(IS_FMC_READPIPE_DELAY(FMC_SDRAMInitStruct->FMC_ReadPipeDelay));   
+  
+  /* Timing parameters */
+  assert_param(IS_FMC_LOADTOACTIVE_DELAY(FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_LoadToActiveDelay)); 
+  assert_param(IS_FMC_EXITSELFREFRESH_DELAY(FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_ExitSelfRefreshDelay));
+  assert_param(IS_FMC_SELFREFRESH_TIME(FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_SelfRefreshTime));
+  assert_param(IS_FMC_ROWCYCLE_DELAY(FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RowCycleDelay));
+  assert_param(IS_FMC_WRITE_RECOVERY_TIME(FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_WriteRecoveryTime)); 
+  assert_param(IS_FMC_RP_DELAY(FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RPDelay)); 
+  assert_param(IS_FMC_RCD_DELAY(FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RCDDelay));    
+  
+  /* SDRAM bank control register configuration */ 
+  tmpr1 =   (uint32_t)FMC_SDRAMInitStruct->FMC_ColumnBitsNumber |
+             FMC_SDRAMInitStruct->FMC_RowBitsNumber |
+             FMC_SDRAMInitStruct->FMC_SDMemoryDataWidth |
+             FMC_SDRAMInitStruct->FMC_InternalBankNumber |           
+             FMC_SDRAMInitStruct->FMC_CASLatency |
+             FMC_SDRAMInitStruct->FMC_WriteProtection |
+             FMC_SDRAMInitStruct->FMC_SDClockPeriod |
+             FMC_SDRAMInitStruct->FMC_ReadBurst | 
+             FMC_SDRAMInitStruct->FMC_ReadPipeDelay;
+            
+  if(FMC_SDRAMInitStruct->FMC_Bank == FMC_Bank1_SDRAM )
+  {
+    FMC_Bank5_6->SDCR[FMC_SDRAMInitStruct->FMC_Bank] = tmpr1;
+  }
+  else   /* SDCR2 "don't care" bits configuration */
+  {
+    tmpr3 = (uint32_t)FMC_SDRAMInitStruct->FMC_SDClockPeriod |
+             FMC_SDRAMInitStruct->FMC_ReadBurst | 
+             FMC_SDRAMInitStruct->FMC_ReadPipeDelay;
+    
+    FMC_Bank5_6->SDCR[FMC_Bank1_SDRAM] = tmpr3;
+    FMC_Bank5_6->SDCR[FMC_SDRAMInitStruct->FMC_Bank] = tmpr1;
+  }
+  /* SDRAM bank timing register configuration */
+  if(FMC_SDRAMInitStruct->FMC_Bank == FMC_Bank1_SDRAM )
+  {
+    tmpr2 =   (uint32_t)((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_LoadToActiveDelay)-1) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_ExitSelfRefreshDelay)-1) << 4) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_SelfRefreshTime)-1) << 8) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RowCycleDelay)-1) << 12) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_WriteRecoveryTime)-1) << 16) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RPDelay)-1) << 20) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RCDDelay)-1) << 24);
+            
+            FMC_Bank5_6->SDTR[FMC_SDRAMInitStruct->FMC_Bank] = tmpr2;
+  }
+  else   /* SDTR "don't care bits configuration */
+  {
+    tmpr2 =   (uint32_t)((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_LoadToActiveDelay)-1) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_ExitSelfRefreshDelay)-1) << 4) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_SelfRefreshTime)-1) << 8) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_WriteRecoveryTime)-1) << 16);
+            
+    tmpr4 =   (uint32_t)(((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RowCycleDelay)-1) << 12) |
+            (((FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RPDelay)-1) << 20);
+            
+            FMC_Bank5_6->SDTR[FMC_Bank1_SDRAM] = tmpr4;
+            FMC_Bank5_6->SDTR[FMC_SDRAMInitStruct->FMC_Bank] = tmpr2;
+  }
+  
+}
+
+/**
+  * @brief  Fills each FMC_SDRAMInitStruct member with its default value.
+  * @param  FMC_SDRAMInitStruct: pointer to a FMC_SDRAMInitTypeDef structure 
+  *         which will be initialized.
+  * @retval None
+  */
+void FMC_SDRAMStructInit(FMC_SDRAMInitTypeDef* FMC_SDRAMInitStruct)  
+{  
+  /* Reset SDRAM Init structure parameters values */
+  FMC_SDRAMInitStruct->FMC_Bank = FMC_Bank1_SDRAM;
+  FMC_SDRAMInitStruct->FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
+  FMC_SDRAMInitStruct->FMC_RowBitsNumber = FMC_RowBits_Number_11b; 
+  FMC_SDRAMInitStruct->FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
+  FMC_SDRAMInitStruct->FMC_InternalBankNumber = FMC_InternalBank_Number_4; 
+  FMC_SDRAMInitStruct->FMC_CASLatency = FMC_CAS_Latency_1;  
+  FMC_SDRAMInitStruct->FMC_WriteProtection = FMC_Write_Protection_Enable;
+  FMC_SDRAMInitStruct->FMC_SDClockPeriod = FMC_SDClock_Disable;
+  FMC_SDRAMInitStruct->FMC_ReadBurst = FMC_Read_Burst_Disable;
+  FMC_SDRAMInitStruct->FMC_ReadPipeDelay = FMC_ReadPipe_Delay_0; 
+   
+  FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_LoadToActiveDelay = 16;
+  FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_ExitSelfRefreshDelay = 16;
+  FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_SelfRefreshTime = 16;
+  FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RowCycleDelay = 16;
+  FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_WriteRecoveryTime = 16;
+  FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RPDelay = 16;
+  FMC_SDRAMInitStruct->FMC_SDRAMTimingStruct->FMC_RCDDelay = 16;
+  
+}
+
+/**
+  * @brief  Configures the SDRAM memory command issued when the device is accessed.   
+  * @param  FMC_SDRAMCommandStruct: pointer to a FMC_SDRAMCommandTypeDef structure 
+  *         which will be configured.
+  * @retval None
+  */
+void FMC_SDRAMCmdConfig(FMC_SDRAMCommandTypeDef* FMC_SDRAMCommandStruct)
+{
+  uint32_t tmpr = 0x0;
+    
+  /* check parameters */
+  assert_param(IS_FMC_COMMAND_MODE(FMC_SDRAMCommandStruct->FMC_CommandMode));
+  assert_param(IS_FMC_COMMAND_TARGET(FMC_SDRAMCommandStruct->FMC_CommandTarget));
+  assert_param(IS_FMC_AUTOREFRESH_NUMBER(FMC_SDRAMCommandStruct->FMC_AutoRefreshNumber));
+  assert_param(IS_FMC_MODE_REGISTER(FMC_SDRAMCommandStruct->FMC_ModeRegisterDefinition));
+  
+  tmpr =   (uint32_t)(FMC_SDRAMCommandStruct->FMC_CommandMode |
+                      FMC_SDRAMCommandStruct->FMC_CommandTarget |
+                     (((FMC_SDRAMCommandStruct->FMC_AutoRefreshNumber)-1)<<5) |
+                     ((FMC_SDRAMCommandStruct->FMC_ModeRegisterDefinition)<<9));
+  
+  FMC_Bank5_6->SDCMR = tmpr;
+
+}
+
+
+/**
+  * @brief  Returns the indicated FMC SDRAM bank mode status.
+  * @param  SDRAM_Bank: Defines the FMC SDRAM bank. This parameter can be 
+  *                     FMC_Bank1_SDRAM or FMC_Bank2_SDRAM. 
+  * @retval The FMC SDRAM bank mode status         
+  */
+uint32_t FMC_GetModeStatus(uint32_t SDRAM_Bank)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameter */
+  assert_param(IS_FMC_SDRAM_BANK(SDRAM_Bank));
+
+  /* Get the busy flag status */
+  if(SDRAM_Bank == FMC_Bank1_SDRAM)
+  {
+    tmpreg = (uint32_t)(FMC_Bank5_6->SDSR & FMC_SDSR_MODES1); 
+  }
+  else
+  {
+    tmpreg = ((uint32_t)(FMC_Bank5_6->SDSR & FMC_SDSR_MODES2) >> 2);
+  }
+  
+  /* Return the mode status */
+  return tmpreg;
+}
+
+/**
+  * @brief  defines the SDRAM Memory Refresh rate.
+  * @param  FMC_Count: specifies the Refresh timer count.       
+  * @retval None
+  */
+void FMC_SetRefreshCount(uint32_t FMC_Count)
+{
+  /* check the parameters */
+  assert_param(IS_FMC_REFRESH_COUNT(FMC_Count));
+  
+  FMC_Bank5_6->SDRTR |= (FMC_Count<<1);
+   
+}
+
+/**
+  * @brief  Sets the Number of consecutive SDRAM Memory auto Refresh commands.
+  * @param  FMC_Number: specifies the auto Refresh number.       
+  * @retval None
+  */
+void FMC_SetAutoRefresh_Number(uint32_t FMC_Number)
+{
+  /* check the parameters */
+  assert_param(IS_FMC_AUTOREFRESH_NUMBER(FMC_Number));
+  
+  FMC_Bank5_6->SDCMR |= (FMC_Number << 5);   
+}
+
+/**
+  * @brief  Enables or disables write protection to the specified FMC SDRAM Bank.
+  * @param  SDRAM_Bank: Defines the FMC SDRAM bank. This parameter can be 
+  *                     FMC_Bank1_SDRAM or FMC_Bank2_SDRAM.   
+  * @param  NewState: new state of the write protection flag.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FMC_SDRAMWriteProtectionConfig(uint32_t SDRAM_Bank, FunctionalState NewState)
+{
+  /* Check the parameter */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_FMC_SDRAM_BANK(SDRAM_Bank));
+  
+  if (NewState != DISABLE)
+  {
+    FMC_Bank5_6->SDCR[SDRAM_Bank] |= FMC_Write_Protection_Enable;    
+  }
+  else
+  {
+    FMC_Bank5_6->SDCR[SDRAM_Bank] &= SDCR_WriteProtection_RESET;
+  } 
+  
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup FMC_Group5  Interrupts and flags management functions
+  * @brief    Interrupts and flags management functions
+  *
+@verbatim   
+ ===============================================================================
+             ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified FMC interrupts.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  *            @arg FMC_Bank4_PCCARD: FMC Bank4 PCCARD
+  *            @arg FMC_Bank1_SDRAM: FMC Bank1 SDRAM 
+  *            @arg FMC_Bank2_SDRAM: FMC Bank2 SDRAM   
+  * @param  FMC_IT: specifies the FMC interrupt sources to be enabled or disabled.
+  *          This parameter can be any combination of the following values:
+  *            @arg FMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *            @arg FMC_IT_Level: Level edge detection interrupt.
+  *            @arg FMC_IT_FallingEdge: Falling edge detection interrupt.
+  *            @arg FMC_IT_Refresh: Refresh error detection interrupt.  
+  * @param  NewState: new state of the specified FMC interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FMC_ITConfig(uint32_t FMC_Bank, uint32_t FMC_IT, FunctionalState NewState)
+{
+  assert_param(IS_FMC_IT_BANK(FMC_Bank));
+  assert_param(IS_FMC_IT(FMC_IT));	
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected FMC_Bank2 interrupts */
+    if(FMC_Bank == FMC_Bank2_NAND)
+    {
+      FMC_Bank2->SR2 |= FMC_IT;
+    }
+    /* Enable the selected FMC_Bank3 interrupts */
+    else if (FMC_Bank == FMC_Bank3_NAND)
+    {
+      FMC_Bank3->SR3 |= FMC_IT;
+    }
+    /* Enable the selected FMC_Bank4 interrupts */
+    else if (FMC_Bank == FMC_Bank4_PCCARD)
+    {
+      FMC_Bank4->SR4 |= FMC_IT;    
+    }
+    /* Enable the selected FMC_Bank5_6 interrupt */
+    else
+    {
+      /* Enables the interrupt if the refresh error flag is set */
+      FMC_Bank5_6->SDRTR |= FMC_IT; 
+    }
+  }
+  else
+  {
+    /* Disable the selected FMC_Bank2 interrupts */
+    if(FMC_Bank == FMC_Bank2_NAND)
+    {
+      
+      FMC_Bank2->SR2 &= (uint32_t)~FMC_IT;
+    }
+    /* Disable the selected FMC_Bank3 interrupts */
+    else if (FMC_Bank == FMC_Bank3_NAND)
+    {
+      FMC_Bank3->SR3 &= (uint32_t)~FMC_IT;
+    }
+    /* Disable the selected FMC_Bank4 interrupts */
+    else if(FMC_Bank == FMC_Bank4_PCCARD)
+    {
+      FMC_Bank4->SR4 &= (uint32_t)~FMC_IT;    
+    }
+    /* Disable the selected FMC_Bank5_6 interrupt */
+    else
+    {
+      /* Disables the interrupt if the refresh error flag is not set */
+      FMC_Bank5_6->SDRTR &= (uint32_t)~FMC_IT; 
+    }
+  }
+}
+
+/**
+  * @brief  Checks whether the specified FMC flag is set or not.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  *            @arg FMC_Bank4_PCCARD: FMC Bank4 PCCARD
+  *            @arg FMC_Bank1_SDRAM: FMC Bank1 SDRAM 
+  *            @arg FMC_Bank2_SDRAM: FMC Bank2 SDRAM 
+  *            @arg FMC_Bank1_SDRAM | FMC_Bank2_SDRAM: FMC Bank1 or Bank2 SDRAM    
+  * @param  FMC_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg FMC_FLAG_RisingEdge: Rising edge detection Flag.
+  *            @arg FMC_FLAG_Level: Level detection Flag.
+  *            @arg FMC_FLAG_FallingEdge: Falling edge detection Flag.
+  *            @arg FMC_FLAG_FEMPT: Fifo empty Flag.
+  *            @arg FMC_FLAG_Refresh: Refresh error Flag.
+  *            @arg FMC_FLAG_Busy: Busy status Flag.     
+  * @retval The new state of FMC_FLAG (SET or RESET).
+  */
+FlagStatus FMC_GetFlagStatus(uint32_t FMC_Bank, uint32_t FMC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t tmpsr = 0x00000000;
+  
+  /* Check the parameters */
+  assert_param(IS_FMC_GETFLAG_BANK(FMC_Bank));
+  assert_param(IS_FMC_GET_FLAG(FMC_FLAG));
+  
+  if(FMC_Bank == FMC_Bank2_NAND)
+  {
+    tmpsr = FMC_Bank2->SR2;
+  }  
+  else if(FMC_Bank == FMC_Bank3_NAND)
+  {
+    tmpsr = FMC_Bank3->SR3;
+  }
+  else if(FMC_Bank == FMC_Bank4_PCCARD)
+  {
+    tmpsr = FMC_Bank4->SR4;
+  }
+  else 
+  {
+    tmpsr = FMC_Bank5_6->SDSR;
+  }
+  
+  /* Get the flag status */
+  if ((tmpsr & FMC_FLAG) != FMC_FLAG )
+  {
+    bitstatus = RESET;
+  }
+  else
+  {
+    bitstatus = SET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the FMC's pending flags.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  *            @arg FMC_Bank4_PCCARD: FMC Bank4 PCCARD
+  *            @arg FMC_Bank1_SDRAM: FMC Bank1 SDRAM 
+  *            @arg FMC_Bank2_SDRAM: FMC Bank2 SDRAM  
+  * @param  FMC_FLAG: specifies the flag to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg FMC_FLAG_RisingEdge: Rising edge detection Flag.
+  *            @arg FMC_FLAG_Level: Level detection Flag.
+  *            @arg FMC_FLAG_FallingEdge: Falling edge detection Flag.
+  *            @arg FMC_FLAG_Refresh: Refresh error Flag.  
+  * @retval None
+  */
+void FMC_ClearFlag(uint32_t FMC_Bank, uint32_t FMC_FLAG)
+{
+ /* Check the parameters */
+  assert_param(IS_FMC_GETFLAG_BANK(FMC_Bank));
+  assert_param(IS_FMC_CLEAR_FLAG(FMC_FLAG)) ;
+    
+  if(FMC_Bank == FMC_Bank2_NAND)
+  {
+    FMC_Bank2->SR2 &= (~FMC_FLAG); 
+  }  
+  else if(FMC_Bank == FMC_Bank3_NAND)
+  {
+    FMC_Bank3->SR3 &= (~FMC_FLAG);
+  }
+  else if(FMC_Bank == FMC_Bank4_PCCARD)
+  {
+    FMC_Bank4->SR4 &= (~FMC_FLAG);
+  }
+  /* FMC_Bank5_6 SDRAM*/
+  else
+  {
+    FMC_Bank5_6->SDRTR &= (~FMC_FLAG);
+  }
+  
+}
+
+/**
+  * @brief  Checks whether the specified FMC interrupt has occurred or not.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  *            @arg FMC_Bank4_PCCARD: FMC Bank4 PCCARD
+  *            @arg FMC_Bank1_SDRAM: FMC Bank1 SDRAM 
+  *            @arg FMC_Bank2_SDRAM: FMC Bank2 SDRAM   
+  * @param  FMC_IT: specifies the FMC interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg FMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *            @arg FMC_IT_Level: Level edge detection interrupt.
+  *            @arg FMC_IT_FallingEdge: Falling edge detection interrupt.
+  *            @arg FMC_IT_Refresh: Refresh error detection interrupt.    
+  * @retval The new state of FMC_IT (SET or RESET).
+  */
+ITStatus FMC_GetITStatus(uint32_t FMC_Bank, uint32_t FMC_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t tmpsr = 0x0;
+  uint32_t tmpsr2 = 0x0;
+  uint32_t itstatus = 0x0;
+  uint32_t itenable = 0x0; 
+  
+  /* Check the parameters */
+  assert_param(IS_FMC_IT_BANK(FMC_Bank));
+  assert_param(IS_FMC_GET_IT(FMC_IT));
+  
+  if(FMC_Bank == FMC_Bank2_NAND)
+  {
+    tmpsr = FMC_Bank2->SR2;
+  }  
+  else if(FMC_Bank == FMC_Bank3_NAND)
+  {
+    tmpsr = FMC_Bank3->SR3;
+  }
+  else if(FMC_Bank == FMC_Bank4_PCCARD)
+  {
+    tmpsr = FMC_Bank4->SR4;
+  }
+  /* FMC_Bank5_6 SDRAM*/
+  else
+  {
+    tmpsr = FMC_Bank5_6->SDRTR;
+    tmpsr2 = FMC_Bank5_6->SDSR;
+  } 
+  
+  /* get the IT enable bit status*/
+  itenable = tmpsr & FMC_IT;
+  
+  /* get the corresponding IT Flag status*/
+  if((FMC_Bank == FMC_Bank1_SDRAM) || (FMC_Bank == FMC_Bank2_SDRAM))
+  {
+    itstatus = tmpsr2 & FMC_SDSR_RE;  
+  }           
+  else
+  {
+    itstatus = tmpsr & (FMC_IT >> 3);  
+  }  
+  
+  if ((itstatus != (uint32_t)RESET)  && (itenable != (uint32_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus; 
+}
+
+/**
+  * @brief  Clears the FMC's interrupt pending bits.
+  * @param  FMC_Bank: specifies the FMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FMC_Bank2_NAND: FMC Bank2 NAND 
+  *            @arg FMC_Bank3_NAND: FMC Bank3 NAND
+  *            @arg FMC_Bank4_PCCARD: FMC Bank4 PCCARD
+  *            @arg FMC_Bank1_SDRAM: FMC Bank1 SDRAM 
+  *            @arg FMC_Bank2_SDRAM: FMC Bank2 SDRAM   
+  * @param  FMC_IT: specifies the interrupt pending bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg FMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *            @arg FMC_IT_Level: Level edge detection interrupt.
+  *            @arg FMC_IT_FallingEdge: Falling edge detection interrupt.
+  *            @arg FMC_IT_Refresh: Refresh error detection interrupt.  
+  * @retval None
+  */
+void FMC_ClearITPendingBit(uint32_t FMC_Bank, uint32_t FMC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_FMC_IT_BANK(FMC_Bank));
+  assert_param(IS_FMC_IT(FMC_IT));
+    
+  if(FMC_Bank == FMC_Bank2_NAND)
+  {
+    FMC_Bank2->SR2 &= ~(FMC_IT >> 3); 
+  }  
+  else if(FMC_Bank == FMC_Bank3_NAND)
+  {
+    FMC_Bank3->SR3 &= ~(FMC_IT >> 3);
+  }
+  else if(FMC_Bank == FMC_Bank4_PCCARD)
+  {
+    FMC_Bank4->SR4 &= ~(FMC_IT >> 3);
+  }
+  /* FMC_Bank5_6 SDRAM*/
+  else
+  {
+    FMC_Bank5_6->SDRTR |= FMC_SDRTR_CRE;
+  }
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c
new file mode 100644
index 0000000000000000000000000000000000000000..f9d91db88dc422dcb8f7db7fbe492ef10688faf0
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_fsmc.c
@@ -0,0 +1,989 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_fsmc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+ * @brief    This file provides firmware functions to manage the following 
+  *          functionalities of the FSMC peripheral:           
+  *           + Interface with SRAM, PSRAM, NOR and OneNAND memories
+  *           + Interface with NAND memories
+  *           + Interface with 16-bit PC Card compatible memories  
+  *           + Interrupts and flags management   
+  *           
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_fsmc.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup FSMC 
+  * @brief FSMC driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* --------------------- FSMC registers bit mask ---------------------------- */
+/* FSMC BCRx Mask */
+#define BCR_MBKEN_SET          ((uint32_t)0x00000001)
+#define BCR_MBKEN_RESET        ((uint32_t)0x000FFFFE)
+#define BCR_FACCEN_SET         ((uint32_t)0x00000040)
+
+/* FSMC PCRx Mask */
+#define PCR_PBKEN_SET          ((uint32_t)0x00000004)
+#define PCR_PBKEN_RESET        ((uint32_t)0x000FFFFB)
+#define PCR_ECCEN_SET          ((uint32_t)0x00000040)
+#define PCR_ECCEN_RESET        ((uint32_t)0x000FFFBF)
+#define PCR_MEMORYTYPE_NAND    ((uint32_t)0x00000008)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup FSMC_Private_Functions
+  * @{
+  */
+
+/** @defgroup FSMC_Group1 NOR/SRAM Controller functions
+ *  @brief   NOR/SRAM Controller functions 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### NOR and SRAM Controller functions #####
+ ===============================================================================  
+
+ [..] The following sequence should be followed to configure the FSMC to interface
+      with SRAM, PSRAM, NOR or OneNAND memory connected to the NOR/SRAM Bank:
+ 
+   (#) Enable the clock for the FSMC and associated GPIOs using the following functions:
+          RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FSMC, ENABLE);
+          RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+
+   (#) FSMC pins configuration 
+       (++) Connect the involved FSMC pins to AF12 using the following function 
+            GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FSMC); 
+       (++) Configure these FSMC pins in alternate function mode by calling the function
+            GPIO_Init();    
+       
+   (#) Declare a FSMC_NORSRAMInitTypeDef structure, for example:
+          FSMC_NORSRAMInitTypeDef  FSMC_NORSRAMInitStructure;
+      and fill the FSMC_NORSRAMInitStructure variable with the allowed values of
+      the structure member.
+      
+   (#) Initialize the NOR/SRAM Controller by calling the function
+          FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure); 
+
+   (#) Then enable the NOR/SRAM Bank, for example:
+          FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM2, ENABLE);  
+
+   (#) At this stage you can read/write from/to the memory connected to the NOR/SRAM Bank. 
+   
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initializes the FSMC NOR/SRAM Banks registers to their default 
+  *   reset values.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1  
+  *            @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 
+  *            @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 
+  *            @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 
+  * @retval None
+  */
+void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank)
+{
+  /* Check the parameter */
+  assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+  
+  /* FSMC_Bank1_NORSRAM1 */
+  if(FSMC_Bank == FSMC_Bank1_NORSRAM1)
+  {
+    FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB;    
+  }
+  /* FSMC_Bank1_NORSRAM2,  FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */
+  else
+  {   
+    FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2; 
+  }
+  FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF;
+  FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF;  
+}
+
+/**
+  * @brief  Initializes the FSMC NOR/SRAM Banks according to the specified
+  *         parameters in the FSMC_NORSRAMInitStruct.
+  * @param  FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef structure
+  *         that contains the configuration information for the FSMC NOR/SRAM 
+  *         specified Banks.                       
+  * @retval None
+  */
+void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank));
+  assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux));
+  assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType));
+  assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth));
+  assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode));
+  assert_param(IS_FSMC_ASYNWAIT(FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait));
+  assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity));
+  assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode));
+  assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive));
+  assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation));
+  assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal));
+  assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode));
+  assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst));  
+  assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime));
+  assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime));
+  assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime));
+  assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration));
+  assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision));
+  assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency));
+  assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode)); 
+  
+  /* Bank1 NOR/SRAM control register configuration */ 
+  FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 
+            (uint32_t)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux |
+            FSMC_NORSRAMInitStruct->FSMC_MemoryType |
+            FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth |
+            FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode |
+            FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait |
+            FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity |
+            FSMC_NORSRAMInitStruct->FSMC_WrapMode |
+            FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive |
+            FSMC_NORSRAMInitStruct->FSMC_WriteOperation |
+            FSMC_NORSRAMInitStruct->FSMC_WaitSignal |
+            FSMC_NORSRAMInitStruct->FSMC_ExtendedMode |
+            FSMC_NORSRAMInitStruct->FSMC_WriteBurst;
+  if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR)
+  {
+    FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (uint32_t)BCR_FACCEN_SET;
+  }
+  /* Bank1 NOR/SRAM timing register configuration */
+  FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] = 
+            (uint32_t)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) |
+            (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) |
+             FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode;
+            
+    
+  /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */
+  if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable)
+  {
+    assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime));
+    assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime));
+    assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime));
+    assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision));
+    assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency));
+    assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode));
+    FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 
+              (uint32_t)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime |
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )|
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) |
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) |
+              (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) |
+               FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode;
+  }
+  else
+  {
+    FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF;
+  }
+}
+
+/**
+  * @brief  Fills each FSMC_NORSRAMInitStruct member with its default value.
+  * @param  FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef structure 
+  *         which will be initialized.
+  * @retval None
+  */
+void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct)
+{  
+  /* Reset NOR/SRAM Init structure parameters values */
+  FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1;
+  FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable;
+  FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM;
+  FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+  FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+  FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+  FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+  FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable;
+  FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; 
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF;
+  FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A;
+}
+
+/**
+  * @brief  Enables or disables the specified NOR/SRAM Memory Bank.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1  
+  *            @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 
+  *            @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 
+  *            @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 
+  * @param  NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */
+    FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_SET;
+  }
+  else
+  {
+    /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */
+    FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_RESET;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Group2 NAND Controller functions
+ *  @brief   NAND Controller functions 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### NAND Controller functions #####
+ ===============================================================================  
+
+ [..]  The following sequence should be followed to configure the FSMC to interface 
+       with 8-bit or 16-bit NAND memory connected to the NAND Bank:
+ 
+  (#) Enable the clock for the FSMC and associated GPIOs using the following functions:
+      (++)  RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FSMC, ENABLE);
+      (++)  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+
+  (#) FSMC pins configuration 
+      (++) Connect the involved FSMC pins to AF12 using the following function 
+           GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FSMC); 
+      (++) Configure these FSMC pins in alternate function mode by calling the function
+           GPIO_Init();    
+       
+  (#) Declare a FSMC_NANDInitTypeDef structure, for example:
+      FSMC_NANDInitTypeDef  FSMC_NANDInitStructure;
+      and fill the FSMC_NANDInitStructure variable with the allowed values of
+      the structure member.
+      
+  (#) Initialize the NAND Controller by calling the function
+      FSMC_NANDInit(&FSMC_NANDInitStructure); 
+
+  (#) Then enable the NAND Bank, for example:
+      FSMC_NANDCmd(FSMC_Bank3_NAND, ENABLE);  
+
+  (#) At this stage you can read/write from/to the memory connected to the NAND Bank. 
+   
+ [..]
+  (@) To enable the Error Correction Code (ECC), you have to use the function
+      FSMC_NANDECCCmd(FSMC_Bank3_NAND, ENABLE);  
+ [..]
+  (@) and to get the current ECC value you have to use the function
+      ECCval = FSMC_GetECC(FSMC_Bank3_NAND); 
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  De-initializes the FSMC NAND Banks registers to their default reset values.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND 
+  * @retval None
+  */
+void FSMC_NANDDeInit(uint32_t FSMC_Bank)
+{
+  /* Check the parameter */
+  assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    /* Set the FSMC_Bank2 registers to their reset values */
+    FSMC_Bank2->PCR2 = 0x00000018;
+    FSMC_Bank2->SR2 = 0x00000040;
+    FSMC_Bank2->PMEM2 = 0xFCFCFCFC;
+    FSMC_Bank2->PATT2 = 0xFCFCFCFC;  
+  }
+  /* FSMC_Bank3_NAND */  
+  else
+  {
+    /* Set the FSMC_Bank3 registers to their reset values */
+    FSMC_Bank3->PCR3 = 0x00000018;
+    FSMC_Bank3->SR3 = 0x00000040;
+    FSMC_Bank3->PMEM3 = 0xFCFCFCFC;
+    FSMC_Bank3->PATT3 = 0xFCFCFCFC; 
+  }  
+}
+
+/**
+  * @brief  Initializes the FSMC NAND Banks according to the specified parameters
+  *         in the FSMC_NANDInitStruct.
+  * @param  FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef structure that
+  *         contains the configuration information for the FSMC NAND specified Banks.                       
+  * @retval None
+  */
+void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{
+  uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; 
+    
+  /* Check the parameters */
+  assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank));
+  assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature));
+  assert_param( IS_FSMC_MEMORY_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth));
+  assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC));
+  assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize));
+  assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime));
+  assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime));
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+  
+  /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */
+  tmppcr = (uint32_t)FSMC_NANDInitStruct->FSMC_Waitfeature |
+            PCR_MEMORYTYPE_NAND |
+            FSMC_NANDInitStruct->FSMC_MemoryDataWidth |
+            FSMC_NANDInitStruct->FSMC_ECC |
+            FSMC_NANDInitStruct->FSMC_ECCPageSize |
+            (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )|
+            (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13);
+            
+  /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */
+  tmppmem = (uint32_t)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+            (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+            (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+            (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); 
+            
+  /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */
+  tmppatt = (uint32_t)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+            (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+            (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+            (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);
+  
+  if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    /* FSMC_Bank2_NAND registers configuration */
+    FSMC_Bank2->PCR2 = tmppcr;
+    FSMC_Bank2->PMEM2 = tmppmem;
+    FSMC_Bank2->PATT2 = tmppatt;
+  }
+  else
+  {
+    /* FSMC_Bank3_NAND registers configuration */
+    FSMC_Bank3->PCR3 = tmppcr;
+    FSMC_Bank3->PMEM3 = tmppmem;
+    FSMC_Bank3->PATT3 = tmppatt;
+  }
+}
+
+
+/**
+  * @brief  Fills each FSMC_NANDInitStruct member with its default value.
+  * @param  FSMC_NANDInitStruct: pointer to a FSMC_NANDInitTypeDef structure which
+  *         will be initialized.
+  * @retval None
+  */
+void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct)
+{ 
+  /* Reset NAND Init structure parameters values */
+  FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND;
+  FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+  FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b;
+  FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable;
+  FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes;
+  FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0;
+  FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;	  
+}
+
+/**
+  * @brief  Enables or disables the specified NAND Memory Bank.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  * @param  NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 |= PCR_PBKEN_SET;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 |= PCR_PBKEN_SET;
+    }
+  }
+  else
+  {
+    /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 &= PCR_PBKEN_RESET;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 &= PCR_PBKEN_RESET;
+    }
+  }
+}
+/**
+  * @brief  Enables or disables the FSMC NAND ECC feature.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  * @param  NewState: new state of the FSMC NAND ECC feature.  
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_NAND_BANK(FSMC_Bank));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 |= PCR_ECCEN_SET;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 |= PCR_ECCEN_SET;
+    }
+  }
+  else
+  {
+    /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->PCR2 &= PCR_ECCEN_RESET;
+    }
+    else
+    {
+      FSMC_Bank3->PCR3 &= PCR_ECCEN_RESET;
+    }
+  }
+}
+
+/**
+  * @brief  Returns the error correction code register value.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  * @retval The Error Correction Code (ECC) value.
+  */
+uint32_t FSMC_GetECC(uint32_t FSMC_Bank)
+{
+  uint32_t eccval = 0x00000000;
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    /* Get the ECCR2 register value */
+    eccval = FSMC_Bank2->ECCR2;
+  }
+  else
+  {
+    /* Get the ECCR3 register value */
+    eccval = FSMC_Bank3->ECCR3;
+  }
+  /* Return the error correction code value */
+  return(eccval);
+}
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Group3 PCCARD Controller functions
+ *  @brief   PCCARD Controller functions 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### PCCARD Controller functions #####
+ ===============================================================================  
+
+ [..]  he following sequence should be followed to configure the FSMC to interface 
+       with 16-bit PC Card compatible memory connected to the PCCARD Bank:
+ 
+  (#)  Enable the clock for the FSMC and associated GPIOs using the following functions:
+       (++)  RCC_AHB3PeriphClockCmd(RCC_AHB3Periph_FSMC, ENABLE);
+       (++)  RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+
+  (#) FSMC pins configuration 
+       (++) Connect the involved FSMC pins to AF12 using the following function 
+            GPIO_PinAFConfig(GPIOx, GPIO_PinSourcex, GPIO_AF_FSMC); 
+       (++) Configure these FSMC pins in alternate function mode by calling the function
+            GPIO_Init();    
+       
+  (#) Declare a FSMC_PCCARDInitTypeDef structure, for example:
+      FSMC_PCCARDInitTypeDef  FSMC_PCCARDInitStructure;
+      and fill the FSMC_PCCARDInitStructure variable with the allowed values of
+      the structure member.
+      
+  (#) Initialize the PCCARD Controller by calling the function
+      FSMC_PCCARDInit(&FSMC_PCCARDInitStructure); 
+
+  (#) Then enable the PCCARD Bank:
+      FSMC_PCCARDCmd(ENABLE);  
+
+  (#) At this stage you can read/write from/to the memory connected to the PCCARD Bank. 
+ 
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initializes the FSMC PCCARD Bank registers to their default reset values.
+  * @param  None                       
+  * @retval None
+  */
+void FSMC_PCCARDDeInit(void)
+{
+  /* Set the FSMC_Bank4 registers to their reset values */
+  FSMC_Bank4->PCR4 = 0x00000018; 
+  FSMC_Bank4->SR4 = 0x00000000;	
+  FSMC_Bank4->PMEM4 = 0xFCFCFCFC;
+  FSMC_Bank4->PATT4 = 0xFCFCFCFC;
+  FSMC_Bank4->PIO4 = 0xFCFCFCFC;
+}
+
+/**
+  * @brief  Initializes the FSMC PCCARD Bank according to the specified parameters
+  *         in the FSMC_PCCARDInitStruct.
+  * @param  FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef structure
+  *         that contains the configuration information for the FSMC PCCARD Bank.                       
+  * @retval None
+  */
+void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature));
+  assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime));
+  assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime));
+ 
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime));
+  
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime));
+  assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime));
+  assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime));
+  assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime));
+  assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime));
+  
+  /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */
+  FSMC_Bank4->PCR4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_Waitfeature |
+                     FSMC_MemoryDataWidth_16b |  
+                     (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) |
+                     (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13);
+            
+  /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */
+  FSMC_Bank4->PMEM4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime |
+                      (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+                      (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+                      (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); 
+            
+  /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */
+  FSMC_Bank4->PATT4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime |
+                      (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+                      (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+                      (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24);	
+            
+  /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */
+  FSMC_Bank4->PIO4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime |
+                     (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) |
+                     (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)|
+                     (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24);             
+}
+
+/**
+  * @brief  Fills each FSMC_PCCARDInitStruct member with its default value.
+  * @param  FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef structure
+  *         which will be initialized.
+  * @retval None
+  */
+void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct)
+{
+  /* Reset PCCARD Init structure parameters values */
+  FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable;
+  FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0;
+  FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;	
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC;
+  FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC;
+}
+
+/**
+  * @brief  Enables or disables the PCCARD Memory Bank.
+  * @param  NewState: new state of the PCCARD Memory Bank.  
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_PCCARDCmd(FunctionalState NewState)
+{
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */
+    FSMC_Bank4->PCR4 |= PCR_PBKEN_SET;
+  }
+  else
+  {
+    /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */
+    FSMC_Bank4->PCR4 &= PCR_PBKEN_RESET;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup FSMC_Group4  Interrupts and flags management functions
+ *  @brief    Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+             ##### Interrupts and flags management functions #####
+ ===============================================================================   
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified FSMC interrupts.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *            @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_IT: specifies the FSMC interrupt sources to be enabled or disabled.
+  *          This parameter can be any combination of the following values:
+  *            @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *            @arg FSMC_IT_Level: Level edge detection interrupt.
+  *            @arg FSMC_IT_FallingEdge: Falling edge detection interrupt.
+  * @param  NewState: new state of the specified FSMC interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState)
+{
+  assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_IT(FSMC_IT));	
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected FSMC_Bank2 interrupts */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      FSMC_Bank2->SR2 |= FSMC_IT;
+    }
+    /* Enable the selected FSMC_Bank3 interrupts */
+    else if (FSMC_Bank == FSMC_Bank3_NAND)
+    {
+      FSMC_Bank3->SR3 |= FSMC_IT;
+    }
+    /* Enable the selected FSMC_Bank4 interrupts */
+    else
+    {
+      FSMC_Bank4->SR4 |= FSMC_IT;    
+    }
+  }
+  else
+  {
+    /* Disable the selected FSMC_Bank2 interrupts */
+    if(FSMC_Bank == FSMC_Bank2_NAND)
+    {
+      
+      FSMC_Bank2->SR2 &= (uint32_t)~FSMC_IT;
+    }
+    /* Disable the selected FSMC_Bank3 interrupts */
+    else if (FSMC_Bank == FSMC_Bank3_NAND)
+    {
+      FSMC_Bank3->SR3 &= (uint32_t)~FSMC_IT;
+    }
+    /* Disable the selected FSMC_Bank4 interrupts */
+    else
+    {
+      FSMC_Bank4->SR4 &= (uint32_t)~FSMC_IT;    
+    }
+  }
+}
+
+/**
+  * @brief  Checks whether the specified FSMC flag is set or not.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *            @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_FLAG_RisingEdge: Rising edge detection Flag.
+  *            @arg FSMC_FLAG_Level: Level detection Flag.
+  *            @arg FSMC_FLAG_FallingEdge: Falling edge detection Flag.
+  *            @arg FSMC_FLAG_FEMPT: Fifo empty Flag. 
+  * @retval The new state of FSMC_FLAG (SET or RESET).
+  */
+FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t tmpsr = 0x00000000;
+  
+  /* Check the parameters */
+  assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG));
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    tmpsr = FSMC_Bank2->SR2;
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    tmpsr = FSMC_Bank3->SR3;
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    tmpsr = FSMC_Bank4->SR4;
+  } 
+  
+  /* Get the flag status */
+  if ((tmpsr & FSMC_FLAG) != (uint16_t)RESET )
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the FSMC's pending flags.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *            @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_FLAG: specifies the flag to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg FSMC_FLAG_RisingEdge: Rising edge detection Flag.
+  *            @arg FSMC_FLAG_Level: Level detection Flag.
+  *            @arg FSMC_FLAG_FallingEdge: Falling edge detection Flag.
+  * @retval None
+  */
+void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG)
+{
+ /* Check the parameters */
+  assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ;
+    
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    FSMC_Bank2->SR2 &= ~FSMC_FLAG; 
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    FSMC_Bank3->SR3 &= ~FSMC_FLAG;
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    FSMC_Bank4->SR4 &= ~FSMC_FLAG;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified FSMC interrupt has occurred or not.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *            @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_IT: specifies the FSMC interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *            @arg FSMC_IT_Level: Level edge detection interrupt.
+  *            @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. 
+  * @retval The new state of FSMC_IT (SET or RESET).
+  */
+ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t tmpsr = 0x0, itstatus = 0x0, itenable = 0x0; 
+  
+  /* Check the parameters */
+  assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_GET_IT(FSMC_IT));
+  
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    tmpsr = FSMC_Bank2->SR2;
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    tmpsr = FSMC_Bank3->SR3;
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    tmpsr = FSMC_Bank4->SR4;
+  } 
+  
+  itstatus = tmpsr & FSMC_IT;
+  
+  itenable = tmpsr & (FSMC_IT >> 3);
+  if ((itstatus != (uint32_t)RESET)  && (itenable != (uint32_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus; 
+}
+
+/**
+  * @brief  Clears the FSMC's interrupt pending bits.
+  * @param  FSMC_Bank: specifies the FSMC Bank to be used
+  *          This parameter can be one of the following values:
+  *            @arg FSMC_Bank2_NAND: FSMC Bank2 NAND 
+  *            @arg FSMC_Bank3_NAND: FSMC Bank3 NAND
+  *            @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD
+  * @param  FSMC_IT: specifies the interrupt pending bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. 
+  *            @arg FSMC_IT_Level: Level edge detection interrupt.
+  *            @arg FSMC_IT_FallingEdge: Falling edge detection interrupt.
+  * @retval None
+  */
+void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_FSMC_IT_BANK(FSMC_Bank));
+  assert_param(IS_FSMC_IT(FSMC_IT));
+    
+  if(FSMC_Bank == FSMC_Bank2_NAND)
+  {
+    FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3); 
+  }  
+  else if(FSMC_Bank == FSMC_Bank3_NAND)
+  {
+    FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3);
+  }
+  /* FSMC_Bank4_PCCARD*/
+  else
+  {
+    FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3);
+  }
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c
new file mode 100644
index 0000000000000000000000000000000000000000..c099e948efc22dda70f4de1a14446dea3b093e01
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c
@@ -0,0 +1,611 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_gpio.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the GPIO peripheral:           
+  *           + Initialization and Configuration
+  *           + GPIO Read and Write
+  *           + GPIO Alternate functions configuration
+  * 
+@verbatim  
+ ===============================================================================
+                      ##### How to use this driver #####
+ ===============================================================================       
+ [..]             
+   (#) Enable the GPIO AHB clock using the following function
+       RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOx, ENABLE);
+               
+   (#) Configure the GPIO pin(s) using GPIO_Init()
+       Four possible configuration are available for each pin:
+       (++) Input: Floating, Pull-up, Pull-down.
+       (++) Output: Push-Pull (Pull-up, Pull-down or no Pull)
+            Open Drain (Pull-up, Pull-down or no Pull). In output mode, the speed 
+            is configurable: 2 MHz, 25 MHz, 50 MHz or 100 MHz.
+       (++) Alternate Function: Push-Pull (Pull-up, Pull-down or no Pull) Open 
+            Drain (Pull-up, Pull-down or no Pull).
+       (++) Analog: required mode when a pin is to be used as ADC channel or DAC 
+            output.
+   
+   (#) Peripherals alternate function:
+       (++) For ADC and DAC, configure the desired pin in analog mode using 
+            GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AN;
+            (+++) For other peripherals (TIM, USART...):
+            (+++) Connect the pin to the desired peripherals' Alternate 
+                     Function (AF) using GPIO_PinAFConfig() function
+            (+++) Configure the desired pin in alternate function mode using
+                     GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
+            (+++) Select the type, pull-up/pull-down and output speed via 
+                     GPIO_PuPd, GPIO_OType and GPIO_Speed members
+            (+++) Call GPIO_Init() function
+          
+   (#) To get the level of a pin configured in input mode use GPIO_ReadInputDataBit()
+            
+   (#) To set/reset the level of a pin configured in output mode use 
+       GPIO_SetBits()/GPIO_ResetBits()
+                 
+   (#) During and just after reset, the alternate functions are not 
+       active and the GPIO pins are configured in input floating mode (except JTAG
+       pins).
+  
+   (#) The LSE oscillator pins OSC32_IN and OSC32_OUT can be used as general purpose 
+       (PC14 and PC15, respectively) when the LSE oscillator is off. The LSE has 
+       priority over the GPIO function.
+  
+   (#) The HSE oscillator pins OSC_IN/OSC_OUT can be used as 
+       general purpose PH0 and PH1, respectively, when the HSE oscillator is off. 
+       The HSE has priority over the GPIO function.
+               
+@endverbatim        
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_gpio.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup GPIO 
+  * @brief GPIO driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup GPIO_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup GPIO_Group1 Initialization and Configuration
+ *  @brief   Initialization and Configuration
+ *
+@verbatim   
+ ===============================================================================
+                 ##### Initialization and Configuration #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initializes the GPIOx peripheral registers to their default reset values.
+  * @note   By default, The GPIO pins are configured in input floating mode (except JTAG pins).
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.  
+  * @retval None
+  */
+void GPIO_DeInit(GPIO_TypeDef* GPIOx)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+  if (GPIOx == GPIOA)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, DISABLE);
+  }
+  else if (GPIOx == GPIOB)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, DISABLE);
+  }
+  else if (GPIOx == GPIOC)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, DISABLE);
+  }
+  else if (GPIOx == GPIOD)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, DISABLE);
+  }
+  else if (GPIOx == GPIOE)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, DISABLE);
+  }
+  else if (GPIOx == GPIOF)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, DISABLE);
+  }
+  else if (GPIOx == GPIOG)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, DISABLE);
+  }
+  else if (GPIOx == GPIOH)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOH, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOH, DISABLE);
+  }
+
+  else if (GPIOx == GPIOI)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOI, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOI, DISABLE);
+  }
+  else if (GPIOx == GPIOJ)
+  {
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOJ, ENABLE);
+    RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOJ, DISABLE);
+  }
+  else
+  {
+    if (GPIOx == GPIOK)
+    {
+      RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOK, ENABLE);
+      RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOK, DISABLE);
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the GPIOx peripheral according to the specified parameters in the GPIO_InitStruct.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices.   
+  * @param  GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that contains
+  *         the configuration information for the specified GPIO peripheral.
+  * @retval None
+  */
+void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct)
+{
+  uint32_t pinpos = 0x00, pos = 0x00 , currentpin = 0x00;
+
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin));
+  assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode));
+  assert_param(IS_GPIO_PUPD(GPIO_InitStruct->GPIO_PuPd));
+
+  /* ------------------------- Configure the port pins ---------------- */
+  /*-- GPIO Mode Configuration --*/
+  for (pinpos = 0x00; pinpos < 0x10; pinpos++)
+  {
+    pos = ((uint32_t)0x01) << pinpos;
+    /* Get the port pins position */
+    currentpin = (GPIO_InitStruct->GPIO_Pin) & pos;
+
+    if (currentpin == pos)
+    {
+      GPIOx->MODER  &= ~(GPIO_MODER_MODER0 << (pinpos * 2));
+      GPIOx->MODER |= (((uint32_t)GPIO_InitStruct->GPIO_Mode) << (pinpos * 2));
+
+      if ((GPIO_InitStruct->GPIO_Mode == GPIO_Mode_OUT) || (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_AF))
+      {
+        /* Check Speed mode parameters */
+        assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed));
+
+        /* Speed mode configuration */
+        GPIOx->OSPEEDR &= ~(GPIO_OSPEEDER_OSPEEDR0 << (pinpos * 2));
+        GPIOx->OSPEEDR |= ((uint32_t)(GPIO_InitStruct->GPIO_Speed) << (pinpos * 2));
+
+        /* Check Output mode parameters */
+        assert_param(IS_GPIO_OTYPE(GPIO_InitStruct->GPIO_OType));
+
+        /* Output mode configuration*/
+        GPIOx->OTYPER  &= ~((GPIO_OTYPER_OT_0) << ((uint16_t)pinpos)) ;
+        GPIOx->OTYPER |= (uint16_t)(((uint16_t)GPIO_InitStruct->GPIO_OType) << ((uint16_t)pinpos));
+      }
+
+      /* Pull-up Pull down resistor configuration*/
+      GPIOx->PUPDR &= ~(GPIO_PUPDR_PUPDR0 << ((uint16_t)pinpos * 2));
+      GPIOx->PUPDR |= (((uint32_t)GPIO_InitStruct->GPIO_PuPd) << (pinpos * 2));
+    }
+  }
+}
+
+/**
+  * @brief  Fills each GPIO_InitStruct member with its default value.
+  * @param  GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct)
+{
+  /* Reset GPIO init structure parameters values */
+  GPIO_InitStruct->GPIO_Pin  = GPIO_Pin_All;
+  GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN;
+  GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz;
+  GPIO_InitStruct->GPIO_OType = GPIO_OType_PP;
+  GPIO_InitStruct->GPIO_PuPd = GPIO_PuPd_NOPULL;
+}
+
+/**
+  * @brief  Locks GPIO Pins configuration registers.
+  * @note   The locked registers are GPIOx_MODER, GPIOx_OTYPER, GPIOx_OSPEEDR,
+  *         GPIOx_PUPDR, GPIOx_AFRL and GPIOx_AFRH.
+  * @note   The configuration of the locked GPIO pins can no longer be modified
+  *         until the next reset.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_Pin: specifies the port bit to be locked.
+  *          This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
+  * @retval None
+  */
+void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  __IO uint32_t tmp = 0x00010000;
+
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+  tmp |= GPIO_Pin;
+  /* Set LCKK bit */
+  GPIOx->LCKR = tmp;
+  /* Reset LCKK bit */
+  GPIOx->LCKR =  GPIO_Pin;
+  /* Set LCKK bit */
+  GPIOx->LCKR = tmp;
+  /* Read LCKK bit*/
+  tmp = GPIOx->LCKR;
+  /* Read LCKK bit*/
+  tmp = GPIOx->LCKR;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Group2 GPIO Read and Write
+ *  @brief   GPIO Read and Write
+ *
+@verbatim   
+ ===============================================================================
+                         ##### GPIO Read and Write #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Reads the specified input port pin.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_Pin: specifies the port bit to read.
+  *         This parameter can be GPIO_Pin_x where x can be (0..15).
+  * @retval The input port pin value.
+  */
+uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  uint8_t bitstatus = 0x00;
+
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
+  if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET)
+  {
+    bitstatus = (uint8_t)Bit_SET;
+  }
+  else
+  {
+    bitstatus = (uint8_t)Bit_RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Reads the specified GPIO input data port.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @retval GPIO input data port value.
+  */
+uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+  return ((uint16_t)GPIOx->IDR);
+}
+
+/**
+  * @brief  Reads the specified output data port bit.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_Pin: specifies the port bit to read.
+  *          This parameter can be GPIO_Pin_x where x can be (0..15).
+  * @retval The output port pin value.
+  */
+uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  uint8_t bitstatus = 0x00;
+
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+
+  if (((GPIOx->ODR) & GPIO_Pin) != (uint32_t)Bit_RESET)
+  {
+    bitstatus = (uint8_t)Bit_SET;
+  }
+  else
+  {
+    bitstatus = (uint8_t)Bit_RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Reads the specified GPIO output data port.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @retval GPIO output data port value.
+  */
+uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+  return ((uint16_t)GPIOx->ODR);
+}
+
+/**
+  * @brief  Sets the selected data port bits.
+  * @note   This functions uses GPIOx_BSRR register to allow atomic read/modify 
+  *         accesses. In this way, there is no risk of an IRQ occurring between
+  *         the read and the modify access.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_Pin: specifies the port bits to be written.
+  *          This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
+  * @retval None
+  */
+void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+  GPIOx->BSRRL = GPIO_Pin;
+}
+
+/**
+  * @brief  Clears the selected data port bits.
+  * @note   This functions uses GPIOx_BSRR register to allow atomic read/modify 
+  *         accesses. In this way, there is no risk of an IRQ occurring between
+  *         the read and the modify access.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_Pin: specifies the port bits to be written.
+  *          This parameter can be any combination of GPIO_Pin_x where x can be (0..15).
+  * @retval None
+  */
+void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN(GPIO_Pin));
+
+  GPIOx->BSRRH = GPIO_Pin;
+}
+
+/**
+  * @brief  Sets or clears the selected data port bit.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_Pin: specifies the port bit to be written.
+  *          This parameter can be one of GPIO_Pin_x where x can be (0..15).
+  * @param  BitVal: specifies the value to be written to the selected bit.
+  *          This parameter can be one of the BitAction enum values:
+  *            @arg Bit_RESET: to clear the port pin
+  *            @arg Bit_SET: to set the port pin
+  * @retval None
+  */
+void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GET_GPIO_PIN(GPIO_Pin));
+  assert_param(IS_GPIO_BIT_ACTION(BitVal));
+
+  if (BitVal != Bit_RESET)
+  {
+    GPIOx->BSRRL = GPIO_Pin;
+  }
+  else
+  {
+    GPIOx->BSRRH = GPIO_Pin ;
+  }
+}
+
+/**
+  * @brief  Writes data to the specified GPIO data port.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  PortVal: specifies the value to be written to the port output data register.
+  * @retval None
+  */
+void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+  GPIOx->ODR = PortVal;
+}
+
+/**
+  * @brief  Toggles the specified GPIO pins..
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_Pin: Specifies the pins to be toggled.
+  * @retval None
+  */
+void GPIO_ToggleBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
+{
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+
+  GPIOx->ODR ^= GPIO_Pin;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup GPIO_Group3 GPIO Alternate functions configuration function
+ *  @brief   GPIO Alternate functions configuration function
+ *
+@verbatim   
+ ===============================================================================
+           ##### GPIO Alternate functions configuration function #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Changes the mapping of the specified pin.
+  * @param  GPIOx: where x can be (A..K) to select the GPIO peripheral for STM32F405xx/407xx and STM32F415xx/417xx devices
+  *                      x can be (A..I) to select the GPIO peripheral for STM32F42xxx/43xxx devices.
+  *                      x can be (A, B, C, D and H) to select the GPIO peripheral for STM32F401xx devices. 
+  * @param  GPIO_PinSource: specifies the pin for the Alternate function.
+  *         This parameter can be GPIO_PinSourcex where x can be (0..15).
+  * @param  GPIO_AFSelection: selects the pin to used as Alternate function.
+  *          This parameter can be one of the following values:
+  *            @arg GPIO_AF_RTC_50Hz: Connect RTC_50Hz pin to AF0 (default after reset) 
+  *            @arg GPIO_AF_MCO: Connect MCO pin (MCO1 and MCO2) to AF0 (default after reset) 
+  *            @arg GPIO_AF_TAMPER: Connect TAMPER pins (TAMPER_1 and TAMPER_2) to AF0 (default after reset) 
+  *            @arg GPIO_AF_SWJ: Connect SWJ pins (SWD and JTAG)to AF0 (default after reset) 
+  *            @arg GPIO_AF_TRACE: Connect TRACE pins to AF0 (default after reset)
+  *            @arg GPIO_AF_TIM1: Connect TIM1 pins to AF1
+  *            @arg GPIO_AF_TIM2: Connect TIM2 pins to AF1
+  *            @arg GPIO_AF_TIM3: Connect TIM3 pins to AF2
+  *            @arg GPIO_AF_TIM4: Connect TIM4 pins to AF2
+  *            @arg GPIO_AF_TIM5: Connect TIM5 pins to AF2
+  *            @arg GPIO_AF_TIM8: Connect TIM8 pins to AF3
+  *            @arg GPIO_AF_TIM9: Connect TIM9 pins to AF3
+  *            @arg GPIO_AF_TIM10: Connect TIM10 pins to AF3
+  *            @arg GPIO_AF_TIM11: Connect TIM11 pins to AF3
+  *            @arg GPIO_AF_I2C1: Connect I2C1 pins to AF4
+  *            @arg GPIO_AF_I2C2: Connect I2C2 pins to AF4
+  *            @arg GPIO_AF_I2C3: Connect I2C3 pins to AF4
+  *            @arg GPIO_AF_SPI1: Connect SPI1 pins to AF5
+  *            @arg GPIO_AF_SPI2: Connect SPI2/I2S2 pins to AF5
+  *            @arg GPIO_AF_SPI4: Connect SPI4 pins to AF5 
+  *            @arg GPIO_AF_SPI5: Connect SPI5 pins to AF5 
+  *            @arg GPIO_AF_SPI6: Connect SPI6 pins to AF5
+  *            @arg GPIO_AF_SAI1: Connect SAI1 pins to AF6 for STM32F42xxx/43xxx devices.       
+  *            @arg GPIO_AF_SPI3: Connect SPI3/I2S3 pins to AF6
+  *            @arg GPIO_AF_I2S3ext: Connect I2S3ext pins to AF7
+  *            @arg GPIO_AF_USART1: Connect USART1 pins to AF7
+  *            @arg GPIO_AF_USART2: Connect USART2 pins to AF7
+  *            @arg GPIO_AF_USART3: Connect USART3 pins to AF7
+  *            @arg GPIO_AF_UART4: Connect UART4 pins to AF8
+  *            @arg GPIO_AF_UART5: Connect UART5 pins to AF8
+  *            @arg GPIO_AF_USART6: Connect USART6 pins to AF8
+  *            @arg GPIO_AF_UART7: Connect UART7 pins to AF8
+  *            @arg GPIO_AF_UART8: Connect UART8 pins to AF8
+  *            @arg GPIO_AF_CAN1: Connect CAN1 pins to AF9
+  *            @arg GPIO_AF_CAN2: Connect CAN2 pins to AF9
+  *            @arg GPIO_AF_TIM12: Connect TIM12 pins to AF9
+  *            @arg GPIO_AF_TIM13: Connect TIM13 pins to AF9
+  *            @arg GPIO_AF_TIM14: Connect TIM14 pins to AF9
+  *            @arg GPIO_AF_OTG_FS: Connect OTG_FS pins to AF10
+  *            @arg GPIO_AF_OTG_HS: Connect OTG_HS pins to AF10
+  *            @arg GPIO_AF_ETH: Connect ETHERNET pins to AF11
+  *            @arg GPIO_AF_FSMC: Connect FSMC pins to AF12 
+  *            @arg GPIO_AF_FMC: Connect FMC pins to AF12 for STM32F42xxx/43xxx devices.   
+  *            @arg GPIO_AF_OTG_HS_FS: Connect OTG HS (configured in FS) pins to AF12
+  *            @arg GPIO_AF_SDIO: Connect SDIO pins to AF12
+  *            @arg GPIO_AF_DCMI: Connect DCMI pins to AF13
+  *            @arg GPIO_AF_LTDC: Connect LTDC pins to AF14 for STM32F429xx/439xx devices. 
+  *            @arg GPIO_AF_EVENTOUT: Connect EVENTOUT pins to AF15
+  * @retval None
+  */
+void GPIO_PinAFConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
+{
+  uint32_t temp = 0x00;
+  uint32_t temp_2 = 0x00;
+  
+  /* Check the parameters */
+  assert_param(IS_GPIO_ALL_PERIPH(GPIOx));
+  assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource));
+  assert_param(IS_GPIO_AF(GPIO_AF));
+  
+  temp = ((uint32_t)(GPIO_AF) << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)) ;
+  GPIOx->AFR[GPIO_PinSource >> 0x03] &= ~((uint32_t)0xF << ((uint32_t)((uint32_t)GPIO_PinSource & (uint32_t)0x07) * 4)) ;
+  temp_2 = GPIOx->AFR[GPIO_PinSource >> 0x03] | temp;
+  GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2;
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c
new file mode 100644
index 0000000000000000000000000000000000000000..04aec66e4c94c5c5d5c5622db88c3f3955876322
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash.c
@@ -0,0 +1,726 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_hash.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the HASH / HMAC Processor (HASH) peripheral:           
+  *           - Initialization and Configuration functions
+  *           - Message Digest generation functions
+  *           - context swapping functions   
+  *           - DMA interface function       
+  *           - Interrupts and flags management       
+  *         
+@verbatim
+ ===================================================================      
+                 ##### How to use this driver #####
+ ===================================================================
+            
+ *** HASH operation : *** 
+ ========================                 
+ [..]
+   (#) Enable the HASH controller clock using 
+       RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE) function.
+             
+   (#) Initialise the HASH using HASH_Init() function. 
+                 
+   (#) Reset the HASH processor core, so that the HASH will be ready 
+       to compute he message digest of a new message by using HASH_Reset() function.
+  
+   (#) Enable the HASH controller using the HASH_Cmd() function. 
+                  
+   (#) if using DMA for Data input transfer, Activate the DMA Request 
+       using HASH_DMACmd() function 
+                      
+   (#) if DMA is not used for data transfer, use HASH_DataIn() function 
+       to enter data to IN FIFO.
+               
+            
+   (#) Configure the Number of valid bits in last word of the message 
+       using HASH_SetLastWordValidBitsNbr() function.
+               
+   (#) if the message length is not an exact multiple of 512 bits, 
+       then the function HASH_StartDigest() must be called to launch the computation
+       of the final digest.     
+               
+   (#) Once computed, the digest can be read using HASH_GetDigest() function.         
+                     
+   (#) To control HASH events you can use one of the following wo methods:
+       (++) Check on HASH flags using the HASH_GetFlagStatus() function.  
+       (++) Use HASH interrupts through the function HASH_ITConfig() at 
+            initialization phase and HASH_GetITStatus() function into 
+            interrupt routines in hashing phase.
+            After checking on a flag you should clear it using HASH_ClearFlag()
+            function. And after checking on an interrupt event you should 
+            clear it using HASH_ClearITPendingBit() function.     
+                       
+   (#) Save and restore hash processor context using 
+       HASH_SaveContext() and HASH_RestoreContext() functions.     
+                
+  
+              
+ *** HMAC operation : *** 
+ ========================
+ [..] The HMAC algorithm is used for message authentication, by 
+      irreversibly binding the message being processed to a key chosen 
+      by the user. 
+      For HMAC specifications, refer to "HMAC: keyed-hashing for message 
+      authentication, H. Krawczyk, M. Bellare, R. Canetti, February 1997"
+            
+ [..] Basically, the HMAC algorithm consists of two nested hash operations:
+      HMAC(message) = Hash[((key | pad) XOR 0x5C) | Hash(((key | pad) XOR 0x36) | message)]
+      where:
+      (+) "pad" is a sequence of zeroes needed to extend the key to the 
+          length of the underlying hash function data block (that is 
+          512 bits for both the SHA-1 and MD5 hash algorithms)
+      (+) "|"   represents the concatenation operator 
+            
+           
+ [..]To compute the HMAC, four different phases are required:                  
+   (#) Initialise the HASH using HASH_Init() function to do HMAC 
+       operation. 
+                  
+   (#) The key (to be used for the inner hash function) is then given to the core. 
+       This operation follows the same mechanism as the one used to send the 
+       message in the hash operation (that is, by HASH_DataIn() function and, 
+       finally, HASH_StartDigest() function.
+            
+   (#) Once the last word has been entered and computation has started, 
+       the hash processor elaborates the key. It is then ready to accept the message
+       text using the same mechanism as the one used to send the message in the
+       hash operation.
+         
+   (#) After the first hash round, the hash processor returns "ready" to indicate 
+       that it is ready to receive the key to be used for the outer hash function 
+       (normally, this key is the same as the one used for the inner hash function). 
+       When the last word of the key is entered and computation starts, the HMAC 
+       result is made available using HASH_GetDigest() function.
+                                
+@endverbatim
+  *         
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_hash.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup HASH 
+  * @brief HASH driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/ 
+
+/** @defgroup HASH_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup HASH_Group1 Initialization and Configuration functions
+ *  @brief    Initialization and Configuration functions 
+ *
+@verbatim    
+ ===============================================================================
+              ##### Initialization and Configuration functions #####
+ ===============================================================================  
+ [..] This section provides functions allowing to 
+   (+) Initialize the HASH peripheral
+   (+) Configure the HASH Processor 
+   (+) MD5/SHA1, 
+   (+) HASH/HMAC, 
+   (+) datatype 
+   (+) HMAC Key (if mode = HMAC)
+   (+) Reset the HASH Processor 
+   
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  De-initializes the HASH peripheral registers to their default reset values
+  * @param  None
+  * @retval None
+  */
+void HASH_DeInit(void)
+{
+  /* Enable HASH reset state */
+  RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_HASH, ENABLE);
+  /* Release HASH from reset state */
+  RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_HASH, DISABLE);
+}
+
+/**
+  * @brief  Initializes the HASH peripheral according to the specified parameters
+  *         in the HASH_InitStruct structure.
+  * @note   the hash processor is reset when calling this function so that the
+  *         HASH will be ready to compute the message digest of a new message.
+  *         There is no need to call HASH_Reset() function.           
+  * @param  HASH_InitStruct: pointer to a HASH_InitTypeDef structure that contains
+  *         the configuration information for the HASH peripheral.
+  * @note   The field HASH_HMACKeyType in HASH_InitTypeDef must be filled only 
+  *          if the algorithm mode is HMAC.       
+  * @retval None
+  */
+void HASH_Init(HASH_InitTypeDef* HASH_InitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_HASH_ALGOSELECTION(HASH_InitStruct->HASH_AlgoSelection));
+  assert_param(IS_HASH_DATATYPE(HASH_InitStruct->HASH_DataType));
+  assert_param(IS_HASH_ALGOMODE(HASH_InitStruct->HASH_AlgoMode));
+  
+  /* Configure the Algorithm used, algorithm mode and the datatype */
+  HASH->CR &= ~ (HASH_CR_ALGO | HASH_CR_DATATYPE | HASH_CR_MODE);
+  HASH->CR |= (HASH_InitStruct->HASH_AlgoSelection | \
+               HASH_InitStruct->HASH_DataType | \
+               HASH_InitStruct->HASH_AlgoMode);
+  
+  /* if algorithm mode is HMAC, set the Key */  
+  if(HASH_InitStruct->HASH_AlgoMode == HASH_AlgoMode_HMAC) 
+  {
+    assert_param(IS_HASH_HMAC_KEYTYPE(HASH_InitStruct->HASH_HMACKeyType));
+    HASH->CR &= ~HASH_CR_LKEY;
+    HASH->CR |= HASH_InitStruct->HASH_HMACKeyType;
+  }
+
+  /* Reset the HASH processor core, so that the HASH will be ready to compute 
+     the message digest of a new message */
+  HASH->CR |= HASH_CR_INIT;  
+}
+
+/**
+  * @brief  Fills each HASH_InitStruct member with its default value.
+  * @param  HASH_InitStruct : pointer to a HASH_InitTypeDef structure which will
+  *          be initialized.  
+  *  @note  The default values set are : Processor mode is HASH, Algorithm selected is SHA1,
+  *          Data type selected is 32b and HMAC Key Type is short key.  
+  * @retval None
+  */
+void HASH_StructInit(HASH_InitTypeDef* HASH_InitStruct)
+{
+  /* Initialize the HASH_AlgoSelection member */
+  HASH_InitStruct->HASH_AlgoSelection = HASH_AlgoSelection_SHA1;
+
+  /* Initialize the HASH_AlgoMode member */
+  HASH_InitStruct->HASH_AlgoMode = HASH_AlgoMode_HASH;
+
+  /* Initialize the HASH_DataType member */
+  HASH_InitStruct->HASH_DataType = HASH_DataType_32b;
+
+  /* Initialize the HASH_HMACKeyType member */
+  HASH_InitStruct->HASH_HMACKeyType = HASH_HMACKeyType_ShortKey;
+}
+
+/**
+  * @brief  Resets the HASH processor core, so that the HASH will be ready
+  *         to compute the message digest of a new message.
+  * @note   Calling this function will clear the HASH_SR_DCIS (Digest calculation 
+  *         completion interrupt status) bit corresponding to HASH_IT_DCI 
+  *         interrupt and HASH_FLAG_DCIS flag. 
+  * @param  None
+  * @retval None
+  */
+void HASH_Reset(void)
+{
+  /* Reset the HASH processor core */
+  HASH->CR |= HASH_CR_INIT;
+}
+/**
+  * @}
+  */
+ 
+/** @defgroup HASH_Group2 Message Digest generation functions
+ *  @brief    Message Digest generation functions
+ *
+@verbatim    
+ ===============================================================================
+                  ##### Message Digest generation functions #####
+ ===============================================================================  
+ [..] This section provides functions allowing the generation of message digest: 
+   (+) Push data in the IN FIFO : using HASH_DataIn()
+   (+) Get the number of words set in IN FIFO, use HASH_GetInFIFOWordsNbr()  
+   (+) set the last word valid bits number using HASH_SetLastWordValidBitsNbr() 
+   (+) start digest calculation : using HASH_StartDigest()
+   (+) Get the Digest message : using HASH_GetDigest()
+ 
+@endverbatim
+  * @{
+  */
+
+
+/**
+  * @brief  Configure the Number of valid bits in last word of the message
+  * @param  ValidNumber: Number of valid bits in last word of the message.
+  *           This parameter must be a number between 0 and 0x1F.
+  *             - 0x00: All 32 bits of the last data written are valid
+  *             - 0x01: Only bit [0] of the last data written is valid
+  *             - 0x02: Only bits[1:0] of the last data written are valid
+  *             - 0x03: Only bits[2:0] of the last data written are valid
+  *             - ...
+  *             - 0x1F: Only bits[30:0] of the last data written are valid    
+  * @note   The Number of valid bits must be set before to start the message 
+  *         digest competition (in Hash and HMAC) and key treatment(in HMAC).    
+  * @retval None
+  */
+void HASH_SetLastWordValidBitsNbr(uint16_t ValidNumber)
+{
+  /* Check the parameters */
+  assert_param(IS_HASH_VALIDBITSNUMBER(ValidNumber));
+  
+  /* Configure the Number of valid bits in last word of the message */
+  HASH->STR &= ~(HASH_STR_NBW);
+  HASH->STR |= ValidNumber;
+}
+
+/**
+  * @brief  Writes data in the Data Input FIFO
+  * @param  Data: new data of the message to be processed.
+  * @retval None
+  */
+void HASH_DataIn(uint32_t Data)
+{
+  /* Write in the DIN register a new data */
+  HASH->DIN = Data;
+}
+
+/**
+  * @brief  Returns the number of words already pushed into the IN FIFO.
+  * @param  None
+  * @retval The value of words already pushed into the IN FIFO.
+  */
+uint8_t HASH_GetInFIFOWordsNbr(void)
+{
+  /* Return the value of NBW bits */
+  return ((HASH->CR & HASH_CR_NBW) >> 8);
+}
+
+/**
+  * @brief  Provides the message digest result.
+  * @note   In MD5 mode, Data[7] to Data[4] filed of HASH_MsgDigest structure is not used
+  *         and is read as zero.
+  *         In SHA-1 mode, Data[7] to Data[5] filed of HASH_MsgDigest structure is not used
+  *         and is read as zero.    
+  *         In SHA-224 mode, Data[7] filed of HASH_MsgDigest structure is not used
+  *         and is read as zero.  
+  * @param  HASH_MessageDigest: pointer to a HASH_MsgDigest structure which will 
+  *         hold the message digest result 
+  * @retval None
+  */
+void HASH_GetDigest(HASH_MsgDigest* HASH_MessageDigest)
+{
+  /* Get the data field */
+  HASH_MessageDigest->Data[0] = HASH->HR[0];
+  HASH_MessageDigest->Data[1] = HASH->HR[1];
+  HASH_MessageDigest->Data[2] = HASH->HR[2];
+  HASH_MessageDigest->Data[3] = HASH->HR[3];
+  HASH_MessageDigest->Data[4] = HASH->HR[4];
+  HASH_MessageDigest->Data[5] = HASH_DIGEST->HR[5];
+  HASH_MessageDigest->Data[6] = HASH_DIGEST->HR[6];
+  HASH_MessageDigest->Data[7] = HASH_DIGEST->HR[7];
+}
+
+/**
+  * @brief  Starts the message padding and calculation of the final message     
+  * @param  None
+  * @retval None
+  */
+void HASH_StartDigest(void)
+{
+  /* Start the Digest calculation */
+  HASH->STR |= HASH_STR_DCAL;
+}
+/**
+  * @}
+  */
+
+/** @defgroup HASH_Group3 Context swapping functions
+ *  @brief   Context swapping functions
+ *
+@verbatim   
+ ===============================================================================
+                      ##### Context swapping functions #####
+ ===============================================================================  
+ 
+ [..] This section provides functions allowing to save and store HASH Context
+  
+ [..] It is possible to interrupt a HASH/HMAC process to perform another processing 
+      with a higher priority, and to complete the interrupted process later on, when 
+      the higher priority task is complete. To do so, the context of the interrupted 
+      task must be saved from the HASH registers to memory, and then be restored 
+      from memory to the HASH registers.
+  
+   (#) To save the current context, use HASH_SaveContext() function
+   (#) To restore the saved context, use HASH_RestoreContext() function 
+  
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Save the Hash peripheral Context. 
+  * @note   The context can be saved only when no block is currently being 
+  *         processed. So user must wait for DINIS = 1 (the last block has been 
+  *         processed and the input FIFO is empty) or NBW != 0 (the FIFO is not 
+  *         full and no processing is ongoing).   
+  * @param  HASH_ContextSave: pointer to a HASH_Context structure that contains
+  *         the repository for current context.
+  * @retval None
+  */
+void HASH_SaveContext(HASH_Context* HASH_ContextSave)
+{
+  uint8_t i = 0;
+  
+  /* save context registers */
+  HASH_ContextSave->HASH_IMR = HASH->IMR;  
+  HASH_ContextSave->HASH_STR = HASH->STR;      
+  HASH_ContextSave->HASH_CR  = HASH->CR;     
+  for(i=0; i<=53;i++)
+  {
+     HASH_ContextSave->HASH_CSR[i] = HASH->CSR[i];
+  }   
+}
+
+/**
+  * @brief  Restore the Hash peripheral Context.  
+  * @note   After calling this function, user can restart the processing from the
+  *         point where it has been interrupted.  
+  * @param  HASH_ContextRestore: pointer to a HASH_Context structure that contains
+  *         the repository for saved context.
+  * @retval None
+  */
+void HASH_RestoreContext(HASH_Context* HASH_ContextRestore)  
+{
+  uint8_t i = 0;
+  
+  /* restore context registers */
+  HASH->IMR = HASH_ContextRestore->HASH_IMR;   
+  HASH->STR = HASH_ContextRestore->HASH_STR;     
+  HASH->CR = HASH_ContextRestore->HASH_CR;
+  
+  /* Initialize the hash processor */
+  HASH->CR |= HASH_CR_INIT; 
+  
+   /* continue restoring context registers */     
+  for(i=0; i<=53;i++)
+  {
+     HASH->CSR[i] = HASH_ContextRestore->HASH_CSR[i];
+  }   
+}
+/**
+  * @}
+  */
+
+/** @defgroup HASH_Group4 HASH's DMA interface Configuration function
+ *  @brief   HASH's DMA interface Configuration function 
+ *
+@verbatim   
+ ===============================================================================
+               ##### HASH's DMA interface Configuration function #####
+ ===============================================================================  
+
+ [..] This section provides functions allowing to configure the DMA interface for 
+      HASH/ HMAC data input transfer.
+   
+ [..] When the DMA mode is enabled (using the HASH_DMACmd() function), data can be 
+      sent to the IN FIFO using the DMA peripheral.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables auto-start message padding and
+  *         calculation of the final message digest at the end of DMA transfer.
+  * @param  NewState: new state of the selected HASH DMA transfer request.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void HASH_AutoStartDigest(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the auto start of the final message digest at the end of DMA transfer */
+    HASH->CR &= ~HASH_CR_MDMAT;
+  }
+  else
+  {
+    /* Disable the auto start of the final message digest at the end of DMA transfer */
+    HASH->CR |= HASH_CR_MDMAT;
+  }
+}
+  
+/**
+  * @brief  Enables or disables the HASH DMA interface.
+  * @note   The DMA is disabled by hardware after the end of transfer.
+  * @param  NewState: new state of the selected HASH DMA transfer request.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void HASH_DMACmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the HASH DMA request */
+    HASH->CR |= HASH_CR_DMAE;
+  }
+  else
+  {
+    /* Disable the HASH DMA request */
+    HASH->CR &= ~HASH_CR_DMAE;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup HASH_Group5 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+               ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+ [..] This section provides functions allowing to configure the HASH Interrupts and 
+      to get the status and clear flags and Interrupts pending bits.
+  
+ [..] The HASH provides 2 Interrupts sources and 5 Flags:
+  
+ *** Flags : ***
+ =============== 
+ [..]
+   (#) HASH_FLAG_DINIS : set when 16 locations are free in the Data IN FIFO 
+      which means that a  new block (512 bit) can be entered into the input buffer.
+                          
+   (#) HASH_FLAG_DCIS :  set when Digest calculation is complete
+      
+   (#) HASH_FLAG_DMAS :  set when HASH's DMA interface is enabled (DMAE=1) or 
+       a transfer is ongoing. This Flag is cleared only by hardware.
+                           
+   (#) HASH_FLAG_BUSY :  set when The hash core is processing a block of data
+       This Flag is cleared only by hardware. 
+                           
+   (#) HASH_FLAG_DINNE : set when Data IN FIFO is not empty which means that 
+       the Data IN FIFO contains at least one word of data. This Flag is cleared 
+       only by hardware.
+     
+ *** Interrupts : ***
+ ====================
+ [..]   
+   (#) HASH_IT_DINI  : if enabled, this interrupt source is pending when 16 
+       locations are free in the Data IN FIFO  which means that a new block (512 bit)
+       can be entered into the input buffer. This interrupt source is cleared using 
+       HASH_ClearITPendingBit(HASH_IT_DINI) function.
+   
+   (#) HASH_IT_DCI   : if enabled, this interrupt source is pending when Digest 
+       calculation is complete. This interrupt source is cleared using 
+       HASH_ClearITPendingBit(HASH_IT_DCI) function.
+
+ *** Managing the HASH controller events : ***
+ =============================================
+ [..] The user should identify which mode will be used in his application to manage 
+      the HASH controller events: Polling mode or Interrupt mode.
+  
+   (#) In the Polling Mode it is advised to use the following functions:
+       (++) HASH_GetFlagStatus() : to check if flags events occur. 
+       (++) HASH_ClearFlag()     : to clear the flags events.
+    
+   (#)  In the Interrupt Mode it is advised to use the following functions:
+       (++) HASH_ITConfig()       : to enable or disable the interrupt source.
+       (++) HASH_GetITStatus()    : to check if Interrupt occurs.
+       (++) HASH_ClearITPendingBit() : to clear the Interrupt pending Bit 
+            (corresponding Flag). 
+
+@endverbatim
+  * @{
+  */ 
+  
+/**
+  * @brief  Enables or disables the specified HASH interrupts.
+  * @param  HASH_IT: specifies the HASH interrupt source to be enabled or disabled.
+  *          This parameter can be any combination of the following values:
+  *            @arg HASH_IT_DINI: Data Input interrupt
+  *            @arg HASH_IT_DCI: Digest Calculation Completion Interrupt
+  * @param  NewState: new state of the specified HASH interrupt.
+  *           This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void HASH_ITConfig(uint32_t HASH_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_HASH_IT(HASH_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected HASH interrupt */
+    HASH->IMR |= HASH_IT;
+  }
+  else
+  {
+    /* Disable the selected HASH interrupt */
+    HASH->IMR &= (uint32_t)(~HASH_IT);
+  }
+}
+
+/**
+  * @brief  Checks whether the specified HASH flag is set or not.
+  * @param  HASH_FLAG: specifies the HASH flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg HASH_FLAG_DINIS: Data input interrupt status flag
+  *            @arg HASH_FLAG_DCIS: Digest calculation completion interrupt status flag
+  *            @arg HASH_FLAG_BUSY: Busy flag
+  *            @arg HASH_FLAG_DMAS: DMAS Status flag
+  *            @arg HASH_FLAG_DINNE: Data Input register (DIN) not empty status flag
+  * @retval The new state of HASH_FLAG (SET or RESET)
+  */
+FlagStatus HASH_GetFlagStatus(uint32_t HASH_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t tempreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_HASH_GET_FLAG(HASH_FLAG));
+
+  /* check if the FLAG is in CR register */
+  if ((HASH_FLAG & HASH_FLAG_DINNE) != (uint32_t)RESET ) 
+  {
+    tempreg = HASH->CR;
+  }
+  else /* The FLAG is in SR register */
+  {
+    tempreg = HASH->SR;
+  }
+
+  /* Check the status of the specified HASH flag */
+  if ((tempreg & HASH_FLAG) != (uint32_t)RESET)
+  {
+    /* HASH is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* HASH_FLAG is reset */
+    bitstatus = RESET;
+  }
+
+  /* Return the HASH_FLAG status */
+  return  bitstatus;
+}
+/**
+  * @brief  Clears the HASH flags.
+  * @param  HASH_FLAG: specifies the flag to clear. 
+  *          This parameter can be any combination of the following values:
+  *            @arg HASH_FLAG_DINIS: Data Input Flag
+  *            @arg HASH_FLAG_DCIS: Digest Calculation Completion Flag                       
+  * @retval None
+  */
+void HASH_ClearFlag(uint32_t HASH_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_HASH_CLEAR_FLAG(HASH_FLAG));
+  
+  /* Clear the selected HASH flags */
+  HASH->SR = ~(uint32_t)HASH_FLAG;
+}
+/**
+  * @brief  Checks whether the specified HASH interrupt has occurred or not.
+  * @param  HASH_IT: specifies the HASH interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg HASH_IT_DINI: Data Input interrupt
+  *            @arg HASH_IT_DCI: Digest Calculation Completion Interrupt
+  * @retval The new state of HASH_IT (SET or RESET).
+  */
+ITStatus HASH_GetITStatus(uint32_t HASH_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_HASH_GET_IT(HASH_IT));  
+
+
+  /* Check the status of the specified HASH interrupt */
+  tmpreg =  HASH->SR;
+
+  if (((HASH->IMR & tmpreg) & HASH_IT) != RESET)
+  {
+    /* HASH_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* HASH_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the HASH_IT status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the HASH interrupt pending bit(s).
+  * @param  HASH_IT: specifies the HASH interrupt pending bit(s) to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg HASH_IT_DINI: Data Input interrupt
+  *            @arg HASH_IT_DCI: Digest Calculation Completion Interrupt
+  * @retval None
+  */
+void HASH_ClearITPendingBit(uint32_t HASH_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_HASH_IT(HASH_IT));
+
+  /* Clear the selected HASH interrupt pending bit */
+  HASH->SR = (uint32_t)(~HASH_IT);
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c
new file mode 100644
index 0000000000000000000000000000000000000000..627804463cf221b0f811ea027b448421a09a98d1
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_md5.c
@@ -0,0 +1,320 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_hash_md5.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides high level functions to compute the HASH MD5 and
+  *          HMAC MD5 Digest of an input message.
+  *          It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH
+  *          peripheral.
+  *
+@verbatim
+ ===================================================================
+                  ##### How to use this driver #####
+ ===================================================================
+ [..]
+   (#) Enable The HASH controller clock using 
+       RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE); function.
+  
+   (#) Calculate the HASH MD5 Digest using HASH_MD5() function.
+  
+   (#) Calculate the HMAC MD5 Digest using HMAC_MD5() function.
+  
+@endverbatim
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_hash.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup HASH 
+  * @brief HASH driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define MD5BUSY_TIMEOUT    ((uint32_t) 0x00010000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup HASH_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup HASH_Group7 High Level MD5 functions
+ *  @brief   High Level MD5 Hash and HMAC functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### High Level MD5 Hash and HMAC functions #####
+ ===============================================================================
+
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Compute the HASH MD5 digest.
+  * @param  Input: pointer to the Input buffer to be treated.
+  * @param  Ilen: length of the Input buffer.
+  * @param  Output: the returned digest
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: digest computation done
+  *          - ERROR: digest computation failed
+  */
+ErrorStatus HASH_MD5(uint8_t *Input, uint32_t Ilen, uint8_t Output[16])
+{
+  HASH_InitTypeDef MD5_HASH_InitStructure;
+  HASH_MsgDigest MD5_MessageDigest;
+  __IO uint16_t nbvalidbitsdata = 0;
+  uint32_t i = 0;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+
+
+  /* Number of valid bits in last word of the Input data */
+  nbvalidbitsdata = 8 * (Ilen % 4);
+
+  /* HASH peripheral initialization */
+  HASH_DeInit();
+
+  /* HASH Configuration */
+  MD5_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_MD5;
+  MD5_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HASH;
+  MD5_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
+  HASH_Init(&MD5_HASH_InitStructure);
+
+  /* Configure the number of valid bits in last word of the data */
+  HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
+
+  /* Write the Input block in the IN FIFO */
+  for(i=0; i<Ilen; i+=4)
+  {
+    HASH_DataIn(*(uint32_t*)inputaddr);
+    inputaddr+=4;
+  }
+
+  /* Start the HASH processor */
+  HASH_StartDigest();
+
+  /* wait until the Busy flag is RESET */
+  do
+  {
+    busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+    counter++;
+  }while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
+
+  if (busystatus != RESET)
+  {
+     status = ERROR;
+  }
+  else
+  {
+    /* Read the message digest */
+    HASH_GetDigest(&MD5_MessageDigest);
+    *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[0]);
+    outputaddr+=4;
+    *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[1]);
+    outputaddr+=4;
+    *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[2]);
+    outputaddr+=4;
+    *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[3]);
+  }
+  return status; 
+}
+
+/**
+  * @brief  Compute the HMAC MD5 digest.
+  * @param  Key: pointer to the Key used for HMAC.
+  * @param  Keylen: length of the Key used for HMAC.
+  * @param  Input: pointer to the Input buffer to be treated.
+  * @param  Ilen: length of the Input buffer.
+  * @param  Output: the returned digest  
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: digest computation done
+  *          - ERROR: digest computation failed
+  */
+ErrorStatus HMAC_MD5(uint8_t *Key, uint32_t Keylen, uint8_t *Input, 
+                     uint32_t Ilen, uint8_t Output[16])
+{
+  HASH_InitTypeDef MD5_HASH_InitStructure;
+  HASH_MsgDigest MD5_MessageDigest;
+  __IO uint16_t nbvalidbitsdata = 0;
+  __IO uint16_t nbvalidbitskey = 0;
+  uint32_t i = 0;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+
+  /* Number of valid bits in last word of the Input data */
+  nbvalidbitsdata = 8 * (Ilen % 4);
+
+  /* Number of valid bits in last word of the Key */
+  nbvalidbitskey = 8 * (Keylen % 4);
+   
+  /* HASH peripheral initialization */
+  HASH_DeInit();
+
+  /* HASH Configuration */
+  MD5_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_MD5;
+  MD5_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HMAC;
+  MD5_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
+  if(Keylen > 64)
+  {
+    /* HMAC long Key */
+    MD5_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_LongKey;
+  }
+  else
+  {
+    /* HMAC short Key */
+    MD5_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_ShortKey;
+  }
+  HASH_Init(&MD5_HASH_InitStructure);
+
+  /* Configure the number of valid bits in last word of the Key */
+  HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
+
+  /* Write the Key */
+  for(i=0; i<Keylen; i+=4)
+  {
+    HASH_DataIn(*(uint32_t*)keyaddr);
+    keyaddr+=4;
+  }
+  
+  /* Start the HASH processor */
+  HASH_StartDigest();
+
+  /* wait until the Busy flag is RESET */
+  do
+  {
+    busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+    counter++;
+  }while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
+
+  if (busystatus != RESET)
+  {
+     status = ERROR;
+  }
+  else
+  {
+    /* Configure the number of valid bits in last word of the Input data */
+    HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
+
+    /* Write the Input block in the IN FIFO */
+    for(i=0; i<Ilen; i+=4)
+    {
+      HASH_DataIn(*(uint32_t*)inputaddr);
+      inputaddr+=4;
+    }
+
+    /* Start the HASH processor */
+    HASH_StartDigest();
+
+    /* wait until the Busy flag is RESET */
+    counter =0;
+    do
+    {
+       busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+       counter++;
+    }while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+    {
+      status = ERROR;
+    }
+    else
+    {  
+      /* Configure the number of valid bits in last word of the Key */
+      HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
+
+      /* Write the Key */
+      keyaddr = (uint32_t)Key;
+      for(i=0; i<Keylen; i+=4)
+      {
+        HASH_DataIn(*(uint32_t*)keyaddr);
+        keyaddr+=4;
+      }
+  
+       /* Start the HASH processor */
+       HASH_StartDigest();
+
+       /* wait until the Busy flag is RESET */
+       counter =0;
+       do
+       {
+          busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+          counter++;
+      }while ((counter != MD5BUSY_TIMEOUT) && (busystatus != RESET));
+
+      if (busystatus != RESET)
+      {
+         status = ERROR;
+      }
+      else
+      {
+         /* Read the message digest */
+         HASH_GetDigest(&MD5_MessageDigest);
+         *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[0]);
+         outputaddr+=4;
+         *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[1]);
+         outputaddr+=4;
+         *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[2]);
+         outputaddr+=4;
+         *(uint32_t*)(outputaddr)  = __REV(MD5_MessageDigest.Data[3]);
+      }
+    }
+  }
+  return status;  
+}
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_sha1.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_sha1.c
new file mode 100644
index 0000000000000000000000000000000000000000..4b0f392dbd90cb3299dbc1a1698dd8c1dd4bb23d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_hash_sha1.c
@@ -0,0 +1,323 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_hash_sha1.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides high level functions to compute the HASH SHA1 and
+  *          HMAC SHA1 Digest of an input message.
+  *          It uses the stm32f4xx_hash.c/.h drivers to access the STM32F4xx HASH
+  *          peripheral.
+  *
+@verbatim
+ ===================================================================
+                 ##### How to use this driver #####
+ ===================================================================
+ [..]
+   (#) Enable The HASH controller clock using 
+       RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_HASH, ENABLE); function.
+  
+   (#) Calculate the HASH SHA1 Digest using HASH_SHA1() function.
+  
+   (#) Calculate the HMAC SHA1 Digest using HMAC_SHA1() function.
+  
+@endverbatim
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_hash.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup HASH 
+  * @brief HASH driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define SHA1BUSY_TIMEOUT    ((uint32_t) 0x00010000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup HASH_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup HASH_Group6 High Level SHA1 functions
+ *  @brief   High Level SHA1 Hash and HMAC functions 
+ *
+@verbatim   
+ ===============================================================================
+               ##### High Level SHA1 Hash and HMAC functions #####
+ ===============================================================================
+
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Compute the HASH SHA1 digest.
+  * @param  Input: pointer to the Input buffer to be treated.
+  * @param  Ilen: length of the Input buffer.
+  * @param  Output: the returned digest
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: digest computation done
+  *          - ERROR: digest computation failed
+  */
+ErrorStatus HASH_SHA1(uint8_t *Input, uint32_t Ilen, uint8_t Output[20])
+{
+  HASH_InitTypeDef SHA1_HASH_InitStructure;
+  HASH_MsgDigest SHA1_MessageDigest;
+  __IO uint16_t nbvalidbitsdata = 0;
+  uint32_t i = 0;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+
+  /* Number of valid bits in last word of the Input data */
+  nbvalidbitsdata = 8 * (Ilen % 4);
+
+  /* HASH peripheral initialization */
+  HASH_DeInit();
+
+  /* HASH Configuration */
+  SHA1_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_SHA1;
+  SHA1_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HASH;
+  SHA1_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
+  HASH_Init(&SHA1_HASH_InitStructure);
+
+  /* Configure the number of valid bits in last word of the data */
+  HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
+
+  /* Write the Input block in the IN FIFO */
+  for(i=0; i<Ilen; i+=4)
+  {
+    HASH_DataIn(*(uint32_t*)inputaddr);
+    inputaddr+=4;
+  }
+
+  /* Start the HASH processor */
+  HASH_StartDigest();
+
+  /* wait until the Busy flag is RESET */
+  do
+  {
+    busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+    counter++;
+  }while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
+
+  if (busystatus != RESET)
+  {
+     status = ERROR;
+  }
+  else
+  {
+    /* Read the message digest */
+    HASH_GetDigest(&SHA1_MessageDigest);
+    *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[0]);
+    outputaddr+=4;
+    *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[1]);
+    outputaddr+=4;
+    *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[2]);
+    outputaddr+=4;
+    *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[3]);
+    outputaddr+=4;
+    *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[4]);
+  }
+  return status;
+}
+
+/**
+  * @brief  Compute the HMAC SHA1 digest.
+  * @param  Key: pointer to the Key used for HMAC.
+  * @param  Keylen: length of the Key used for HMAC.  
+  * @param  Input: pointer to the Input buffer to be treated.
+  * @param  Ilen: length of the Input buffer.
+  * @param  Output: the returned digest
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: digest computation done
+  *          - ERROR: digest computation failed
+  */
+ErrorStatus HMAC_SHA1(uint8_t *Key, uint32_t Keylen, uint8_t *Input,
+                      uint32_t Ilen, uint8_t Output[20])
+{
+  HASH_InitTypeDef SHA1_HASH_InitStructure;
+  HASH_MsgDigest SHA1_MessageDigest;
+  __IO uint16_t nbvalidbitsdata = 0;
+  __IO uint16_t nbvalidbitskey = 0;
+  uint32_t i = 0;
+  __IO uint32_t counter = 0;
+  uint32_t busystatus = 0;
+  ErrorStatus status = SUCCESS;
+  uint32_t keyaddr    = (uint32_t)Key;
+  uint32_t inputaddr  = (uint32_t)Input;
+  uint32_t outputaddr = (uint32_t)Output;
+
+  /* Number of valid bits in last word of the Input data */
+  nbvalidbitsdata = 8 * (Ilen % 4);
+
+  /* Number of valid bits in last word of the Key */
+  nbvalidbitskey = 8 * (Keylen % 4);
+
+  /* HASH peripheral initialization */
+  HASH_DeInit();
+
+  /* HASH Configuration */
+  SHA1_HASH_InitStructure.HASH_AlgoSelection = HASH_AlgoSelection_SHA1;
+  SHA1_HASH_InitStructure.HASH_AlgoMode = HASH_AlgoMode_HMAC;
+  SHA1_HASH_InitStructure.HASH_DataType = HASH_DataType_8b;
+  if(Keylen > 64)
+  {
+    /* HMAC long Key */
+    SHA1_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_LongKey;
+  }
+  else
+  {
+    /* HMAC short Key */
+    SHA1_HASH_InitStructure.HASH_HMACKeyType = HASH_HMACKeyType_ShortKey;
+  }
+  HASH_Init(&SHA1_HASH_InitStructure);
+
+  /* Configure the number of valid bits in last word of the Key */
+  HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
+
+  /* Write the Key */
+  for(i=0; i<Keylen; i+=4)
+  {
+    HASH_DataIn(*(uint32_t*)keyaddr);
+    keyaddr+=4;
+  }
+
+  /* Start the HASH processor */
+  HASH_StartDigest();
+
+  /* wait until the Busy flag is RESET */
+  do
+  {
+    busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+    counter++;
+  }while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
+
+  if (busystatus != RESET)
+  {
+     status = ERROR;
+  }
+  else
+  {
+    /* Configure the number of valid bits in last word of the Input data */
+    HASH_SetLastWordValidBitsNbr(nbvalidbitsdata);
+
+    /* Write the Input block in the IN FIFO */
+    for(i=0; i<Ilen; i+=4)
+    {
+      HASH_DataIn(*(uint32_t*)inputaddr);
+      inputaddr+=4;
+    }
+
+    /* Start the HASH processor */
+    HASH_StartDigest();
+
+
+    /* wait until the Busy flag is RESET */
+    counter =0;
+    do
+    {
+      busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+      counter++;
+    }while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
+
+    if (busystatus != RESET)
+    {
+      status = ERROR;
+    }
+    else
+    {  
+      /* Configure the number of valid bits in last word of the Key */
+      HASH_SetLastWordValidBitsNbr(nbvalidbitskey);
+
+      /* Write the Key */
+      keyaddr = (uint32_t)Key;
+      for(i=0; i<Keylen; i+=4)
+      {
+        HASH_DataIn(*(uint32_t*)keyaddr);
+        keyaddr+=4;
+      }
+
+      /* Start the HASH processor */
+      HASH_StartDigest();
+
+      /* wait until the Busy flag is RESET */
+      counter =0;
+      do
+      {
+        busystatus = HASH_GetFlagStatus(HASH_FLAG_BUSY);
+        counter++;
+      }while ((counter != SHA1BUSY_TIMEOUT) && (busystatus != RESET));
+
+      if (busystatus != RESET)
+      {
+        status = ERROR;
+      }
+      else
+      {
+        /* Read the message digest */
+        HASH_GetDigest(&SHA1_MessageDigest);
+        *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[0]);
+        outputaddr+=4;
+        *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[1]);
+        outputaddr+=4;
+        *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[2]);
+        outputaddr+=4;
+        *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[3]);
+        outputaddr+=4;
+        *(uint32_t*)(outputaddr)  = __REV(SHA1_MessageDigest.Data[4]);
+      }
+    }  
+  }
+  return status;  
+}
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c
new file mode 100644
index 0000000000000000000000000000000000000000..b0f8a32cb1756f69f8eef4f49246e15a8264867e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c
@@ -0,0 +1,1462 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_i2c.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Inter-integrated circuit (I2C)
+  *           + Initialization and Configuration
+  *           + Data transfers
+  *           + PEC management
+  *           + DMA transfers management
+  *           + Interrupts, events and flags management 
+  *           
+    @verbatim    
+ ===============================================================================
+                    ##### How to use this driver #####
+ ===============================================================================
+    [..]
+      (#) Enable peripheral clock using RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2Cx, ENABLE)
+          function for I2C1, I2C2 or I2C3.
+  
+      (#) Enable SDA, SCL  and SMBA (when used) GPIO clocks using 
+          RCC_AHBPeriphClockCmd() function. 
+  
+      (#) Peripherals alternate function: 
+        (++) Connect the pin to the desired peripherals' Alternate 
+             Function (AF) using GPIO_PinAFConfig() function
+        (++) Configure the desired pin in alternate function by:
+             GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
+        (++) Select the type, pull-up/pull-down and output speed via 
+             GPIO_PuPd, GPIO_OType and GPIO_Speed members
+        (++) Call GPIO_Init() function
+             Recommended configuration is Push-Pull, Pull-up, Open-Drain.
+             Add an external pull up if necessary (typically 4.7 KOhm).      
+          
+      (#) Program the Mode, duty cycle , Own address, Ack, Speed and Acknowledged
+          Address using the I2C_Init() function.
+  
+      (#) Optionally you can enable/configure the following parameters without
+          re-initialization (i.e there is no need to call again I2C_Init() function):
+        (++) Enable the acknowledge feature using I2C_AcknowledgeConfig() function
+        (++) Enable the dual addressing mode using I2C_DualAddressCmd() function
+        (++) Enable the general call using the I2C_GeneralCallCmd() function
+        (++) Enable the clock stretching using I2C_StretchClockCmd() function
+        (++) Enable the fast mode duty cycle using the I2C_FastModeDutyCycleConfig()
+             function.
+        (++) Configure the NACK position for Master Receiver mode in case of 
+             2 bytes reception using the function I2C_NACKPositionConfig().  
+        (++) Enable the PEC Calculation using I2C_CalculatePEC() function
+        (++) For SMBus Mode: 
+          (+++) Enable the Address Resolution Protocol (ARP) using I2C_ARPCmd() function
+          (+++) Configure the SMBusAlert pin using I2C_SMBusAlertConfig() function
+  
+      (#) Enable the NVIC and the corresponding interrupt using the function 
+          I2C_ITConfig() if you need to use interrupt mode. 
+  
+      (#) When using the DMA mode 
+        (++) Configure the DMA using DMA_Init() function
+        (++) Active the needed channel Request using I2C_DMACmd() or
+             I2C_DMALastTransferCmd() function.
+        -@@- When using DMA mode, I2C interrupts may be used at the same time to
+             control the communication flow (Start/Stop/Ack... events and errors).
+   
+      (#) Enable the I2C using the I2C_Cmd() function.
+   
+      (#) Enable the DMA using the DMA_Cmd() function when using DMA mode in the 
+          transfers. 
+  
+    @endverbatim  
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_i2c.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup I2C 
+  * @brief I2C driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+#define CR1_CLEAR_MASK    ((uint16_t)0xFBF5)      /*<! I2C registers Masks */
+#define FLAG_MASK         ((uint32_t)0x00FFFFFF)  /*<! I2C FLAG mask */
+#define ITEN_MASK         ((uint32_t)0x07000000)  /*<! I2C Interrupt Enable mask */
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup I2C_Private_Functions
+  * @{
+  */
+
+/** @defgroup I2C_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+            ##### Initialization and Configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitialize the I2Cx peripheral registers to their default reset values.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @retval None
+  */
+void I2C_DeInit(I2C_TypeDef* I2Cx)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+  if (I2Cx == I2C1)
+  {
+    /* Enable I2C1 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE);
+    /* Release I2C1 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE);    
+  }
+  else if (I2Cx == I2C2)
+  {
+    /* Enable I2C2 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE);
+    /* Release I2C2 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE);      
+  }
+  else 
+  {
+    if (I2Cx == I2C3)
+    {
+      /* Enable I2C3 reset state */
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C3, ENABLE);
+      /* Release I2C3 from reset state */
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C3, DISABLE);     
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the I2Cx peripheral according to the specified 
+  *         parameters in the I2C_InitStruct.
+  *           
+  * @note   To use the I2C at 400 KHz (in fast mode), the PCLK1 frequency 
+  *         (I2C peripheral input clock) must be a multiple of 10 MHz.  
+  *           
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_InitStruct: pointer to a I2C_InitTypeDef structure that contains 
+  *         the configuration information for the specified I2C peripheral.
+  * @retval None
+  */
+void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct)
+{
+  uint16_t tmpreg = 0, freqrange = 0;
+  uint16_t result = 0x04;
+  uint32_t pclk1 = 8000000;
+  RCC_ClocksTypeDef  rcc_clocks;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed));
+  assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode));
+  assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle));
+  assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1));
+  assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack));
+  assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress));
+
+/*---------------------------- I2Cx CR2 Configuration ------------------------*/
+  /* Get the I2Cx CR2 value */
+  tmpreg = I2Cx->CR2;
+  /* Clear frequency FREQ[5:0] bits */
+  tmpreg &= (uint16_t)~((uint16_t)I2C_CR2_FREQ);
+  /* Get pclk1 frequency value */
+  RCC_GetClocksFreq(&rcc_clocks);
+  pclk1 = rcc_clocks.PCLK1_Frequency;
+  /* Set frequency bits depending on pclk1 value */
+  freqrange = (uint16_t)(pclk1 / 1000000);
+  tmpreg |= freqrange;
+  /* Write to I2Cx CR2 */
+  I2Cx->CR2 = tmpreg;
+
+/*---------------------------- I2Cx CCR Configuration ------------------------*/
+  /* Disable the selected I2C peripheral to configure TRISE */
+  I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_PE);
+  /* Reset tmpreg value */
+  /* Clear F/S, DUTY and CCR[11:0] bits */
+  tmpreg = 0;
+
+  /* Configure speed in standard mode */
+  if (I2C_InitStruct->I2C_ClockSpeed <= 100000)
+  {
+    /* Standard mode speed calculate */
+    result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1));
+    /* Test if CCR value is under 0x4*/
+    if (result < 0x04)
+    {
+      /* Set minimum allowed value */
+      result = 0x04;  
+    }
+    /* Set speed value for standard mode */
+    tmpreg |= result;
+    /* Set Maximum Rise Time for standard mode */
+    I2Cx->TRISE = freqrange + 1; 
+  }
+  /* Configure speed in fast mode */
+  /* To use the I2C at 400 KHz (in fast mode), the PCLK1 frequency (I2C peripheral
+     input clock) must be a multiple of 10 MHz */
+  else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/
+  {
+    if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2)
+    {
+      /* Fast mode speed calculate: Tlow/Thigh = 2 */
+      result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3));
+    }
+    else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/
+    {
+      /* Fast mode speed calculate: Tlow/Thigh = 16/9 */
+      result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25));
+      /* Set DUTY bit */
+      result |= I2C_DutyCycle_16_9;
+    }
+
+    /* Test if CCR value is under 0x1*/
+    if ((result & I2C_CCR_CCR) == 0)
+    {
+      /* Set minimum allowed value */
+      result |= (uint16_t)0x0001;  
+    }
+    /* Set speed value and set F/S bit for fast mode */
+    tmpreg |= (uint16_t)(result | I2C_CCR_FS);
+    /* Set Maximum Rise Time for fast mode */
+    I2Cx->TRISE = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1);  
+  }
+
+  /* Write to I2Cx CCR */
+  I2Cx->CCR = tmpreg;
+  /* Enable the selected I2C peripheral */
+  I2Cx->CR1 |= I2C_CR1_PE;
+
+/*---------------------------- I2Cx CR1 Configuration ------------------------*/
+  /* Get the I2Cx CR1 value */
+  tmpreg = I2Cx->CR1;
+  /* Clear ACK, SMBTYPE and  SMBUS bits */
+  tmpreg &= CR1_CLEAR_MASK;
+  /* Configure I2Cx: mode and acknowledgement */
+  /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */
+  /* Set ACK bit according to I2C_Ack value */
+  tmpreg |= (uint16_t)((uint32_t)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack);
+  /* Write to I2Cx CR1 */
+  I2Cx->CR1 = tmpreg;
+
+/*---------------------------- I2Cx OAR1 Configuration -----------------------*/
+  /* Set I2Cx Own Address1 and acknowledged address */
+  I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1);
+}
+
+/**
+  * @brief  Fills each I2C_InitStruct member with its default value.
+  * @param  I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct)
+{
+/*---------------- Reset I2C init structure parameters values ----------------*/
+  /* initialize the I2C_ClockSpeed member */
+  I2C_InitStruct->I2C_ClockSpeed = 5000;
+  /* Initialize the I2C_Mode member */
+  I2C_InitStruct->I2C_Mode = I2C_Mode_I2C;
+  /* Initialize the I2C_DutyCycle member */
+  I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2;
+  /* Initialize the I2C_OwnAddress1 member */
+  I2C_InitStruct->I2C_OwnAddress1 = 0;
+  /* Initialize the I2C_Ack member */
+  I2C_InitStruct->I2C_Ack = I2C_Ack_Disable;
+  /* Initialize the I2C_AcknowledgedAddress member */
+  I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
+}
+
+/**
+  * @brief  Enables or disables the specified I2C peripheral.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx peripheral. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C peripheral */
+    I2Cx->CR1 |= I2C_CR1_PE;
+  }
+  else
+  {
+    /* Disable the selected I2C peripheral */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_PE);
+  }
+}
+
+/**
+  * @brief  Enables or disables the Analog filter of I2C peripheral.
+  * 
+  * @note   This function can be used only for STM32F42xxx/STM3243xxx and STM32F401xx devices.
+  *        
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the Analog filter. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @note   This function should be called before initializing and enabling
+            the I2C Peripheral.
+  * @retval None
+  */
+void I2C_AnalogFilterCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the analog filter */
+    I2Cx->FLTR &= (uint16_t)~((uint16_t)I2C_FLTR_ANOFF);    
+  }
+  else
+  {
+    /* Disable the analog filter */
+    I2Cx->FLTR |= I2C_FLTR_ANOFF;
+  }
+}
+
+/**
+  * @brief  Configures the Digital noise filter of I2C peripheral.
+  * 
+  * @note   This function can be used only for STM32F42xxx/STM3243xxx and STM32F401xx devices.
+  *       
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_DigitalFilter: Coefficient of digital noise filter. 
+  *          This parameter can be a number between 0x00 and 0x0F.
+  * @note   This function should be called before initializing and enabling
+            the I2C Peripheral.
+  * @retval None
+  */
+void I2C_DigitalFilterConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DigitalFilter)
+{
+  uint16_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_DIGITAL_FILTER(I2C_DigitalFilter));
+  
+  /* Get the old register value */
+  tmpreg = I2Cx->FLTR;
+  
+  /* Reset I2Cx DNF bit [3:0] */
+  tmpreg &= (uint16_t)~((uint16_t)I2C_FLTR_DNF);
+  
+  /* Set I2Cx DNF coefficient */
+  tmpreg |= (uint16_t)((uint16_t)I2C_DigitalFilter & I2C_FLTR_DNF);
+  
+  /* Store the new register value */
+  I2Cx->FLTR = tmpreg;
+}
+
+/**
+  * @brief  Generates I2Cx communication START condition.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C START condition generation.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Generate a START condition */
+    I2Cx->CR1 |= I2C_CR1_START;
+  }
+  else
+  {
+    /* Disable the START condition generation */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_START);
+  }
+}
+
+/**
+  * @brief  Generates I2Cx communication STOP condition.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C STOP condition generation.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Generate a STOP condition */
+    I2Cx->CR1 |= I2C_CR1_STOP;
+  }
+  else
+  {
+    /* Disable the STOP condition generation */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_STOP);
+  }
+}
+
+/**
+  * @brief  Transmits the address byte to select the slave device.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  Address: specifies the slave address which will be transmitted
+  * @param  I2C_Direction: specifies whether the I2C device will be a Transmitter
+  *         or a Receiver. 
+  *          This parameter can be one of the following values
+  *            @arg I2C_Direction_Transmitter: Transmitter mode
+  *            @arg I2C_Direction_Receiver: Receiver mode
+  * @retval None.
+  */
+void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_DIRECTION(I2C_Direction));
+  /* Test on the direction to set/reset the read/write bit */
+  if (I2C_Direction != I2C_Direction_Transmitter)
+  {
+    /* Set the address bit0 for read */
+    Address |= I2C_OAR1_ADD0;
+  }
+  else
+  {
+    /* Reset the address bit0 for write */
+    Address &= (uint8_t)~((uint8_t)I2C_OAR1_ADD0);
+  }
+  /* Send the address */
+  I2Cx->DR = Address;
+}
+
+/**
+  * @brief  Enables or disables the specified I2C acknowledge feature.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C Acknowledgement.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None.
+  */
+void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the acknowledgement */
+    I2Cx->CR1 |= I2C_CR1_ACK;
+  }
+  else
+  {
+    /* Disable the acknowledgement */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ACK);
+  }
+}
+
+/**
+  * @brief  Configures the specified I2C own address2.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  Address: specifies the 7bit I2C own address2.
+  * @retval None.
+  */
+void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address)
+{
+  uint16_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+  /* Get the old register value */
+  tmpreg = I2Cx->OAR2;
+
+  /* Reset I2Cx Own address2 bit [7:1] */
+  tmpreg &= (uint16_t)~((uint16_t)I2C_OAR2_ADD2);
+
+  /* Set I2Cx Own address2 */
+  tmpreg |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE);
+
+  /* Store the new register value */
+  I2Cx->OAR2 = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the specified I2C dual addressing mode.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C dual addressing mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable dual addressing mode */
+    I2Cx->OAR2 |= I2C_OAR2_ENDUAL;
+  }
+  else
+  {
+    /* Disable dual addressing mode */
+    I2Cx->OAR2 &= (uint16_t)~((uint16_t)I2C_OAR2_ENDUAL);
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C general call feature.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C General call.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable generall call */
+    I2Cx->CR1 |= I2C_CR1_ENGC;
+  }
+  else
+  {
+    /* Disable generall call */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ENGC);
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C software reset.
+  * @note   When software reset is enabled, the I2C IOs are released (this can
+  *         be useful to recover from bus errors).  
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C software reset.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Peripheral under reset */
+    I2Cx->CR1 |= I2C_CR1_SWRST;
+  }
+  else
+  {
+    /* Peripheral not under reset */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_SWRST);
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C Clock stretching.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx Clock stretching.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState == DISABLE)
+  {
+    /* Enable the selected I2C Clock stretching */
+    I2Cx->CR1 |= I2C_CR1_NOSTRETCH;
+  }
+  else
+  {
+    /* Disable the selected I2C Clock stretching */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_NOSTRETCH);
+  }
+}
+
+/**
+  * @brief  Selects the specified I2C fast mode duty cycle.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_DutyCycle: specifies the fast mode duty cycle.
+  *          This parameter can be one of the following values:
+  *            @arg I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2
+  *            @arg I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9
+  * @retval None
+  */
+void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle));
+  if (I2C_DutyCycle != I2C_DutyCycle_16_9)
+  {
+    /* I2C fast mode Tlow/Thigh=2 */
+    I2Cx->CCR &= I2C_DutyCycle_2;
+  }
+  else
+  {
+    /* I2C fast mode Tlow/Thigh=16/9 */
+    I2Cx->CCR |= I2C_DutyCycle_16_9;
+  }
+}
+
+/**
+  * @brief  Selects the specified I2C NACK position in master receiver mode.
+  * @note   This function is useful in I2C Master Receiver mode when the number
+  *         of data to be received is equal to 2. In this case, this function 
+  *         should be called (with parameter I2C_NACKPosition_Next) before data 
+  *         reception starts,as described in the 2-byte reception procedure 
+  *         recommended in Reference Manual in Section: Master receiver.                
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_NACKPosition: specifies the NACK position. 
+  *          This parameter can be one of the following values:
+  *            @arg I2C_NACKPosition_Next: indicates that the next byte will be the last
+  *                                        received byte.  
+  *            @arg I2C_NACKPosition_Current: indicates that current byte is the last 
+  *                                           received byte.
+  *            
+  * @note    This function configures the same bit (POS) as I2C_PECPositionConfig() 
+  *          but is intended to be used in I2C mode while I2C_PECPositionConfig() 
+  *          is intended to used in SMBUS mode. 
+  *            
+  * @retval None
+  */
+void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_NACK_POSITION(I2C_NACKPosition));
+  
+  /* Check the input parameter */
+  if (I2C_NACKPosition == I2C_NACKPosition_Next)
+  {
+    /* Next byte in shift register is the last received byte */
+    I2Cx->CR1 |= I2C_NACKPosition_Next;
+  }
+  else
+  {
+    /* Current byte in shift register is the last received byte */
+    I2Cx->CR1 &= I2C_NACKPosition_Current;
+  }
+}
+
+/**
+  * @brief  Drives the SMBusAlert pin high or low for the specified I2C.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_SMBusAlert: specifies SMBAlert pin level. 
+  *          This parameter can be one of the following values:
+  *            @arg I2C_SMBusAlert_Low: SMBAlert pin driven low
+  *            @arg I2C_SMBusAlert_High: SMBAlert pin driven high
+  * @retval None
+  */
+void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert));
+  if (I2C_SMBusAlert == I2C_SMBusAlert_Low)
+  {
+    /* Drive the SMBusAlert pin Low */
+    I2Cx->CR1 |= I2C_SMBusAlert_Low;
+  }
+  else
+  {
+    /* Drive the SMBusAlert pin High  */
+    I2Cx->CR1 &= I2C_SMBusAlert_High;
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified I2C ARP.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx ARP. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C ARP */
+    I2Cx->CR1 |= I2C_CR1_ENARP;
+  }
+  else
+  {
+    /* Disable the selected I2C ARP */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ENARP);
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Group2 Data transfers functions
+ *  @brief   Data transfers functions 
+ *
+@verbatim   
+ ===============================================================================
+                  ##### Data transfers functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Sends a data byte through the I2Cx peripheral.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  Data: Byte to be transmitted..
+  * @retval None
+  */
+void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  /* Write in the DR register the data to be sent */
+  I2Cx->DR = Data;
+}
+
+/**
+  * @brief  Returns the most recent received data by the I2Cx peripheral.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @retval The value of the received data.
+  */
+uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  /* Return the data in the DR register */
+  return (uint8_t)I2Cx->DR;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Group3 PEC management functions
+ *  @brief   PEC management functions 
+ *
+@verbatim   
+ ===============================================================================
+                  ##### PEC management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified I2C PEC transfer.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C PEC transmission.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C PEC transmission */
+    I2Cx->CR1 |= I2C_CR1_PEC;
+  }
+  else
+  {
+    /* Disable the selected I2C PEC transmission */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_PEC);
+  }
+}
+
+/**
+  * @brief  Selects the specified I2C PEC position.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_PECPosition: specifies the PEC position. 
+  *          This parameter can be one of the following values:
+  *            @arg I2C_PECPosition_Next: indicates that the next byte is PEC
+  *            @arg I2C_PECPosition_Current: indicates that current byte is PEC
+  *       
+  * @note    This function configures the same bit (POS) as I2C_NACKPositionConfig()
+  *          but is intended to be used in SMBUS mode while I2C_NACKPositionConfig() 
+  *          is intended to used in I2C mode.
+  *                
+  * @retval None
+  */
+void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition));
+  if (I2C_PECPosition == I2C_PECPosition_Next)
+  {
+    /* Next byte in shift register is PEC */
+    I2Cx->CR1 |= I2C_PECPosition_Next;
+  }
+  else
+  {
+    /* Current byte in shift register is PEC */
+    I2Cx->CR1 &= I2C_PECPosition_Current;
+  }
+}
+
+/**
+  * @brief  Enables or disables the PEC value calculation of the transferred bytes.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2Cx PEC value calculation.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C PEC calculation */
+    I2Cx->CR1 |= I2C_CR1_ENPEC;
+  }
+  else
+  {
+    /* Disable the selected I2C PEC calculation */
+    I2Cx->CR1 &= (uint16_t)~((uint16_t)I2C_CR1_ENPEC);
+  }
+}
+
+/**
+  * @brief  Returns the PEC value for the specified I2C.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @retval The PEC value.
+  */
+uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  /* Return the selected I2C PEC value */
+  return ((I2Cx->SR2) >> 8);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Group4 DMA transfers management functions
+ *  @brief   DMA transfers management functions 
+ *
+@verbatim   
+ ===============================================================================
+                ##### DMA transfers management functions #####
+ ===============================================================================  
+  This section provides functions allowing to configure the I2C DMA channels 
+  requests.
+  
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified I2C DMA requests.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C DMA transfer.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C DMA requests */
+    I2Cx->CR2 |= I2C_CR2_DMAEN;
+  }
+  else
+  {
+    /* Disable the selected I2C DMA requests */
+    I2Cx->CR2 &= (uint16_t)~((uint16_t)I2C_CR2_DMAEN);
+  }
+}
+
+/**
+  * @brief  Specifies that the next DMA transfer is the last one.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  NewState: new state of the I2C DMA last transfer.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Next DMA transfer is the last transfer */
+    I2Cx->CR2 |= I2C_CR2_LAST;
+  }
+  else
+  {
+    /* Next DMA transfer is not the last transfer */
+    I2Cx->CR2 &= (uint16_t)~((uint16_t)I2C_CR2_LAST);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup I2C_Group5 Interrupts events and flags management functions
+ *  @brief   Interrupts, events and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+          ##### Interrupts, events and flags management functions #####
+ ===============================================================================
+    [..]
+    This section provides functions allowing to configure the I2C Interrupts 
+    sources and check or clear the flags or pending bits status.
+    The user should identify which mode will be used in his application to manage 
+    the communication: Polling mode, Interrupt mode or DMA mode. 
+
+
+                ##### I2C State Monitoring Functions #####                   
+ =============================================================================== 
+    [..]  
+    This I2C driver provides three different ways for I2C state monitoring
+    depending on the application requirements and constraints:
+         
+   
+     (#) Basic state monitoring (Using I2C_CheckEvent() function)
+     
+        It compares the status registers (SR1 and SR2) content to a given event
+        (can be the combination of one or more flags).
+        It returns SUCCESS if the current status includes the given flags 
+        and returns ERROR if one or more flags are missing in the current status.
+
+          (++) When to use
+             (+++) This function is suitable for most applications as well as for startup 
+               activity since the events are fully described in the product reference 
+               manual (RM0090).
+             (+++) It is also suitable for users who need to define their own events.
+
+          (++) Limitations
+               If an error occurs (ie. error flags are set besides to the monitored 
+               flags), the I2C_CheckEvent() function may return SUCCESS despite 
+               the communication hold or corrupted real state. 
+               In this case, it is advised to use error interrupts to monitor 
+               the error events and handle them in the interrupt IRQ handler.
+         
+     -@@- For error management, it is advised to use the following functions:
+        (+@@) I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR).
+        (+@@) I2Cx_ER_IRQHandler() which is called when the error interrupt occurs.
+              Where x is the peripheral instance (I2C1, I2C2 ...)
+        (+@@) I2C_GetFlagStatus() or I2C_GetITStatus()  to be called into the 
+              I2Cx_ER_IRQHandler() function in order to determine which error occurred.
+        (+@@) I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() 
+              and/or I2C_GenerateStop() in order to clear the error flag and source 
+              and return to correct  communication status.
+             
+ 
+     (#) Advanced state monitoring (Using the function I2C_GetLastEvent())
+
+        Using the function I2C_GetLastEvent() which returns the image of both status 
+        registers in a single word (uint32_t) (Status Register 2 value is shifted left 
+        by 16 bits and concatenated to Status Register 1).
+
+          (++) When to use
+             (+++) This function is suitable for the same applications above but it 
+               allows to overcome the mentioned limitation of I2C_GetFlagStatus() 
+               function.
+             (+++) The returned value could be compared to events already defined in 
+               the library (stm32f4xx_i2c.h) or to custom values defined by user.
+               This function is suitable when multiple flags are monitored at the 
+               same time.
+             (+++) At the opposite of I2C_CheckEvent() function, this function allows 
+               user to choose when an event is accepted (when all events flags are 
+               set and no other flags are set or just when the needed flags are set 
+               like I2C_CheckEvent() function.
+
+          (++) Limitations
+             (+++) User may need to define his own events.
+             (+++) Same remark concerning the error management is applicable for this 
+               function if user decides to check only regular communication flags 
+               (and ignores error flags).
+      
+ 
+     (#) Flag-based state monitoring (Using the function I2C_GetFlagStatus())
+     
+      Using the function I2C_GetFlagStatus() which simply returns the status of 
+      one single flag (ie. I2C_FLAG_RXNE ...). 
+
+          (++) When to use
+             (+++) This function could be used for specific applications or in debug 
+               phase.
+             (+++) It is suitable when only one flag checking is needed (most I2C 
+               events are monitored through multiple flags).
+          (++) Limitations: 
+             (+++) When calling this function, the Status register is accessed. 
+               Some flags are cleared when the status register is accessed. 
+               So checking the status of one Flag, may clear other ones.
+             (+++) Function may need to be called twice or more in order to monitor 
+               one single event.
+ 
+   For detailed description of Events, please refer to section I2C_Events in 
+   stm32f4xx_i2c.h file.
+       
+@endverbatim
+  * @{
+  */
+   
+/**
+  * @brief  Reads the specified I2C register and returns its value.
+  * @param  I2C_Register: specifies the register to read.
+  *          This parameter can be one of the following values:
+  *            @arg I2C_Register_CR1:  CR1 register.
+  *            @arg I2C_Register_CR2:   CR2 register.
+  *            @arg I2C_Register_OAR1:  OAR1 register.
+  *            @arg I2C_Register_OAR2:  OAR2 register.
+  *            @arg I2C_Register_DR:    DR register.
+  *            @arg I2C_Register_SR1:   SR1 register.
+  *            @arg I2C_Register_SR2:   SR2 register.
+  *            @arg I2C_Register_CCR:   CCR register.
+  *            @arg I2C_Register_TRISE: TRISE register.
+  * @retval The value of the read register.
+  */
+uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_REGISTER(I2C_Register));
+
+  tmp = (uint32_t) I2Cx;
+  tmp += I2C_Register;
+
+  /* Return the selected register value */
+  return (*(__IO uint16_t *) tmp);
+}
+
+/**
+  * @brief  Enables or disables the specified I2C interrupts.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. 
+  *          This parameter can be any combination of the following values:
+  *            @arg I2C_IT_BUF: Buffer interrupt mask
+  *            @arg I2C_IT_EVT: Event interrupt mask
+  *            @arg I2C_IT_ERR: Error interrupt mask
+  * @param  NewState: new state of the specified I2C interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_I2C_CONFIG_IT(I2C_IT));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected I2C interrupts */
+    I2Cx->CR2 |= I2C_IT;
+  }
+  else
+  {
+    /* Disable the selected I2C interrupts */
+    I2Cx->CR2 &= (uint16_t)~I2C_IT;
+  }
+}
+
+/*
+ ===============================================================================
+                          1. Basic state monitoring                    
+ ===============================================================================  
+ */
+
+/**
+  * @brief  Checks whether the last I2Cx Event is equal to the one passed
+  *         as parameter.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_EVENT: specifies the event to be checked. 
+  *          This parameter can be one of the following values:
+  *            @arg I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED: EV1
+  *            @arg I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED: EV1
+  *            @arg I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED: EV1
+  *            @arg I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED: EV1
+  *            @arg I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED: EV1
+  *            @arg I2C_EVENT_SLAVE_BYTE_RECEIVED: EV2
+  *            @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF): EV2
+  *            @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL): EV2
+  *            @arg I2C_EVENT_SLAVE_BYTE_TRANSMITTED: EV3
+  *            @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF): EV3
+  *            @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL): EV3
+  *            @arg I2C_EVENT_SLAVE_ACK_FAILURE: EV3_2
+  *            @arg I2C_EVENT_SLAVE_STOP_DETECTED: EV4
+  *            @arg I2C_EVENT_MASTER_MODE_SELECT: EV5
+  *            @arg I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED: EV6     
+  *            @arg I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED: EV6
+  *            @arg I2C_EVENT_MASTER_BYTE_RECEIVED: EV7
+  *            @arg I2C_EVENT_MASTER_BYTE_TRANSMITTING: EV8
+  *            @arg I2C_EVENT_MASTER_BYTE_TRANSMITTED: EV8_2
+  *            @arg I2C_EVENT_MASTER_MODE_ADDRESS10: EV9
+  *     
+  * @note   For detailed description of Events, please refer to section I2C_Events
+  *         in stm32f4xx_i2c.h file.
+  *    
+  * @retval An ErrorStatus enumeration value:
+  *           - SUCCESS: Last event is equal to the I2C_EVENT
+  *           - ERROR: Last event is different from the I2C_EVENT
+  */
+ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT)
+{
+  uint32_t lastevent = 0;
+  uint32_t flag1 = 0, flag2 = 0;
+  ErrorStatus status = ERROR;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_EVENT(I2C_EVENT));
+
+  /* Read the I2Cx status register */
+  flag1 = I2Cx->SR1;
+  flag2 = I2Cx->SR2;
+  flag2 = flag2 << 16;
+
+  /* Get the last event value from I2C status register */
+  lastevent = (flag1 | flag2) & FLAG_MASK;
+
+  /* Check whether the last event contains the I2C_EVENT */
+  if ((lastevent & I2C_EVENT) == I2C_EVENT)
+  {
+    /* SUCCESS: last event is equal to I2C_EVENT */
+    status = SUCCESS;
+  }
+  else
+  {
+    /* ERROR: last event is different from I2C_EVENT */
+    status = ERROR;
+  }
+  /* Return status */
+  return status;
+}
+
+/*
+ ===============================================================================
+                          2. Advanced state monitoring                   
+ ===============================================================================  
+ */
+
+/**
+  * @brief  Returns the last I2Cx Event.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  *     
+  * @note   For detailed description of Events, please refer to section I2C_Events
+  *         in stm32f4xx_i2c.h file.
+  *    
+  * @retval The last event
+  */
+uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx)
+{
+  uint32_t lastevent = 0;
+  uint32_t flag1 = 0, flag2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+
+  /* Read the I2Cx status register */
+  flag1 = I2Cx->SR1;
+  flag2 = I2Cx->SR2;
+  flag2 = flag2 << 16;
+
+  /* Get the last event value from I2C status register */
+  lastevent = (flag1 | flag2) & FLAG_MASK;
+
+  /* Return status */
+  return lastevent;
+}
+
+/*
+ ===============================================================================
+                          3. Flag-based state monitoring                   
+ ===============================================================================  
+ */
+
+/**
+  * @brief  Checks whether the specified I2C flag is set or not.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_FLAG: specifies the flag to check. 
+  *          This parameter can be one of the following values:
+  *            @arg I2C_FLAG_DUALF: Dual flag (Slave mode)
+  *            @arg I2C_FLAG_SMBHOST: SMBus host header (Slave mode)
+  *            @arg I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode)
+  *            @arg I2C_FLAG_GENCALL: General call header flag (Slave mode)
+  *            @arg I2C_FLAG_TRA: Transmitter/Receiver flag
+  *            @arg I2C_FLAG_BUSY: Bus busy flag
+  *            @arg I2C_FLAG_MSL: Master/Slave flag
+  *            @arg I2C_FLAG_SMBALERT: SMBus Alert flag
+  *            @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+  *            @arg I2C_FLAG_PECERR: PEC error in reception flag
+  *            @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+  *            @arg I2C_FLAG_AF: Acknowledge failure flag
+  *            @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+  *            @arg I2C_FLAG_BERR: Bus error flag
+  *            @arg I2C_FLAG_TXE: Data register empty flag (Transmitter)
+  *            @arg I2C_FLAG_RXNE: Data register not empty (Receiver) flag
+  *            @arg I2C_FLAG_STOPF: Stop detection flag (Slave mode)
+  *            @arg I2C_FLAG_ADD10: 10-bit header sent flag (Master mode)
+  *            @arg I2C_FLAG_BTF: Byte transfer finished flag
+  *            @arg I2C_FLAG_ADDR: Address sent flag (Master mode) "ADSL"
+  *                                Address matched flag (Slave mode)"ENDAD"
+  *            @arg I2C_FLAG_SB: Start bit flag (Master mode)
+  * @retval The new state of I2C_FLAG (SET or RESET).
+  */
+FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  __IO uint32_t i2creg = 0, i2cxbase = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_GET_FLAG(I2C_FLAG));
+
+  /* Get the I2Cx peripheral base address */
+  i2cxbase = (uint32_t)I2Cx;
+  
+  /* Read flag register index */
+  i2creg = I2C_FLAG >> 28;
+  
+  /* Get bit[23:0] of the flag */
+  I2C_FLAG &= FLAG_MASK;
+  
+  if(i2creg != 0)
+  {
+    /* Get the I2Cx SR1 register address */
+    i2cxbase += 0x14;
+  }
+  else
+  {
+    /* Flag in I2Cx SR2 Register */
+    I2C_FLAG = (uint32_t)(I2C_FLAG >> 16);
+    /* Get the I2Cx SR2 register address */
+    i2cxbase += 0x18;
+  }
+  
+  if(((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET)
+  {
+    /* I2C_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* I2C_FLAG is reset */
+    bitstatus = RESET;
+  }
+  
+  /* Return the I2C_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the I2Cx's pending flags.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_FLAG: specifies the flag to clear. 
+  *          This parameter can be any combination of the following values:
+  *            @arg I2C_FLAG_SMBALERT: SMBus Alert flag
+  *            @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag
+  *            @arg I2C_FLAG_PECERR: PEC error in reception flag
+  *            @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode)
+  *            @arg I2C_FLAG_AF: Acknowledge failure flag
+  *            @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode)
+  *            @arg I2C_FLAG_BERR: Bus error flag
+  *   
+  * @note   STOPF (STOP detection) is cleared by software sequence: a read operation 
+  *          to I2C_SR1 register (I2C_GetFlagStatus()) followed by a write operation 
+  *          to I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral).
+  * @note   ADD10 (10-bit header sent) is cleared by software sequence: a read 
+  *          operation to I2C_SR1 (I2C_GetFlagStatus()) followed by writing the 
+  *          second byte of the address in DR register.
+  * @note   BTF (Byte Transfer Finished) is cleared by software sequence: a read 
+  *          operation to I2C_SR1 register (I2C_GetFlagStatus()) followed by a 
+  *          read/write to I2C_DR register (I2C_SendData()).
+  * @note   ADDR (Address sent) is cleared by software sequence: a read operation to 
+  *          I2C_SR1 register (I2C_GetFlagStatus()) followed by a read operation to 
+  *          I2C_SR2 register ((void)(I2Cx->SR2)).
+  * @note   SB (Start Bit) is cleared software sequence: a read operation to I2C_SR1
+  *          register (I2C_GetFlagStatus()) followed by a write operation to I2C_DR
+  *          register (I2C_SendData()).
+  *  
+  * @retval None
+  */
+void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG)
+{
+  uint32_t flagpos = 0;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG));
+  /* Get the I2C flag position */
+  flagpos = I2C_FLAG & FLAG_MASK;
+  /* Clear the selected I2C flag */
+  I2Cx->SR1 = (uint16_t)~flagpos;
+}
+
+/**
+  * @brief  Checks whether the specified I2C interrupt has occurred or not.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_IT: specifies the interrupt source to check. 
+  *          This parameter can be one of the following values:
+  *            @arg I2C_IT_SMBALERT: SMBus Alert flag
+  *            @arg I2C_IT_TIMEOUT: Timeout or Tlow error flag
+  *            @arg I2C_IT_PECERR: PEC error in reception flag
+  *            @arg I2C_IT_OVR: Overrun/Underrun flag (Slave mode)
+  *            @arg I2C_IT_AF: Acknowledge failure flag
+  *            @arg I2C_IT_ARLO: Arbitration lost flag (Master mode)
+  *            @arg I2C_IT_BERR: Bus error flag
+  *            @arg I2C_IT_TXE: Data register empty flag (Transmitter)
+  *            @arg I2C_IT_RXNE: Data register not empty (Receiver) flag
+  *            @arg I2C_IT_STOPF: Stop detection flag (Slave mode)
+  *            @arg I2C_IT_ADD10: 10-bit header sent flag (Master mode)
+  *            @arg I2C_IT_BTF: Byte transfer finished flag
+  *            @arg I2C_IT_ADDR: Address sent flag (Master mode) "ADSL"
+  *                              Address matched flag (Slave mode)"ENDAD"
+  *            @arg I2C_IT_SB: Start bit flag (Master mode)
+  * @retval The new state of I2C_IT (SET or RESET).
+  */
+ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t enablestatus = 0;
+
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_GET_IT(I2C_IT));
+
+  /* Check if the interrupt source is enabled or not */
+  enablestatus = (uint32_t)(((I2C_IT & ITEN_MASK) >> 16) & (I2Cx->CR2)) ;
+  
+  /* Get bit[23:0] of the flag */
+  I2C_IT &= FLAG_MASK;
+
+  /* Check the status of the specified I2C flag */
+  if (((I2Cx->SR1 & I2C_IT) != (uint32_t)RESET) && enablestatus)
+  {
+    /* I2C_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* I2C_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the I2C_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the I2Cx's interrupt pending bits.
+  * @param  I2Cx: where x can be 1, 2 or 3 to select the I2C peripheral.
+  * @param  I2C_IT: specifies the interrupt pending bit to clear. 
+  *          This parameter can be any combination of the following values:
+  *            @arg I2C_IT_SMBALERT: SMBus Alert interrupt
+  *            @arg I2C_IT_TIMEOUT: Timeout or Tlow error interrupt
+  *            @arg I2C_IT_PECERR: PEC error in reception  interrupt
+  *            @arg I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode)
+  *            @arg I2C_IT_AF: Acknowledge failure interrupt
+  *            @arg I2C_IT_ARLO: Arbitration lost interrupt (Master mode)
+  *            @arg I2C_IT_BERR: Bus error interrupt
+  * 
+  * @note   STOPF (STOP detection) is cleared by software sequence: a read operation 
+  *          to I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to 
+  *          I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral).
+  * @note   ADD10 (10-bit header sent) is cleared by software sequence: a read 
+  *          operation to I2C_SR1 (I2C_GetITStatus()) followed by writing the second 
+  *          byte of the address in I2C_DR register.
+  * @note   BTF (Byte Transfer Finished) is cleared by software sequence: a read 
+  *          operation to I2C_SR1 register (I2C_GetITStatus()) followed by a 
+  *          read/write to I2C_DR register (I2C_SendData()).
+  * @note   ADDR (Address sent) is cleared by software sequence: a read operation to 
+  *          I2C_SR1 register (I2C_GetITStatus()) followed by a read operation to 
+  *          I2C_SR2 register ((void)(I2Cx->SR2)).
+  * @note   SB (Start Bit) is cleared by software sequence: a read operation to 
+  *          I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to 
+  *          I2C_DR register (I2C_SendData()).
+  * @retval None
+  */
+void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT)
+{
+  uint32_t flagpos = 0;
+  /* Check the parameters */
+  assert_param(IS_I2C_ALL_PERIPH(I2Cx));
+  assert_param(IS_I2C_CLEAR_IT(I2C_IT));
+
+  /* Get the I2C flag position */
+  flagpos = I2C_IT & FLAG_MASK;
+
+  /* Clear the selected I2C flag */
+  I2Cx->SR1 = (uint16_t)~flagpos;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c
new file mode 100644
index 0000000000000000000000000000000000000000..43de75eb0d7b555588bf5d264e7e0cb6ebe039fa
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_iwdg.c
@@ -0,0 +1,266 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_iwdg.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Independent watchdog (IWDG) peripheral:           
+  *           + Prescaler and Counter configuration
+  *           + IWDG activation
+  *           + Flag management
+  *
+    @verbatim    
+ ===============================================================================
+                          ##### IWDG features #####
+ ===============================================================================
+    [..]  
+      The IWDG can be started by either software or hardware (configurable
+      through option byte).
+              
+      The IWDG is clocked by its own dedicated low-speed clock (LSI) and
+      thus stays active even if the main clock fails.
+      Once the IWDG is started, the LSI is forced ON and cannot be disabled
+      (LSI cannot be disabled too), and the counter starts counting down from 
+      the reset value of 0xFFF. When it reaches the end of count value (0x000)
+      a system reset is generated.
+      The IWDG counter should be reloaded at regular intervals to prevent
+      an MCU reset.
+                             
+      The IWDG is implemented in the VDD voltage domain that is still functional
+      in STOP and STANDBY mode (IWDG reset can wake-up from STANDBY).          
+              
+      IWDGRST flag in RCC_CSR register can be used to inform when a IWDG
+      reset occurs.
+              
+      Min-max timeout value @32KHz (LSI): ~125us / ~32.7s
+      The IWDG timeout may vary due to LSI frequency dispersion. STM32F4xx
+      devices provide the capability to measure the LSI frequency (LSI clock
+      connected internally to TIM5 CH4 input capture). The measured value
+      can be used to have an IWDG timeout with an acceptable accuracy. 
+      For more information, please refer to the STM32F4xx Reference manual
+            
+                     ##### How to use this driver #####
+ ===============================================================================
+    [..]
+      (#) Enable write access to IWDG_PR and IWDG_RLR registers using
+          IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable) function
+                 
+      (#) Configure the IWDG prescaler using IWDG_SetPrescaler() function
+              
+      (#) Configure the IWDG counter value using IWDG_SetReload() function.
+          This value will be loaded in the IWDG counter each time the counter
+          is reloaded, then the IWDG will start counting down from this value.
+              
+      (#) Start the IWDG using IWDG_Enable() function, when the IWDG is used
+          in software mode (no need to enable the LSI, it will be enabled
+          by hardware)
+               
+      (#) Then the application program must reload the IWDG counter at regular
+          intervals during normal operation to prevent an MCU reset, using
+          IWDG_ReloadCounter() function.      
+            
+    @endverbatim    
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_iwdg.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup IWDG 
+  * @brief IWDG driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* KR register bit mask */
+#define KR_KEY_RELOAD    ((uint16_t)0xAAAA)
+#define KR_KEY_ENABLE    ((uint16_t)0xCCCC)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup IWDG_Private_Functions
+  * @{
+  */
+
+/** @defgroup IWDG_Group1 Prescaler and Counter configuration functions
+ *  @brief   Prescaler and Counter configuration functions
+ *
+@verbatim   
+ ===============================================================================
+              ##### Prescaler and Counter configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables write access to IWDG_PR and IWDG_RLR registers.
+  * @param  IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers.
+  *          This parameter can be one of the following values:
+  *            @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers
+  *            @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers
+  * @retval None
+  */
+void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess)
+{
+  /* Check the parameters */
+  assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess));
+  IWDG->KR = IWDG_WriteAccess;
+}
+
+/**
+  * @brief  Sets IWDG Prescaler value.
+  * @param  IWDG_Prescaler: specifies the IWDG Prescaler value.
+  *          This parameter can be one of the following values:
+  *            @arg IWDG_Prescaler_4: IWDG prescaler set to 4
+  *            @arg IWDG_Prescaler_8: IWDG prescaler set to 8
+  *            @arg IWDG_Prescaler_16: IWDG prescaler set to 16
+  *            @arg IWDG_Prescaler_32: IWDG prescaler set to 32
+  *            @arg IWDG_Prescaler_64: IWDG prescaler set to 64
+  *            @arg IWDG_Prescaler_128: IWDG prescaler set to 128
+  *            @arg IWDG_Prescaler_256: IWDG prescaler set to 256
+  * @retval None
+  */
+void IWDG_SetPrescaler(uint8_t IWDG_Prescaler)
+{
+  /* Check the parameters */
+  assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler));
+  IWDG->PR = IWDG_Prescaler;
+}
+
+/**
+  * @brief  Sets IWDG Reload value.
+  * @param  Reload: specifies the IWDG Reload value.
+  *          This parameter must be a number between 0 and 0x0FFF.
+  * @retval None
+  */
+void IWDG_SetReload(uint16_t Reload)
+{
+  /* Check the parameters */
+  assert_param(IS_IWDG_RELOAD(Reload));
+  IWDG->RLR = Reload;
+}
+
+/**
+  * @brief  Reloads IWDG counter with value defined in the reload register
+  *         (write access to IWDG_PR and IWDG_RLR registers disabled).
+  * @param  None
+  * @retval None
+  */
+void IWDG_ReloadCounter(void)
+{
+  IWDG->KR = KR_KEY_RELOAD;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Group2 IWDG activation function
+ *  @brief   IWDG activation function 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### IWDG activation function #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled).
+  * @param  None
+  * @retval None
+  */
+void IWDG_Enable(void)
+{
+  IWDG->KR = KR_KEY_ENABLE;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup IWDG_Group3 Flag management function 
+ *  @brief  Flag management function  
+ *
+@verbatim   
+ ===============================================================================
+                    ##### Flag management function #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Checks whether the specified IWDG flag is set or not.
+  * @param  IWDG_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg IWDG_FLAG_PVU: Prescaler Value Update on going
+  *            @arg IWDG_FLAG_RVU: Reload Value Update on going
+  * @retval The new state of IWDG_FLAG (SET or RESET).
+  */
+FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_IWDG_FLAG(IWDG_FLAG));
+  if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_ltdc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_ltdc.c
new file mode 100644
index 0000000000000000000000000000000000000000..e321ae1a4d4d8d5b2fb2c3f66fc9625aba67974f
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_ltdc.c
@@ -0,0 +1,1104 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_ltdc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the LTDC controller (LTDC) peripheral:
+  *           + Initialization and configuration
+  *           + Interrupts and flags management
+  *           
+  *  @verbatim
+  
+ ===============================================================================
+                      ##### How to use this driver #####
+ ===============================================================================
+    [..]
+        (#) Enable LTDC clock using 
+            RCC_APB2PeriphResetCmd(RCC_APB2Periph_LTDC, ENABLE) function.
+        (#) Configures LTDC
+          (++) Configure the required Pixel clock following the panel datasheet
+          (++) Configure the Synchronous timings: VSYNC, HSYNC, Vertical and 
+              Horizontal back proch, active data area and the front proch 
+              timings 
+          (++) Configure the synchronous signals and clock polarity in the 
+              LTDC_GCR register
+        (#) Configures Layer1/2 parameters
+          (++) The Layer window horizontal and vertical position in the LTDC_LxWHPCR and 
+               LTDC_WVPCR registers. The layer window must be in the active data area.
+          (++) The pixel input format in the LTDC_LxPFCR register
+          (++) The color frame buffer start address in the LTDC_LxCFBAR register
+          (++) The line length and pitch of the color frame buffer in the 
+               LTDC_LxCFBLR register
+          (++) The number of lines of the color frame buffer in 
+               the LTDC_LxCFBLNR register
+          (++) if needed, load the CLUT with the RGB values and the address 
+               in the LTDC_LxCLUTWR register
+          (++) If needed, configure the default color and the blending factors 
+               respectively in the LTDC_LxDCCR and LTDC_LxBFCR registers 
+
+          (++) If needed, Dithering and color keying can be be enabled respectively 
+               in the LTDC_GCR and LTDC_LxCKCR registers. It can be also enabled 
+               on the fly.    
+        (#) Enable Layer1/2 and if needed the CLUT in the LTDC_LxCR register 
+  
+        (#) Reload the shadow registers to active register through 
+            the LTDC_SRCR register.
+          -@- All layer parameters can be be modified on the fly except the CLUT. 
+              The new configuration has to be either reloaded immediately 
+              or during vertical blanking period by configuring the LTDC_SRCR register.              
+        (#) Call the LTDC_Cmd() to enable the LTDC controller.
+
+    @endverbatim
+  
+  ******************************************************************************
+  * @attention
+  *
+  * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
+  * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
+  * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
+  * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
+  * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
+  * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_ltdc.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup LTDC 
+  * @brief LTDC driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+#define GCR_MASK                     ((uint32_t)0x0FFE888F)  /* LTDC GCR Mask */
+
+
+/** @defgroup LTDC_Private_Functions
+  * @{
+  */
+
+/** @defgroup LTDC_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim
+ ===============================================================================
+            ##### Initialization and Configuration functions #####
+ ===============================================================================
+    [..]  This section provides functions allowing to:
+      (+) Initialize and configure the LTDC
+      (+) Enable or Disable Dither
+      (+) Define the position of the line interrupt
+      (+) reload layers registers with new parameters
+      (+) Initialize and configure layer1 and layer2
+      (+) Set and configure the color keying functionality
+      (+) Configure and Enables or disables CLUT 
+      
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the LTDC peripheral registers to their default reset
+  *         values.
+  * @param  None
+  * @retval None
+  */
+
+void LTDC_DeInit(void)
+{
+  /* Enable LTDC reset state */
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_LTDC, ENABLE);
+  /* Release LTDC from reset state */
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_LTDC, DISABLE);
+}
+
+/**
+  * @brief  Initializes the LTDC peripheral according to the specified parameters
+  *         in the LTDC_InitStruct.
+  * @note   This function can be used only when the LTDC is disabled.
+  * @param  LTDC_InitStruct: pointer to a LTDC_InitTypeDef structure that contains
+  *         the configuration information for the specified LTDC peripheral.
+  * @retval None
+  */
+
+void LTDC_Init(LTDC_InitTypeDef* LTDC_InitStruct)
+{
+  uint32_t horizontalsync = 0;
+  uint32_t accumulatedHBP = 0;
+  uint32_t accumulatedactiveW = 0;
+  uint32_t totalwidth = 0;
+  uint32_t backgreen = 0;
+  uint32_t backred = 0;
+
+  /* Check function parameters */
+  assert_param(IS_LTDC_HSYNC(LTDC_InitStruct->LTDC_HorizontalSync));
+  assert_param(IS_LTDC_VSYNC(LTDC_InitStruct->LTDC_VerticalSync));
+  assert_param(IS_LTDC_AHBP(LTDC_InitStruct->LTDC_AccumulatedHBP));
+  assert_param(IS_LTDC_AVBP(LTDC_InitStruct->LTDC_AccumulatedVBP));
+  assert_param(IS_LTDC_AAH(LTDC_InitStruct->LTDC_AccumulatedActiveH));
+  assert_param(IS_LTDC_AAW(LTDC_InitStruct->LTDC_AccumulatedActiveW));
+  assert_param(IS_LTDC_TOTALH(LTDC_InitStruct->LTDC_TotalHeigh));
+  assert_param(IS_LTDC_TOTALW(LTDC_InitStruct->LTDC_TotalWidth));
+  assert_param(IS_LTDC_HSPOL(LTDC_InitStruct->LTDC_HSPolarity));
+  assert_param(IS_LTDC_VSPOL(LTDC_InitStruct->LTDC_VSPolarity));
+  assert_param(IS_LTDC_DEPOL(LTDC_InitStruct->LTDC_DEPolarity));
+  assert_param(IS_LTDC_PCPOL(LTDC_InitStruct->LTDC_PCPolarity));
+  assert_param(IS_LTDC_BackBlueValue(LTDC_InitStruct->LTDC_BackgroundBlueValue));
+  assert_param(IS_LTDC_BackGreenValue(LTDC_InitStruct->LTDC_BackgroundGreenValue));
+  assert_param(IS_LTDC_BackRedValue(LTDC_InitStruct->LTDC_BackgroundRedValue));
+
+  /* Sets Synchronization size */
+  LTDC->SSCR &= ~(LTDC_SSCR_VSH | LTDC_SSCR_HSW);
+  horizontalsync = (LTDC_InitStruct->LTDC_HorizontalSync << 16);
+  LTDC->SSCR |= (horizontalsync | LTDC_InitStruct->LTDC_VerticalSync);
+
+  /* Sets Accumulated Back porch */
+  LTDC->BPCR &= ~(LTDC_BPCR_AVBP | LTDC_BPCR_AHBP);
+  accumulatedHBP = (LTDC_InitStruct->LTDC_AccumulatedHBP << 16);
+  LTDC->BPCR |= (accumulatedHBP | LTDC_InitStruct->LTDC_AccumulatedVBP);
+
+  /* Sets Accumulated Active Width */
+  LTDC->AWCR &= ~(LTDC_AWCR_AAH | LTDC_AWCR_AAW);
+  accumulatedactiveW = (LTDC_InitStruct->LTDC_AccumulatedActiveW << 16);
+  LTDC->AWCR |= (accumulatedactiveW | LTDC_InitStruct->LTDC_AccumulatedActiveH);
+
+  /* Sets Total Width */
+  LTDC->TWCR &= ~(LTDC_TWCR_TOTALH | LTDC_TWCR_TOTALW);
+  totalwidth = (LTDC_InitStruct->LTDC_TotalWidth << 16);
+  LTDC->TWCR |= (totalwidth | LTDC_InitStruct->LTDC_TotalHeigh);
+
+  LTDC->GCR &= (uint32_t)GCR_MASK;
+  LTDC->GCR |=  (uint32_t)(LTDC_InitStruct->LTDC_HSPolarity | LTDC_InitStruct->LTDC_VSPolarity | \
+                           LTDC_InitStruct->LTDC_DEPolarity | LTDC_InitStruct->LTDC_PCPolarity);
+
+  /* sets the background color value */
+  backgreen = (LTDC_InitStruct->LTDC_BackgroundGreenValue << 8);
+  backred = (LTDC_InitStruct->LTDC_BackgroundRedValue << 16);
+
+  LTDC->BCCR &= ~(LTDC_BCCR_BCBLUE | LTDC_BCCR_BCGREEN | LTDC_BCCR_BCRED);
+  LTDC->BCCR |= (backred | backgreen | LTDC_InitStruct->LTDC_BackgroundBlueValue);
+}
+
+/**
+  * @brief  Fills each LTDC_InitStruct member with its default value.
+  * @param  LTDC_InitStruct: pointer to a LTDC_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+
+void LTDC_StructInit(LTDC_InitTypeDef* LTDC_InitStruct)
+{
+  /*--------------- Reset LTDC init structure parameters values ----------------*/
+  LTDC_InitStruct->LTDC_HSPolarity = LTDC_HSPolarity_AL;      /*!< Initialize the LTDC_HSPolarity member */ 
+  LTDC_InitStruct->LTDC_VSPolarity = LTDC_VSPolarity_AL;      /*!< Initialize the LTDC_VSPolarity member */
+  LTDC_InitStruct->LTDC_DEPolarity = LTDC_DEPolarity_AL;      /*!< Initialize the LTDC_DEPolarity member */
+  LTDC_InitStruct->LTDC_PCPolarity = LTDC_PCPolarity_IPC;     /*!< Initialize the LTDC_PCPolarity member */
+  LTDC_InitStruct->LTDC_HorizontalSync = 0x00;                /*!< Initialize the LTDC_HorizontalSync member */
+  LTDC_InitStruct->LTDC_VerticalSync = 0x00;                  /*!< Initialize the LTDC_VerticalSync member */
+  LTDC_InitStruct->LTDC_AccumulatedHBP = 0x00;                /*!< Initialize the LTDC_AccumulatedHBP member */
+  LTDC_InitStruct->LTDC_AccumulatedVBP = 0x00;                /*!< Initialize the LTDC_AccumulatedVBP member */
+  LTDC_InitStruct->LTDC_AccumulatedActiveW = 0x00;            /*!< Initialize the LTDC_AccumulatedActiveW member */
+  LTDC_InitStruct->LTDC_AccumulatedActiveH = 0x00;            /*!< Initialize the LTDC_AccumulatedActiveH member */
+  LTDC_InitStruct->LTDC_TotalWidth = 0x00;                    /*!< Initialize the LTDC_TotalWidth member */
+  LTDC_InitStruct->LTDC_TotalHeigh = 0x00;                    /*!< Initialize the LTDC_TotalHeigh member */
+  LTDC_InitStruct->LTDC_BackgroundRedValue = 0x00;            /*!< Initialize the LTDC_BackgroundRedValue member */
+  LTDC_InitStruct->LTDC_BackgroundGreenValue = 0x00;          /*!< Initialize the LTDC_BackgroundGreenValue member */
+  LTDC_InitStruct->LTDC_BackgroundBlueValue = 0x00;           /*!< Initialize the LTDC_BackgroundBlueValue member */
+}
+
+/**
+  * @brief  Enables or disables the LTDC Controller.
+  * @param  NewState: new state of the LTDC peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+
+void LTDC_Cmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable LTDC by setting LTDCEN bit */
+    LTDC->GCR |= (uint32_t)LTDC_GCR_LTDCEN;
+  }
+  else
+  {
+    /* Disable LTDC by clearing LTDCEN bit */
+    LTDC->GCR &= ~(uint32_t)LTDC_GCR_LTDCEN;
+  }
+}
+
+/**
+  * @brief  Enables or disables Dither.
+  * @param  NewState: new state of the Dither.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+
+void LTDC_DitherCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable Dither by setting DTEN bit */
+    LTDC->GCR |= (uint32_t)LTDC_GCR_DTEN;
+  }
+  else
+  {
+    /* Disable Dither by clearing DTEN bit */
+    LTDC->GCR &= ~(uint32_t)LTDC_GCR_DTEN;
+  }
+}
+
+/**
+  * @brief  Get the dither RGB width.
+  * @param  LTDC_RGB_InitStruct: pointer to a LTDC_RGBTypeDef structure that contains
+  *         the Dither RGB width.
+  * @retval None
+  */
+
+LTDC_RGBTypeDef LTDC_GetRGBWidth(void)
+{
+  LTDC_RGBTypeDef LTDC_RGB_InitStruct;
+
+  LTDC->GCR &= (uint32_t)GCR_MASK;
+
+  LTDC_RGB_InitStruct.LTDC_BlueWidth = (uint32_t)((LTDC->GCR >> 4) & 0x7);
+  LTDC_RGB_InitStruct.LTDC_GreenWidth = (uint32_t)((LTDC->GCR >> 8) & 0x7);
+  LTDC_RGB_InitStruct.LTDC_RedWidth = (uint32_t)((LTDC->GCR >> 12) & 0x7);
+
+  return LTDC_RGB_InitStruct;
+}
+
+/**
+  * @brief  Fills each LTDC_RGBStruct member with its default value.
+  * @param  LTDC_RGB_InitStruct: pointer to a LTDC_RGBTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+
+void LTDC_RGBStructInit(LTDC_RGBTypeDef* LTDC_RGB_InitStruct)
+{
+  LTDC_RGB_InitStruct->LTDC_BlueWidth = 0x02;
+  LTDC_RGB_InitStruct->LTDC_GreenWidth = 0x02;
+  LTDC_RGB_InitStruct->LTDC_RedWidth = 0x02;
+}
+
+
+/**
+  * @brief  Define the position of the line interrupt .
+  * @param  LTDC_LIPositionConfig: Line Interrupt Position.
+  * @retval None
+  */
+
+void LTDC_LIPConfig(uint32_t LTDC_LIPositionConfig)
+{
+  /* Check the parameters */
+  assert_param(IS_LTDC_LIPOS(LTDC_LIPositionConfig));
+
+  /* Sets the Line Interrupt position */
+  LTDC->LIPCR = (uint32_t)LTDC_LIPositionConfig;
+}
+
+/**
+  * @brief  reload layers registers with new parameters 
+  * @param  LTDC_Reload: specifies the type of reload.
+  *   This parameter can be one of the following values:
+  *     @arg LTDC_IMReload: Vertical blanking reload.
+  *     @arg LTDC_VBReload: Immediate reload.  
+  * @retval None
+  */
+
+void LTDC_ReloadConfig(uint32_t LTDC_Reload)
+{
+  /* Check the parameters */
+  assert_param(IS_LTDC_RELOAD(LTDC_Reload));
+
+  /* Sets the Reload type */
+  LTDC->SRCR = (uint32_t)LTDC_Reload;
+}
+
+
+/**
+  * @brief  Initializes the LTDC Layer according to the specified parameters
+  *         in the LTDC_LayerStruct.
+  * @note   This function can be used only when the LTDC is disabled.
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2    
+  * @param  LTDC_LayerStruct: pointer to a LTDC_LayerTypeDef structure that contains
+  *         the configuration information for the specified LTDC peripheral.
+  * @retval None
+  */
+
+void LTDC_LayerInit(LTDC_Layer_TypeDef* LTDC_Layerx, LTDC_Layer_InitTypeDef* LTDC_Layer_InitStruct)
+{
+
+  uint32_t whsppos = 0;
+  uint32_t wvsppos = 0;
+  uint32_t dcgreen = 0;
+  uint32_t dcred = 0;
+  uint32_t dcalpha = 0;
+  uint32_t cfbp = 0;
+
+/* Check the parameters */
+  assert_param(IS_LTDC_Pixelformat(LTDC_Layer_InitStruct->LTDC_PixelFormat));
+  assert_param(IS_LTDC_BlendingFactor1(LTDC_Layer_InitStruct->LTDC_BlendingFactor_1));
+  assert_param(IS_LTDC_BlendingFactor2(LTDC_Layer_InitStruct->LTDC_BlendingFactor_2));
+  assert_param(IS_LTDC_HCONFIGST(LTDC_Layer_InitStruct->LTDC_HorizontalStart));
+  assert_param(IS_LTDC_HCONFIGSP(LTDC_Layer_InitStruct->LTDC_HorizontalStop));
+  assert_param(IS_LTDC_VCONFIGST(LTDC_Layer_InitStruct->LTDC_VerticalStart));
+  assert_param(IS_LTDC_VCONFIGSP(LTDC_Layer_InitStruct->LTDC_VerticalStop));  
+  assert_param(IS_LTDC_DEFAULTCOLOR(LTDC_Layer_InitStruct->LTDC_DefaultColorBlue));
+  assert_param(IS_LTDC_DEFAULTCOLOR(LTDC_Layer_InitStruct->LTDC_DefaultColorGreen));
+  assert_param(IS_LTDC_DEFAULTCOLOR(LTDC_Layer_InitStruct->LTDC_DefaultColorRed));
+  assert_param(IS_LTDC_DEFAULTCOLOR(LTDC_Layer_InitStruct->LTDC_DefaultColorAlpha));
+  assert_param(IS_LTDC_CFBP(LTDC_Layer_InitStruct->LTDC_CFBPitch));
+  assert_param(IS_LTDC_CFBLL(LTDC_Layer_InitStruct->LTDC_CFBLineLength));
+  assert_param(IS_LTDC_CFBLNBR(LTDC_Layer_InitStruct->LTDC_CFBLineNumber));
+
+  /* Configures the horizontal start and stop position */
+  whsppos = LTDC_Layer_InitStruct->LTDC_HorizontalStop << 16;
+  LTDC_Layerx->WHPCR &= ~(LTDC_LxWHPCR_WHSTPOS | LTDC_LxWHPCR_WHSPPOS);
+  LTDC_Layerx->WHPCR = (LTDC_Layer_InitStruct->LTDC_HorizontalStart | whsppos);
+
+  /* Configures the vertical start and stop position */
+  wvsppos = LTDC_Layer_InitStruct->LTDC_VerticalStop << 16;
+  LTDC_Layerx->WVPCR &= ~(LTDC_LxWVPCR_WVSTPOS | LTDC_LxWVPCR_WVSPPOS);
+  LTDC_Layerx->WVPCR  = (LTDC_Layer_InitStruct->LTDC_VerticalStart | wvsppos);
+
+  /* Specifies the pixel format */
+  LTDC_Layerx->PFCR &= ~(LTDC_LxPFCR_PF);
+  LTDC_Layerx->PFCR = (LTDC_Layer_InitStruct->LTDC_PixelFormat);
+
+  /* Configures the default color values */
+  dcgreen = (LTDC_Layer_InitStruct->LTDC_DefaultColorGreen << 8);
+  dcred = (LTDC_Layer_InitStruct->LTDC_DefaultColorRed << 16);
+  dcalpha = (LTDC_Layer_InitStruct->LTDC_DefaultColorAlpha << 24);
+  LTDC_Layerx->DCCR &=  ~(LTDC_LxDCCR_DCBLUE | LTDC_LxDCCR_DCGREEN | LTDC_LxDCCR_DCRED | LTDC_LxDCCR_DCALPHA);
+  LTDC_Layerx->DCCR = (LTDC_Layer_InitStruct->LTDC_DefaultColorBlue | dcgreen | \
+                        dcred | dcalpha);
+
+  /* Specifies the constant alpha value */      
+  LTDC_Layerx->CACR &= ~(LTDC_LxCACR_CONSTA);
+  LTDC_Layerx->CACR = (LTDC_Layer_InitStruct->LTDC_ConstantAlpha);
+
+  /* Specifies the blending factors */
+  LTDC_Layerx->BFCR &= ~(LTDC_LxBFCR_BF2 | LTDC_LxBFCR_BF1);
+  LTDC_Layerx->BFCR = (LTDC_Layer_InitStruct->LTDC_BlendingFactor_1 | LTDC_Layer_InitStruct->LTDC_BlendingFactor_2);
+
+  /* Configures the color frame buffer start address */
+  LTDC_Layerx->CFBAR &= ~(LTDC_LxCFBAR_CFBADD);
+  LTDC_Layerx->CFBAR = (LTDC_Layer_InitStruct->LTDC_CFBStartAdress);
+
+  /* Configures the color frame buffer pitch in byte */
+  cfbp = (LTDC_Layer_InitStruct->LTDC_CFBPitch << 16);
+  LTDC_Layerx->CFBLR  &= ~(LTDC_LxCFBLR_CFBLL | LTDC_LxCFBLR_CFBP);
+  LTDC_Layerx->CFBLR  = (LTDC_Layer_InitStruct->LTDC_CFBLineLength | cfbp);
+
+  /* Configures the frame buffer line number */
+  LTDC_Layerx->CFBLNR  &= ~(LTDC_LxCFBLNR_CFBLNBR);
+  LTDC_Layerx->CFBLNR  = (LTDC_Layer_InitStruct->LTDC_CFBLineNumber);
+
+}
+
+/**
+  * @brief  Fills each LTDC_Layer_InitStruct member with its default value.
+  * @param  LTDC_Layer_InitStruct: pointer to a LTDC_LayerTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+
+void LTDC_LayerStructInit(LTDC_Layer_InitTypeDef * LTDC_Layer_InitStruct)
+{
+  /*--------------- Reset Layer structure parameters values -------------------*/
+
+  /*!< Initialize the horizontal limit member */
+  LTDC_Layer_InitStruct->LTDC_HorizontalStart = 0x00;
+  LTDC_Layer_InitStruct->LTDC_HorizontalStop = 0x00;
+
+  /*!< Initialize the vertical limit member */
+  LTDC_Layer_InitStruct->LTDC_VerticalStart = 0x00;
+  LTDC_Layer_InitStruct->LTDC_VerticalStop = 0x00;
+
+  /*!< Initialize the pixel format member */
+  LTDC_Layer_InitStruct->LTDC_PixelFormat = LTDC_Pixelformat_ARGB8888;
+
+  /*!< Initialize the constant alpha value */
+  LTDC_Layer_InitStruct->LTDC_ConstantAlpha = 0xFF;
+
+  /*!< Initialize the default color values */
+  LTDC_Layer_InitStruct->LTDC_DefaultColorBlue = 0x00;
+  LTDC_Layer_InitStruct->LTDC_DefaultColorGreen = 0x00;
+  LTDC_Layer_InitStruct->LTDC_DefaultColorRed = 0x00;
+  LTDC_Layer_InitStruct->LTDC_DefaultColorAlpha = 0x00;
+
+  /*!< Initialize the blending factors */
+  LTDC_Layer_InitStruct->LTDC_BlendingFactor_1 = LTDC_BlendingFactor1_PAxCA;
+  LTDC_Layer_InitStruct->LTDC_BlendingFactor_2 = LTDC_BlendingFactor2_PAxCA;
+
+  /*!< Initialize the frame buffer start address */
+  LTDC_Layer_InitStruct->LTDC_CFBStartAdress = 0x00;
+
+  /*!< Initialize the frame buffer pitch and line length */
+  LTDC_Layer_InitStruct->LTDC_CFBLineLength = 0x00;
+  LTDC_Layer_InitStruct->LTDC_CFBPitch = 0x00;
+
+  /*!< Initialize the frame buffer line number */
+  LTDC_Layer_InitStruct->LTDC_CFBLineNumber = 0x00;
+}
+
+
+/**
+  * @brief  Enables or disables the LTDC_Layer Controller.
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2
+  * @param  NewState: new state of the LTDC_Layer peripheral.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+
+void LTDC_LayerCmd(LTDC_Layer_TypeDef* LTDC_Layerx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable LTDC_Layer by setting LEN bit */
+    LTDC_Layerx->CR |= (uint32_t)LTDC_LxCR_LEN;
+  }
+  else
+  {
+    /* Disable LTDC_Layer by clearing LEN bit */
+    LTDC_Layerx->CR &= ~(uint32_t)LTDC_LxCR_LEN;
+  }
+}
+
+
+/**
+  * @brief  Get the current position.
+  * @param  LTDC_Pos_InitStruct: pointer to a LTDC_PosTypeDef structure that contains
+  *         the current position.
+  * @retval None
+  */
+
+LTDC_PosTypeDef LTDC_GetPosStatus(void)
+{
+  LTDC_PosTypeDef LTDC_Pos_InitStruct;
+
+  LTDC->CPSR &= ~(LTDC_CPSR_CYPOS | LTDC_CPSR_CXPOS);
+
+  LTDC_Pos_InitStruct.LTDC_POSX = (uint32_t)(LTDC->CPSR >> 16);
+  LTDC_Pos_InitStruct.LTDC_POSY = (uint32_t)(LTDC->CPSR & 0xFFFF);
+
+  return LTDC_Pos_InitStruct;
+}
+
+/**
+  * @brief  Fills each LTDC_Pos_InitStruct member with its default value.
+  * @param  LTDC_Pos_InitStruct: pointer to a LTDC_PosTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+
+void LTDC_PosStructInit(LTDC_PosTypeDef* LTDC_Pos_InitStruct)
+{
+  LTDC_Pos_InitStruct->LTDC_POSX = 0x00;
+  LTDC_Pos_InitStruct->LTDC_POSY = 0x00;
+}
+
+/**
+  * @brief  Checks whether the specified LTDC's flag is set or not.
+  * @param  LTDC_CD: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg LTDC_CD_VDES: vertical data enable current status.
+  *     @arg LTDC_CD_HDES: horizontal data enable current status.
+  *     @arg LTDC_CD_VSYNC:  Vertical Synchronization current status.
+  *     @arg LTDC_CD_HSYNC:  Horizontal Synchronization current status.
+  * @retval The new state of LTDC_CD (SET or RESET).
+  */
+
+FlagStatus LTDC_GetCDStatus(uint32_t LTDC_CD)
+{
+  FlagStatus bitstatus;
+
+  /* Check the parameters */
+  assert_param(IS_LTDC_GET_CD(LTDC_CD));
+
+  if ((LTDC->CDSR & LTDC_CD) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Set and configure the color keying.
+  * @param  LTDC_colorkeying_InitStruct: pointer to a LTDC_ColorKeying_InitTypeDef 
+  *         structure that contains the color keying configuration.
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2   
+  * @retval None
+  */
+
+void LTDC_ColorKeyingConfig(LTDC_Layer_TypeDef* LTDC_Layerx, LTDC_ColorKeying_InitTypeDef* LTDC_colorkeying_InitStruct, FunctionalState NewState)
+{ 
+  uint32_t ckgreen = 0;
+  uint32_t ckred = 0;
+
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_LTDC_CKEYING(LTDC_colorkeying_InitStruct->LTDC_ColorKeyBlue));
+  assert_param(IS_LTDC_CKEYING(LTDC_colorkeying_InitStruct->LTDC_ColorKeyGreen));
+  assert_param(IS_LTDC_CKEYING(LTDC_colorkeying_InitStruct->LTDC_ColorKeyRed));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable LTDC color keying by setting COLKEN bit */
+    LTDC_Layerx->CR |= (uint32_t)LTDC_LxCR_COLKEN;
+    
+    /* Sets the color keying values */
+    ckgreen = (LTDC_colorkeying_InitStruct->LTDC_ColorKeyGreen << 8);
+    ckred = (LTDC_colorkeying_InitStruct->LTDC_ColorKeyRed << 16);
+    LTDC_Layerx->CKCR  &= ~(LTDC_LxCKCR_CKBLUE | LTDC_LxCKCR_CKGREEN | LTDC_LxCKCR_CKRED);
+    LTDC_Layerx->CKCR |= (LTDC_colorkeying_InitStruct->LTDC_ColorKeyBlue | ckgreen | ckred);
+  }
+  else
+  {
+    /* Disable LTDC color keying by clearing COLKEN bit */
+    LTDC_Layerx->CR &= ~(uint32_t)LTDC_LxCR_COLKEN;
+  }
+  
+  /* Reload shadow register */
+  LTDC->SRCR = LTDC_IMReload;
+}
+
+/**
+  * @brief  Fills each LTDC_colorkeying_InitStruct member with its default value.
+  * @param  LTDC_colorkeying_InitStruct: pointer to a LTDC_ColorKeying_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+
+void LTDC_ColorKeyingStructInit(LTDC_ColorKeying_InitTypeDef* LTDC_colorkeying_InitStruct)
+{
+  /*!< Initialize the color keying values */
+  LTDC_colorkeying_InitStruct->LTDC_ColorKeyBlue = 0x00;
+  LTDC_colorkeying_InitStruct->LTDC_ColorKeyGreen = 0x00;
+  LTDC_colorkeying_InitStruct->LTDC_ColorKeyRed = 0x00;
+}
+
+
+/**
+  * @brief  Enables or disables CLUT.
+  * @param  NewState: new state of CLUT.
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2  
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+
+void LTDC_CLUTCmd(LTDC_Layer_TypeDef* LTDC_Layerx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable CLUT by setting CLUTEN bit */
+    LTDC_Layerx->CR |= (uint32_t)LTDC_LxCR_CLUTEN;
+  }
+  else
+  {
+    /* Disable CLUT by clearing CLUTEN bit */
+    LTDC_Layerx->CR &= ~(uint32_t)LTDC_LxCR_CLUTEN;
+  }
+  
+  /* Reload shadow register */
+  LTDC->SRCR = LTDC_IMReload;
+}
+
+/**
+  * @brief  configure the CLUT.
+  * @param  LTDC_CLUT_InitStruct: pointer to a LTDC_CLUT_InitTypeDef structure that contains
+  *         the CLUT configuration.
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2   
+  * @retval None
+  */
+
+void LTDC_CLUTInit(LTDC_Layer_TypeDef* LTDC_Layerx, LTDC_CLUT_InitTypeDef* LTDC_CLUT_InitStruct)
+{  
+  uint32_t green = 0;
+  uint32_t red = 0;
+  uint32_t clutadd = 0;
+
+  /* Check the parameters */
+  assert_param(IS_LTDC_CLUTWR(LTDC_CLUT_InitStruct->LTDC_CLUTAdress));
+  assert_param(IS_LTDC_CLUTWR(LTDC_CLUT_InitStruct->LTDC_RedValue));
+  assert_param(IS_LTDC_CLUTWR(LTDC_CLUT_InitStruct->LTDC_GreenValue));
+  assert_param(IS_LTDC_CLUTWR(LTDC_CLUT_InitStruct->LTDC_BlueValue));
+    
+  /* Specifies the CLUT address and RGB value */
+  green = (LTDC_CLUT_InitStruct->LTDC_GreenValue << 8);
+  red = (LTDC_CLUT_InitStruct->LTDC_RedValue << 16);
+  clutadd = (LTDC_CLUT_InitStruct->LTDC_CLUTAdress << 24);
+  LTDC_Layerx->CLUTWR  = (clutadd | LTDC_CLUT_InitStruct->LTDC_BlueValue | \
+                              green | red);
+}
+
+/**
+  * @brief  Fills each LTDC_CLUT_InitStruct member with its default value.
+  * @param  LTDC_CLUT_InitStruct: pointer to a LTDC_CLUT_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+
+void LTDC_CLUTStructInit(LTDC_CLUT_InitTypeDef* LTDC_CLUT_InitStruct)
+{
+  /*!< Initialize the CLUT adress and RGB values */
+  LTDC_CLUT_InitStruct->LTDC_CLUTAdress = 0x00;
+  LTDC_CLUT_InitStruct->LTDC_BlueValue = 0x00;
+  LTDC_CLUT_InitStruct->LTDC_GreenValue = 0x00;
+  LTDC_CLUT_InitStruct->LTDC_RedValue = 0x00;
+}
+
+
+/**
+  * @brief  reconfigure the layer position.
+  * @param  OffsetX: horizontal offset from start active width .
+  * @param  OffsetY: vertical offset from start active height.   
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2   
+  * @retval Reload of the shadow registers values must be applied after layer 
+  *         position reconfiguration.
+  */
+
+void LTDC_LayerPosition(LTDC_Layer_TypeDef* LTDC_Layerx, uint16_t OffsetX, uint16_t OffsetY)
+{
+  
+  uint32_t tempreg, temp;
+  uint32_t horizontal_start;
+  uint32_t horizontal_stop;
+  uint32_t vertical_start;
+  uint32_t vertical_stop;
+  
+  LTDC_Layerx->WHPCR &= ~(LTDC_LxWHPCR_WHSTPOS | LTDC_LxWHPCR_WHSPPOS);
+  LTDC_Layerx->WVPCR &= ~(LTDC_LxWVPCR_WVSTPOS | LTDC_LxWVPCR_WVSPPOS);
+  
+  /* Reconfigures the horizontal and vertical start position */
+  tempreg = LTDC->BPCR;
+  horizontal_start = (tempreg >> 16) + 1 + OffsetX;
+  vertical_start = (tempreg & 0xFFFF) + 1 + OffsetY;
+  
+  /* Reconfigures the horizontal and vertical stop position */
+  /* Get the number of byte per pixel */
+  
+  tempreg = LTDC_Layerx->PFCR;
+  
+  if (tempreg == LTDC_Pixelformat_ARGB8888)
+  {
+    temp = 4;
+  }
+  else if (tempreg == LTDC_Pixelformat_RGB888)
+  {
+    temp = 3;
+  }
+  else if ((tempreg == LTDC_Pixelformat_ARGB4444) || 
+          (tempreg == LTDC_Pixelformat_RGB565)    ||  
+          (tempreg == LTDC_Pixelformat_ARGB1555)  ||
+          (tempreg == LTDC_Pixelformat_AL88))
+  {
+    temp = 2;  
+  }
+  else
+  {
+    temp = 1;
+  }  
+    
+  tempreg = LTDC_Layerx->CFBLR;
+  horizontal_stop = (((tempreg & 0x1FFF) - 3)/temp) + horizontal_start - 1;
+  
+  tempreg = LTDC_Layerx->CFBLNR;
+  vertical_stop = (tempreg & 0x7FF) + vertical_start - 1;  
+  
+  LTDC_Layerx->WHPCR = horizontal_start | (horizontal_stop << 16);
+  LTDC_Layerx->WVPCR = vertical_start | (vertical_stop << 16);  
+}
+  
+/**
+  * @brief  reconfigure constant alpha.
+  * @param  ConstantAlpha: constant alpha value.
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2    
+  * @retval Reload of the shadow registers values must be applied after constant 
+  *         alpha reconfiguration.         
+  */
+
+void LTDC_LayerAlpha(LTDC_Layer_TypeDef* LTDC_Layerx, uint8_t ConstantAlpha)
+{  
+  /* reconfigure the constant alpha value */      
+  LTDC_Layerx->CACR = ConstantAlpha;
+}
+
+/**
+  * @brief  reconfigure layer address.
+  * @param  Address: The color frame buffer start address.
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2     
+  * @retval Reload of the shadow registers values must be applied after layer 
+  *         address reconfiguration.
+  */
+
+void LTDC_LayerAddress(LTDC_Layer_TypeDef* LTDC_Layerx, uint32_t Address)
+{
+  /* Reconfigures the color frame buffer start address */
+  LTDC_Layerx->CFBAR = Address;
+}
+  
+/**
+  * @brief  reconfigure layer size.
+  * @param  Width: layer window width.
+  * @param  Height: layer window height.   
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2   
+  * @retval Reload of the shadow registers values must be applied after layer 
+  *         size reconfiguration.
+  */
+
+void LTDC_LayerSize(LTDC_Layer_TypeDef* LTDC_Layerx, uint32_t Width, uint32_t Height)
+{
+
+  uint8_t temp;
+  uint32_t tempreg;
+  uint32_t horizontal_start;
+  uint32_t horizontal_stop;
+  uint32_t vertical_start;
+  uint32_t vertical_stop;  
+  
+  tempreg = LTDC_Layerx->PFCR;
+  
+  if (tempreg == LTDC_Pixelformat_ARGB8888)
+  {
+    temp = 4;
+  }
+  else if (tempreg == LTDC_Pixelformat_RGB888)
+  {
+    temp = 3;
+  }
+  else if ((tempreg == LTDC_Pixelformat_ARGB4444) || \
+          (tempreg == LTDC_Pixelformat_RGB565)    || \
+          (tempreg == LTDC_Pixelformat_ARGB1555)  || \
+          (tempreg == LTDC_Pixelformat_AL88))
+  {
+    temp = 2;  
+  }
+  else
+  {
+    temp = 1;
+  }
+
+  /* update horizontal and vertical stop */
+  tempreg = LTDC_Layerx->WHPCR;
+  horizontal_start = (tempreg & 0x1FFF);
+  horizontal_stop = Width + horizontal_start - 1;  
+
+  tempreg = LTDC_Layerx->WVPCR;
+  vertical_start = (tempreg & 0x1FFF);
+  vertical_stop = Height + vertical_start - 1;  
+  
+  LTDC_Layerx->WHPCR = horizontal_start | (horizontal_stop << 16);
+  LTDC_Layerx->WVPCR = vertical_start | (vertical_stop << 16);  
+
+  /* Reconfigures the color frame buffer pitch in byte */
+  LTDC_Layerx->CFBLR  = ((Width * temp) << 16) | ((Width * temp) + 3);  
+
+  /* Reconfigures the frame buffer line number */
+  LTDC_Layerx->CFBLNR  = Height;  
+  
+}
+
+/**
+  * @brief  reconfigure layer pixel format.
+  * @param  PixelFormat: reconfigure the pixel format, this parameter can be 
+  *         one of the following values:@ref LTDC_Pixelformat.   
+  * @param  LTDC_layerx: Select the layer to be configured, this parameter can be 
+  *         one of the following values: LTDC_Layer1, LTDC_Layer2   
+  * @retval Reload of the shadow registers values must be applied after layer 
+  *         pixel format reconfiguration.
+  */
+
+void LTDC_LayerPixelFormat(LTDC_Layer_TypeDef* LTDC_Layerx, uint32_t PixelFormat)
+{
+
+  uint8_t temp;
+  uint32_t tempreg;
+  
+  tempreg = LTDC_Layerx->PFCR;
+  
+  if (tempreg == LTDC_Pixelformat_ARGB8888)
+  {
+    temp = 4;
+  }
+  else if (tempreg == LTDC_Pixelformat_RGB888)
+  {
+    temp = 3;
+  }
+  else if ((tempreg == LTDC_Pixelformat_ARGB4444) || \
+          (tempreg == LTDC_Pixelformat_RGB565)    || \
+          (tempreg == LTDC_Pixelformat_ARGB1555)  || \
+          (tempreg == LTDC_Pixelformat_AL88))  
+  {
+    temp = 2;  
+  }
+  else
+  {
+    temp = 1;
+  }
+  
+  tempreg = (LTDC_Layerx->CFBLR >> 16);
+  tempreg = (tempreg / temp); 
+  
+  if (PixelFormat == LTDC_Pixelformat_ARGB8888)
+  {
+    temp = 4;
+  }
+  else if (PixelFormat == LTDC_Pixelformat_RGB888)
+  {
+    temp = 3;
+  }
+  else if ((PixelFormat == LTDC_Pixelformat_ARGB4444) || \
+          (PixelFormat == LTDC_Pixelformat_RGB565)    || \
+          (PixelFormat == LTDC_Pixelformat_ARGB1555)  || \
+          (PixelFormat == LTDC_Pixelformat_AL88))
+  {
+    temp = 2;  
+  }
+  else
+  {
+    temp = 1;
+  }
+  
+  /* Reconfigures the color frame buffer pitch in byte */
+  LTDC_Layerx->CFBLR  = ((tempreg * temp) << 16) | ((tempreg * temp) + 3);  
+
+  /* Reconfigures the color frame buffer start address */
+  LTDC_Layerx->PFCR = PixelFormat;
+    
+}
+    
+/**
+  * @}
+  */
+
+/** @defgroup LTDC_Group2 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim
+ ===============================================================================
+            ##### Interrupts and flags management functions #####
+ ===============================================================================
+
+    [..] This section provides functions allowing to configure the LTDC Interrupts 
+         and to get the status and clear flags and Interrupts pending bits.
+  
+    [..] The LTDC provides 4 Interrupts sources and 4 Flags
+    
+    *** Flags ***
+    =============
+    [..]
+      (+) LTDC_FLAG_LI:   Line Interrupt flag.
+      (+) LTDC_FLAG_FU:   FIFO Underrun Interrupt flag.
+      (+) LTDC_FLAG_TERR: Transfer Error Interrupt flag.
+      (+) LTDC_FLAG_RR:   Register Reload interrupt flag.
+      
+    *** Interrupts ***
+    ==================
+    [..]
+      (+) LTDC_IT_LI: Line Interrupt is generated when a programmed line 
+                      is reached. The line interrupt position is programmed in 
+                      the LTDC_LIPR register.
+      (+) LTDC_IT_FU: FIFO Underrun interrupt is generated when a pixel is requested 
+                      from an empty layer FIFO
+      (+) LTDC_IT_TERR: Transfer Error interrupt is generated when an AHB bus 
+                        error occurs during data transfer.
+      (+) LTDC_IT_RR: Register Reload interrupt is generated when the shadow 
+                      registers reload was performed during the vertical blanking 
+                      period.
+               
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified LTDC's interrupts.
+  * @param  LTDC_IT: specifies the LTDC interrupts sources to be enabled or disabled.
+  *   This parameter can be any combination of the following values:
+  *     @arg LTDC_IT_LI: Line Interrupt Enable.
+  *     @arg LTDC_IT_FU: FIFO Underrun Interrupt Enable.
+  *     @arg LTDC_IT_TERR: Transfer Error Interrupt Enable.
+  *     @arg LTDC_IT_RR: Register Reload interrupt enable.  
+  * @param NewState: new state of the specified LTDC interrupts.
+  *   This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void LTDC_ITConfig(uint32_t LTDC_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_LTDC_IT(LTDC_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    LTDC->IER |= LTDC_IT;
+  }
+  else
+  {
+    LTDC->IER &= (uint32_t)~LTDC_IT;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified LTDC's flag is set or not.
+  * @param  LTDC_FLAG: specifies the flag to check.
+  *   This parameter can be one of the following values:
+  *     @arg LTDC_FLAG_LI:    Line Interrupt flag.
+  *     @arg LTDC_FLAG_FU:   FIFO Underrun Interrupt flag.
+  *     @arg LTDC_FLAG_TERR: Transfer Error Interrupt flag.
+  *     @arg LTDC_FLAG_RR:   Register Reload interrupt flag.
+  * @retval The new state of LTDC_FLAG (SET or RESET).
+  */
+FlagStatus LTDC_GetFlagStatus(uint32_t LTDC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+
+  /* Check the parameters */
+  assert_param(IS_LTDC_FLAG(LTDC_FLAG));
+
+  if ((LTDC->ISR & LTDC_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the LTDC's pending flags.
+  * @param  LTDC_FLAG: specifies the flag to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg LTDC_FLAG_LI:    Line Interrupt flag.
+  *     @arg LTDC_FLAG_FU:   FIFO Underrun Interrupt flag.
+  *     @arg LTDC_FLAG_TERR: Transfer Error Interrupt flag.
+  *     @arg LTDC_FLAG_RR:   Register Reload interrupt flag.  
+  * @retval None
+  */
+void LTDC_ClearFlag(uint32_t LTDC_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_LTDC_FLAG(LTDC_FLAG));
+
+  /* Clear the corresponding LTDC flag */
+  LTDC->ICR = (uint32_t)LTDC_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified LTDC's interrupt has occurred or not.
+  * @param  LTDC_IT: specifies the LTDC interrupts sources to check.
+  *   This parameter can be one of the following values:
+  *     @arg LTDC_IT_LI:    Line Interrupt Enable.
+  *     @arg LTDC_IT_FU:   FIFO Underrun Interrupt Enable.
+  *     @arg LTDC_IT_TERR: Transfer Error Interrupt Enable.
+  *     @arg LTDC_IT_RR:   Register Reload interrupt Enable.
+  * @retval The new state of the LTDC_IT (SET or RESET).
+  */
+ITStatus LTDC_GetITStatus(uint32_t LTDC_IT)
+{
+  ITStatus bitstatus = RESET;
+
+  /* Check the parameters */
+  assert_param(IS_LTDC_IT(LTDC_IT));
+
+  if ((LTDC->ISR & LTDC_IT) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+
+  if (((LTDC->IER & LTDC_IT) != (uint32_t)RESET) && (bitstatus != (uint32_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+
+/**
+  * @brief  Clears the LTDC's interrupt pending bits.
+  * @param  LTDC_IT: specifies the interrupt pending bit to clear.
+  *   This parameter can be any combination of the following values:
+  *     @arg LTDC_IT_LIE:    Line Interrupt.
+  *     @arg LTDC_IT_FUIE:   FIFO Underrun Interrupt.
+  *     @arg LTDC_IT_TERRIE: Transfer Error Interrupt.
+  *     @arg LTDC_IT_RRIE:   Register Reload interrupt.
+  * @retval None
+  */
+void LTDC_ClearITPendingBit(uint32_t LTDC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_LTDC_IT(LTDC_IT));
+
+  /* Clear the corresponding LTDC Interrupt */
+  LTDC->ICR = (uint32_t)LTDC_IT;
+}
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_misc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_misc.c
new file mode 100644
index 0000000000000000000000000000000000000000..ca41b11c5cb63b58b6413bf48eb4f82528e615c5
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_misc.c
@@ -0,0 +1,249 @@
+/**
+  ******************************************************************************
+  * @file    misc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides all the miscellaneous firmware functions (add-on
+  *          to CMSIS functions).
+  *          
+  *  @verbatim   
+  *                               
+  *          ===================================================================      
+  *                        How to configure Interrupts using driver 
+  *          ===================================================================      
+  * 
+  *            This section provide functions allowing to configure the NVIC interrupts (IRQ).
+  *            The Cortex-M4 exceptions are managed by CMSIS functions.
+  *
+  *            1. Configure the NVIC Priority Grouping using NVIC_PriorityGroupConfig()
+  *                function according to the following table.
+ 
+  *  The table below gives the allowed values of the pre-emption priority and subpriority according
+  *  to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function
+  *    ==========================================================================================================================
+  *      NVIC_PriorityGroup   | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority  |       Description
+  *    ==========================================================================================================================
+  *     NVIC_PriorityGroup_0  |                0                  |            0-15             | 0 bits for pre-emption priority
+  *                           |                                   |                             | 4 bits for subpriority
+  *    --------------------------------------------------------------------------------------------------------------------------
+  *     NVIC_PriorityGroup_1  |                0-1                |            0-7              | 1 bits for pre-emption priority
+  *                           |                                   |                             | 3 bits for subpriority
+  *    --------------------------------------------------------------------------------------------------------------------------    
+  *     NVIC_PriorityGroup_2  |                0-3                |            0-3              | 2 bits for pre-emption priority
+  *                           |                                   |                             | 2 bits for subpriority
+  *    --------------------------------------------------------------------------------------------------------------------------    
+  *     NVIC_PriorityGroup_3  |                0-7                |            0-1              | 3 bits for pre-emption priority
+  *                           |                                   |                             | 1 bits for subpriority
+  *    --------------------------------------------------------------------------------------------------------------------------    
+  *     NVIC_PriorityGroup_4  |                0-15               |            0                | 4 bits for pre-emption priority
+  *                           |                                   |                             | 0 bits for subpriority                       
+  *    ==========================================================================================================================     
+  *
+  *            2. Enable and Configure the priority of the selected IRQ Channels using NVIC_Init()  
+  *
+  * @note  When the NVIC_PriorityGroup_0 is selected, IRQ pre-emption is no more possible. 
+  *        The pending IRQ priority will be managed only by the subpriority.
+  *
+  * @note  IRQ priority order (sorted by highest to lowest priority):
+  *         - Lowest pre-emption priority
+  *         - Lowest subpriority
+  *         - Lowest hardware priority (IRQ number)
+  *
+  *  @endverbatim
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_misc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup MISC 
+  * @brief MISC driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+#define AIRCR_VECTKEY_MASK    ((uint32_t)0x05FA0000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup MISC_Private_Functions
+  * @{
+  */
+
+/**
+  * @brief  Configures the priority grouping: pre-emption priority and subpriority.
+  * @param  NVIC_PriorityGroup: specifies the priority grouping bits length. 
+  *   This parameter can be one of the following values:
+  *     @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority
+  *                                4 bits for subpriority
+  *     @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority
+  *                                3 bits for subpriority
+  *     @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority
+  *                                2 bits for subpriority
+  *     @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority
+  *                                1 bits for subpriority
+  *     @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority
+  *                                0 bits for subpriority
+  * @note   When the NVIC_PriorityGroup_0 is selected, IRQ pre-emption is no more possible. 
+  *         The pending IRQ priority will be managed only by the subpriority. 
+  * @retval None
+  */
+void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup)
+{
+  /* Check the parameters */
+  assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup));
+  
+  /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */
+  SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup;
+}
+
+/**
+  * @brief  Initializes the NVIC peripheral according to the specified
+  *         parameters in the NVIC_InitStruct.
+  * @note   To configure interrupts priority correctly, the NVIC_PriorityGroupConfig()
+  *         function should be called before. 
+  * @param  NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains
+  *         the configuration information for the specified NVIC peripheral.
+  * @retval None
+  */
+void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct)
+{
+  uint8_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F;
+  
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd));
+  assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority));  
+  assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority));
+    
+  if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE)
+  {
+    /* Compute the Corresponding IRQ Priority --------------------------------*/    
+    tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08;
+    tmppre = (0x4 - tmppriority);
+    tmpsub = tmpsub >> tmppriority;
+
+    tmppriority = NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre;
+    tmppriority |=  (uint8_t)(NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub);
+        
+    tmppriority = tmppriority << 0x04;
+        
+    NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority;
+    
+    /* Enable the Selected IRQ Channels --------------------------------------*/
+    NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
+      (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
+  }
+  else
+  {
+    /* Disable the Selected IRQ Channels -------------------------------------*/
+    NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] =
+      (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F);
+  }
+}
+
+/**
+  * @brief  Sets the vector table location and Offset.
+  * @param  NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory.
+  *   This parameter can be one of the following values:
+  *     @arg NVIC_VectTab_RAM: Vector Table in internal SRAM.
+  *     @arg NVIC_VectTab_FLASH: Vector Table in internal FLASH.
+  * @param  Offset: Vector Table base offset field. This value must be a multiple of 0x200.
+  * @retval None
+  */
+void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset)
+{ 
+  /* Check the parameters */
+  assert_param(IS_NVIC_VECTTAB(NVIC_VectTab));
+  assert_param(IS_NVIC_OFFSET(Offset));  
+   
+  SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80);
+}
+
+/**
+  * @brief  Selects the condition for the system to enter low power mode.
+  * @param  LowPowerMode: Specifies the new mode for the system to enter low power mode.
+  *   This parameter can be one of the following values:
+  *     @arg NVIC_LP_SEVONPEND: Low Power SEV on Pend.
+  *     @arg NVIC_LP_SLEEPDEEP: Low Power DEEPSLEEP request.
+  *     @arg NVIC_LP_SLEEPONEXIT: Low Power Sleep on Exit.
+  * @param  NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_NVIC_LP(LowPowerMode));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));  
+  
+  if (NewState != DISABLE)
+  {
+    SCB->SCR |= LowPowerMode;
+  }
+  else
+  {
+    SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode);
+  }
+}
+
+/**
+  * @brief  Configures the SysTick clock source.
+  * @param  SysTick_CLKSource: specifies the SysTick clock source.
+  *   This parameter can be one of the following values:
+  *     @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source.
+  *     @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source.
+  * @retval None
+  */
+void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
+  if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
+  {
+    SysTick->CTRL |= SysTick_CLKSource_HCLK;
+  }
+  else
+  {
+    SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
+  }
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c
new file mode 100644
index 0000000000000000000000000000000000000000..61b8515e1048cb4d3f1875e2f2db06677f6b0fcb
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_pwr.c
@@ -0,0 +1,885 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_pwr.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Power Controller (PWR) peripheral:           
+  *           + Backup Domain Access
+  *           + PVD configuration
+  *           + WakeUp pin configuration
+  *           + Main and Backup Regulators configuration
+  *           + FLASH Power Down configuration
+  *           + Low Power modes configuration
+  *           + Flags management
+  *               
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_pwr.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup PWR 
+  * @brief PWR driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* --------- PWR registers bit address in the alias region ---------- */
+#define PWR_OFFSET               (PWR_BASE - PERIPH_BASE)
+
+/* --- CR Register ---*/
+
+/* Alias word address of DBP bit */
+#define CR_OFFSET                (PWR_OFFSET + 0x00)
+#define DBP_BitNumber            0x08
+#define CR_DBP_BB                (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4))
+
+/* Alias word address of PVDE bit */
+#define PVDE_BitNumber           0x04
+#define CR_PVDE_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4))
+
+/* Alias word address of FPDS bit */
+#define FPDS_BitNumber           0x09
+#define CR_FPDS_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (FPDS_BitNumber * 4))
+
+/* Alias word address of PMODE bit */
+#define PMODE_BitNumber           0x0E
+#define CR_PMODE_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PMODE_BitNumber * 4))
+
+/* Alias word address of ODEN bit */
+#define ODEN_BitNumber           0x10
+#define CR_ODEN_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (ODEN_BitNumber * 4))
+
+/* Alias word address of ODSWEN bit */
+#define ODSWEN_BitNumber         0x11
+#define CR_ODSWEN_BB             (PERIPH_BB_BASE + (CR_OFFSET * 32) + (ODSWEN_BitNumber * 4))
+
+/* --- CSR Register ---*/
+
+/* Alias word address of EWUP bit */
+#define CSR_OFFSET               (PWR_OFFSET + 0x04)
+#define EWUP_BitNumber           0x08
+#define CSR_EWUP_BB              (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4))
+
+/* Alias word address of BRE bit */
+#define BRE_BitNumber            0x09
+#define CSR_BRE_BB              (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (BRE_BitNumber * 4))
+
+/* ------------------ PWR registers bit mask ------------------------ */
+
+/* CR register bit mask */
+#define CR_DS_MASK               ((uint32_t)0xFFFFF3FC)
+#define CR_PLS_MASK              ((uint32_t)0xFFFFFF1F)
+#define CR_VOS_MASK              ((uint32_t)0xFFFF3FFF)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup PWR_Private_Functions
+  * @{
+  */
+
+/** @defgroup PWR_Group1 Backup Domain Access function 
+ *  @brief   Backup Domain Access function  
+ *
+@verbatim   
+ ===============================================================================
+                  ##### Backup Domain Access function #####
+ ===============================================================================  
+    [..]
+      After reset, the backup domain (RTC registers, RTC backup data 
+      registers and backup SRAM) is protected against possible unwanted 
+      write accesses. 
+      To enable access to the RTC Domain and RTC registers, proceed as follows:
+        (+) Enable the Power Controller (PWR) APB1 interface clock using the
+            RCC_APB1PeriphClockCmd() function.
+        (+) Enable access to RTC domain using the PWR_BackupAccessCmd() function.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the PWR peripheral registers to their default reset values.     
+  * @param  None
+  * @retval None
+  */
+void PWR_DeInit(void)
+{
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE);
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE);
+}
+
+/**
+  * @brief  Enables or disables access to the backup domain (RTC registers, RTC 
+  *         backup data registers and backup SRAM).
+  * @note   If the HSE divided by 2, 3, ..31 is used as the RTC clock, the 
+  *         Backup Domain Access should be kept enabled.
+  * @param  NewState: new state of the access to the backup domain.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_BackupAccessCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Group2 PVD configuration functions
+ *  @brief   PVD configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### PVD configuration functions #####
+ ===============================================================================  
+    [..]
+      (+) The PVD is used to monitor the VDD power supply by comparing it to a 
+          threshold selected by the PVD Level (PLS[2:0] bits in the PWR_CR).
+      (+) A PVDO flag is available to indicate if VDD/VDDA is higher or lower 
+          than the PVD threshold. This event is internally connected to the EXTI 
+          line16 and can generate an interrupt if enabled through the EXTI registers.
+      (+) The PVD is stopped in Standby mode.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the voltage threshold detected by the Power Voltage Detector(PVD).
+  * @param  PWR_PVDLevel: specifies the PVD detection level
+  *          This parameter can be one of the following values:
+  *            @arg PWR_PVDLevel_0
+  *            @arg PWR_PVDLevel_1
+  *            @arg PWR_PVDLevel_2
+  *            @arg PWR_PVDLevel_3
+  *            @arg PWR_PVDLevel_4
+  *            @arg PWR_PVDLevel_5
+  *            @arg PWR_PVDLevel_6
+  *            @arg PWR_PVDLevel_7
+  * @note   Refer to the electrical characteristics of your device datasheet for
+  *         more details about the voltage threshold corresponding to each 
+  *         detection level.
+  * @retval None
+  */
+void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel));
+  
+  tmpreg = PWR->CR;
+  
+  /* Clear PLS[7:5] bits */
+  tmpreg &= CR_PLS_MASK;
+  
+  /* Set PLS[7:5] bits according to PWR_PVDLevel value */
+  tmpreg |= PWR_PVDLevel;
+  
+  /* Store the new value */
+  PWR->CR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the Power Voltage Detector(PVD).
+  * @param  NewState: new state of the PVD.
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_PVDCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Group3 WakeUp pin configuration functions
+ *  @brief   WakeUp pin configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+                 ##### WakeUp pin configuration functions #####
+ ===============================================================================  
+    [..]
+      (+) WakeUp pin is used to wakeup the system from Standby mode. This pin is 
+          forced in input pull down configuration and is active on rising edges.
+      (+) There is only one WakeUp pin: WakeUp Pin 1 on PA.00.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the WakeUp Pin functionality.
+  * @param  NewState: new state of the WakeUp Pin functionality.
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_WakeUpPinCmd(FunctionalState NewState)
+{
+  /* Check the parameters */  
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Group4 Main and Backup Regulators configuration functions
+ *  @brief   Main and Backup Regulators configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+          ##### Main and Backup Regulators configuration functions #####
+ ===============================================================================  
+    [..]
+      (+) The backup domain includes 4 Kbytes of backup SRAM accessible only from 
+          the CPU, and address in 32-bit, 16-bit or 8-bit mode. Its content is 
+          retained even in Standby or VBAT mode when the low power backup regulator
+          is enabled. It can be considered as an internal EEPROM when VBAT is 
+          always present. You can use the PWR_BackupRegulatorCmd() function to 
+          enable the low power backup regulator and use the PWR_GetFlagStatus
+          (PWR_FLAG_BRR) to check if it is ready or not. 
+
+      (+) When the backup domain is supplied by VDD (analog switch connected to VDD) 
+          the backup SRAM is powered from VDD which replaces the VBAT power supply to 
+          save battery life.
+
+      (+) The backup SRAM is not mass erased by an tamper event. It is read 
+          protected to prevent confidential data, such as cryptographic private 
+          key, from being accessed. The backup SRAM can be erased only through 
+          the Flash interface when a protection level change from level 1 to 
+          level 0 is requested. 
+      -@- Refer to the description of Read protection (RDP) in the reference manual.
+
+      (+) The main internal regulator can be configured to have a tradeoff between 
+          performance and power consumption when the device does not operate at 
+          the maximum frequency. 
+      (+) For STM32F405xx/407xx and STM32F415xx/417xx  Devices, the regulator can be     
+          configured on the fly through PWR_MainRegulatorModeConfig() function which  
+          configure VOS bit in PWR_CR register:
+        (++) When this bit is set (Regulator voltage output Scale 1 mode selected) 
+             the System frequency can go up to 168 MHz. 
+        (++) When this bit is reset (Regulator voltage output Scale 2 mode selected) 
+             the System frequency can go up to 144 MHz.
+             
+       (+) For STM32F42xxx/43xxx Devices, the regulator can be configured through    
+           PWR_MainRegulatorModeConfig() function which configure VOS[1:0] bits in
+           PWR_CR register:  
+           which configure VOS[1:0] bits in PWR_CR register: 
+        (++) When VOS[1:0] = 11 (Regulator voltage output Scale 1 mode selected) 
+             the System frequency can go up to 168 MHz. 
+        (++) When VOS[1:0] = 10 (Regulator voltage output Scale 2 mode selected) 
+             the System frequency can go up to 144 MHz.  
+        (++) When VOS[1:0] = 01 (Regulator voltage output Scale 3 mode selected) 
+             the System frequency can go up to 120 MHz. 
+                          
+       (+) For STM32F42xxx/43xxx Devices, the scale can be modified only when the PLL 
+           is OFF and the HSI or HSE clock source is selected as system clock. 
+           The new value programmed is active only when the PLL is ON.
+           When the PLL is OFF, the voltage scale 3 is automatically selected. 
+        Refer to the datasheets for more details.
+        
+       (+) For STM32F42xxx/43xxx Devices, in Run mode: the main regulator has
+           2 operating modes available:
+        (++) Normal mode: The CPU and core logic operate at maximum frequency at a given 
+             voltage scaling (scale 1, scale 2 or scale 3)
+        (++) Over-drive mode: This mode allows the CPU and the core logic to operate at a 
+            higher frequency than the normal mode for a given voltage scaling (scale 1,  
+            scale 2 or scale 3). This mode is enabled through PWR_OverDriveCmd() function and
+            PWR_OverDriveSWCmd() function, to enter or exit from Over-drive mode please follow 
+            the sequence described in Reference manual.
+             
+       (+) For STM32F42xxx/43xxx Devices, in Stop mode: the main regulator or low power regulator 
+           supplies a low power voltage to the 1.2V domain, thus preserving the content of registers 
+           and internal SRAM. 2 operating modes are available:
+         (++) Normal mode: the 1.2V domain is preserved in nominal leakage mode. This mode is only 
+              available when the main regulator or the low power regulator is used in Scale 3 or 
+              low voltage mode.
+         (++) Under-drive mode: the 1.2V domain is preserved in reduced leakage mode. This mode is only
+              available when the main regulator or the low power regulator is in low voltage mode.
+              This mode is enabled through PWR_UnderDriveCmd() function.
+            
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the Backup Regulator.
+  * @param  NewState: new state of the Backup Regulator.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_BackupRegulatorCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CSR_BRE_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the main internal regulator output voltage.
+  * @param  PWR_Regulator_Voltage: specifies the regulator output voltage to achieve
+  *         a tradeoff between performance and power consumption when the device does
+  *         not operate at the maximum frequency (refer to the datasheets for more details).
+  *          This parameter can be one of the following values:
+  *            @arg PWR_Regulator_Voltage_Scale1: Regulator voltage output Scale 1 mode, 
+  *                                                System frequency up to 168 MHz. 
+  *            @arg PWR_Regulator_Voltage_Scale2: Regulator voltage output Scale 2 mode, 
+  *                                                System frequency up to 144 MHz.    
+  *            @arg PWR_Regulator_Voltage_Scale3: Regulator voltage output Scale 3 mode, 
+  *                                                System frequency up to 120 MHz (only for STM32F42xxx/43xxx devices)
+  * @retval None
+  */
+void PWR_MainRegulatorModeConfig(uint32_t PWR_Regulator_Voltage)
+{
+  uint32_t tmpreg = 0;
+	
+  /* Check the parameters */
+  assert_param(IS_PWR_REGULATOR_VOLTAGE(PWR_Regulator_Voltage));
+
+  tmpreg = PWR->CR;
+  
+  /* Clear VOS[15:14] bits */
+  tmpreg &= CR_VOS_MASK;
+  
+  /* Set VOS[15:14] bits according to PWR_Regulator_Voltage value */
+  tmpreg |= PWR_Regulator_Voltage;
+  
+  /* Store the new value */
+  PWR->CR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the Over-Drive.
+  * 
+  * @note   This function can be used only for STM32F42xxx/STM3243xxx devices.
+  *         This mode allows the CPU and the core logic to operate at a higher frequency
+  *         than the normal mode for a given voltage scaling (scale 1, scale 2 or scale 3).   
+  * 
+  * @note   It is recommended to enter or exit Over-drive mode when the application is not running 
+  *          critical tasks and when the system clock source is either HSI or HSE. 
+  *          During the Over-drive switch activation, no peripheral clocks should be enabled.   
+  *          The peripheral clocks must be enabled once the Over-drive mode is activated.
+  *            
+  * @param  NewState: new state of the Over Drive mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_OverDriveCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  /* Set/Reset the ODEN bit to enable/disable the Over Drive mode */
+  *(__IO uint32_t *) CR_ODEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the Over-Drive switching.
+  * 
+  * @note   This function can be used only for STM32F42xxx/STM3243xxx devices. 
+  *       
+  * @param  NewState: new state of the Over Drive switching mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_OverDriveSWCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Set/Reset the ODSWEN bit to enable/disable the Over Drive switching mode */
+  *(__IO uint32_t *) CR_ODSWEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief   Enables or disables the Under-Drive mode.
+  * 
+  * @note   This function can be used only for STM32F42xxx/STM3243xxx devices.
+  * @note    This mode is enabled only with STOP low power mode.
+  *          In this mode, the 1.2V domain is preserved in reduced leakage mode. This 
+  *          mode is only available when the main regulator or the low power regulator 
+  *          is in low voltage mode
+  *        
+  * @note   If the Under-drive mode was enabled, it is automatically disabled after 
+  *         exiting Stop mode. 
+  *         When the voltage regulator operates in Under-drive mode, an additional  
+  *         startup delay is induced when waking up from Stop mode.
+  *                    
+  * @param  NewState: new state of the Under Drive mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_UnderDriveCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Set the UDEN[1:0] bits to enable the Under Drive mode */
+    PWR->CR |= (uint32_t)PWR_CR_UDEN;
+  }
+  else
+  {
+    /* Reset the UDEN[1:0] bits to disable the Under Drive mode */
+    PWR->CR &= (uint32_t)(~PWR_CR_UDEN);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Group5 FLASH Power Down configuration functions
+ *  @brief   FLASH Power Down configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+             ##### FLASH Power Down configuration functions #####
+ ===============================================================================  
+    [..]
+      (+) By setting the FPDS bit in the PWR_CR register by using the 
+          PWR_FlashPowerDownCmd() function, the Flash memory also enters power 
+          down mode when the device enters Stop mode. When the Flash memory 
+          is in power down mode, an additional startup delay is incurred when 
+          waking up from Stop mode.
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the Flash Power Down in STOP mode.
+  * @param  NewState: new state of the Flash power mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void PWR_FlashPowerDownCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CR_FPDS_BB = (uint32_t)NewState;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Group6 Low Power modes configuration functions
+ *  @brief   Low Power modes configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Low Power modes configuration functions #####
+ ===============================================================================  
+    [..]
+      The devices feature 3 low-power modes:
+      (+) Sleep mode: Cortex-M4 core stopped, peripherals kept running.
+      (+) Stop mode: all clocks are stopped, regulator running, regulator 
+          in low power mode
+      (+) Standby mode: 1.2V domain powered off.
+   
+   *** Sleep mode ***
+   ==================
+    [..]
+      (+) Entry:
+        (++) The Sleep mode is entered by using the __WFI() or __WFE() functions.
+      (+) Exit:
+        (++) Any peripheral interrupt acknowledged by the nested vectored interrupt 
+             controller (NVIC) can wake up the device from Sleep mode.
+
+   *** Stop mode ***
+   =================
+    [..]
+      In Stop mode, all clocks in the 1.2V domain are stopped, the PLL, the HSI,
+      and the HSE RC oscillators are disabled. Internal SRAM and register contents 
+      are preserved.
+      The voltage regulator can be configured either in normal or low-power mode.
+      To minimize the consumption In Stop mode, FLASH can be powered off before 
+      entering the Stop mode. It can be switched on again by software after exiting 
+      the Stop mode using the PWR_FlashPowerDownCmd() function. 
+   
+      (+) Entry:
+        (++) The Stop mode is entered using the PWR_EnterSTOPMode(PWR_MainRegulator_ON) 
+             function with:
+          (+++) Main regulator ON.
+          (+++) Low Power regulator ON.
+      (+) Exit:
+        (++) Any EXTI Line (Internal or External) configured in Interrupt/Event mode.
+      
+   *** Standby mode ***
+   ====================
+    [..]
+      The Standby mode allows to achieve the lowest power consumption. It is based 
+      on the Cortex-M4 deepsleep mode, with the voltage regulator disabled. 
+      The 1.2V domain is consequently powered off. The PLL, the HSI oscillator and 
+      the HSE oscillator are also switched off. SRAM and register contents are lost 
+      except for the RTC registers, RTC backup registers, backup SRAM and Standby 
+      circuitry.
+   
+      The voltage regulator is OFF.
+      
+      (+) Entry:
+        (++) The Standby mode is entered using the PWR_EnterSTANDBYMode() function.
+      (+) Exit:
+        (++) WKUP pin rising edge, RTC alarm (Alarm A and Alarm B), RTC wakeup,
+             tamper event, time-stamp event, external reset in NRST pin, IWDG reset.              
+
+   *** Auto-wakeup (AWU) from low-power mode ***
+   =============================================
+    [..]
+      The MCU can be woken up from low-power mode by an RTC Alarm event, an RTC 
+      Wakeup event, a tamper event, a time-stamp event, or a comparator event, 
+      without depending on an external interrupt (Auto-wakeup mode).
+
+      (#) RTC auto-wakeup (AWU) from the Stop mode
+       
+        (++) To wake up from the Stop mode with an RTC alarm event, it is necessary to:
+          (+++) Configure the EXTI Line 17 to be sensitive to rising edges (Interrupt 
+                or Event modes) using the EXTI_Init() function.
+          (+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function
+          (+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm() 
+                and RTC_AlarmCmd() functions.
+        (++) To wake up from the Stop mode with an RTC Tamper or time stamp event, it 
+             is necessary to:
+          (+++) Configure the EXTI Line 21 to be sensitive to rising edges (Interrupt 
+                or Event modes) using the EXTI_Init() function.
+          (+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig() 
+                function
+          (+++) Configure the RTC to detect the tamper or time stamp event using the
+                RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
+                functions.
+        (++) To wake up from the Stop mode with an RTC WakeUp event, it is necessary to:
+           (+++) Configure the EXTI Line 22 to be sensitive to rising edges (Interrupt 
+                 or Event modes) using the EXTI_Init() function.
+           (+++) Enable the RTC WakeUp Interrupt using the RTC_ITConfig() function
+           (+++) Configure the RTC to generate the RTC WakeUp event using the RTC_WakeUpClockConfig(), 
+                 RTC_SetWakeUpCounter() and RTC_WakeUpCmd() functions.
+
+      (#) RTC auto-wakeup (AWU) from the Standby mode
+   
+        (++) To wake up from the Standby mode with an RTC alarm event, it is necessary to:
+          (+++) Enable the RTC Alarm Interrupt using the RTC_ITConfig() function
+          (+++) Configure the RTC to generate the RTC alarm using the RTC_SetAlarm() 
+                and RTC_AlarmCmd() functions.
+        (++) To wake up from the Standby mode with an RTC Tamper or time stamp event, it 
+             is necessary to:
+          (+++) Enable the RTC Tamper or time stamp Interrupt using the RTC_ITConfig() 
+                function
+          (+++) Configure the RTC to detect the tamper or time stamp event using the
+                RTC_TimeStampConfig(), RTC_TamperTriggerConfig() and RTC_TamperCmd()
+                functions.
+        (++) To wake up from the Standby mode with an RTC WakeUp event, it is necessary to:
+          (+++) Enable the RTC WakeUp Interrupt using the RTC_ITConfig() function
+          (+++) Configure the RTC to generate the RTC WakeUp event using the RTC_WakeUpClockConfig(), 
+                RTC_SetWakeUpCounter() and RTC_WakeUpCmd() functions.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enters STOP mode.
+  *   
+  * @note   In Stop mode, all I/O pins keep the same state as in Run mode.
+  * @note   When exiting Stop mode by issuing an interrupt or a wakeup event, 
+  *         the HSI RC oscillator is selected as system clock.
+  * @note   When the voltage regulator operates in low power mode, an additional 
+  *         startup delay is incurred when waking up from Stop mode. 
+  *         By keeping the internal regulator ON during Stop mode, the consumption 
+  *         is higher although the startup time is reduced.
+  *     
+  * @param  PWR_Regulator: specifies the regulator state in STOP mode.
+  *          This parameter can be one of the following values:
+  *            @arg PWR_MainRegulator_ON: STOP mode with regulator ON
+  *            @arg PWR_LowPowerRegulator_ON: STOP mode with low power regulator ON
+  * @param  PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction.
+  *          This parameter can be one of the following values:
+  *            @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
+  *            @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
+  * @retval None
+  */
+void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_PWR_REGULATOR(PWR_Regulator));
+  assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
+  
+  /* Select the regulator state in STOP mode ---------------------------------*/
+  tmpreg = PWR->CR;
+  /* Clear PDDS and LPDS bits */
+  tmpreg &= CR_DS_MASK;
+  
+  /* Set LPDS, MRLVDS and LPLVDS bits according to PWR_Regulator value */
+  tmpreg |= PWR_Regulator;
+  
+  /* Store the new value */
+  PWR->CR = tmpreg;
+  
+  /* Set SLEEPDEEP bit of Cortex System Control Register */
+  SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+  
+  /* Select STOP mode entry --------------------------------------------------*/
+  if(PWR_STOPEntry == PWR_STOPEntry_WFI)
+  {   
+    /* Request Wait For Interrupt */
+    __WFI();
+  }
+  else
+  {
+    /* Request Wait For Event */
+    __WFE();
+  }
+  /* Reset SLEEPDEEP bit of Cortex System Control Register */
+  SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);  
+}
+
+/**
+  * @brief  Enters in Under-Drive STOP mode.
+  *  
+  * @note   This mode is only available for STM32F42xxx/STM3243xxx devices. 
+  * 
+  * @note    This mode can be selected only when the Under-Drive is already active 
+  *         
+  * @note   In Stop mode, all I/O pins keep the same state as in Run mode.
+  * @note   When exiting Stop mode by issuing an interrupt or a wakeup event, 
+  *         the HSI RC oscillator is selected as system clock.
+  * @note   When the voltage regulator operates in low power mode, an additional 
+  *         startup delay is incurred when waking up from Stop mode. 
+  *         By keeping the internal regulator ON during Stop mode, the consumption 
+  *         is higher although the startup time is reduced.
+  *     
+  * @param  PWR_Regulator: specifies the regulator state in STOP mode.
+  *          This parameter can be one of the following values:
+  *            @arg PWR_MainRegulator_UnderDrive_ON:  Main Regulator in under-drive mode 
+  *                 and Flash memory in power-down when the device is in Stop under-drive mode
+  *            @arg PWR_LowPowerRegulator_UnderDrive_ON:  Low Power Regulator in under-drive mode 
+  *                and Flash memory in power-down when the device is in Stop under-drive mode
+  * @param  PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction.
+  *          This parameter can be one of the following values:
+  *            @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction
+  *            @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction
+  * @retval None
+  */
+void PWR_EnterUnderDriveSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_PWR_REGULATOR_UNDERDRIVE(PWR_Regulator));
+  assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry));
+  
+  /* Select the regulator state in STOP mode ---------------------------------*/
+  tmpreg = PWR->CR;
+  /* Clear PDDS and LPDS bits */
+  tmpreg &= CR_DS_MASK;
+  
+  /* Set LPDS, MRLUDS and LPLUDS bits according to PWR_Regulator value */
+  tmpreg |= PWR_Regulator;
+  
+  /* Store the new value */
+  PWR->CR = tmpreg;
+  
+  /* Set SLEEPDEEP bit of Cortex System Control Register */
+  SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+  
+  /* Select STOP mode entry --------------------------------------------------*/
+  if(PWR_STOPEntry == PWR_STOPEntry_WFI)
+  {   
+    /* Request Wait For Interrupt */
+    __WFI();
+  }
+  else
+  {
+    /* Request Wait For Event */
+    __WFE();
+  }
+  /* Reset SLEEPDEEP bit of Cortex System Control Register */
+  SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP_Msk);  
+}
+
+/**
+  * @brief  Enters STANDBY mode.
+  * @note   In Standby mode, all I/O pins are high impedance except for:
+  *          - Reset pad (still available) 
+  *          - RTC_AF1 pin (PC13) if configured for tamper, time-stamp, RTC 
+  *            Alarm out, or RTC clock calibration out.
+  *          - RTC_AF2 pin (PI8) if configured for tamper or time-stamp.  
+  *          - WKUP pin 1 (PA0) if enabled.       
+  * @param  None
+  * @retval None
+  */
+void PWR_EnterSTANDBYMode(void)
+{
+  /* Clear Wakeup flag */
+  PWR->CR |= PWR_CR_CWUF;
+  
+  /* Select STANDBY mode */
+  PWR->CR |= PWR_CR_PDDS;
+  
+  /* Set SLEEPDEEP bit of Cortex System Control Register */
+  SCB->SCR |= SCB_SCR_SLEEPDEEP_Msk;
+  
+/* This option is used to ensure that store operations are completed */
+#if defined ( __CC_ARM   )
+  __force_stores();
+#endif
+  /* Request Wait For Interrupt */
+  __WFI();
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup PWR_Group7 Flags management functions
+ *  @brief   Flags management functions 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### Flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Checks whether the specified PWR flag is set or not.
+  * @param  PWR_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event 
+  *                  was received from the WKUP pin or from the RTC alarm (Alarm A 
+  *                  or Alarm B), RTC Tamper event, RTC TimeStamp event or RTC Wakeup.
+  *                  An additional wakeup event is detected if the WKUP pin is enabled 
+  *                  (by setting the EWUP bit) when the WKUP pin level is already high.  
+  *            @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was
+  *                  resumed from StandBy mode.    
+  *            @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled 
+  *                  by the PWR_PVDCmd() function. The PVD is stopped by Standby mode 
+  *                  For this reason, this bit is equal to 0 after Standby or reset
+  *                  until the PVDE bit is set.
+  *            @arg PWR_FLAG_BRR: Backup regulator ready flag. This bit is not reset 
+  *                  when the device wakes up from Standby mode or by a system reset 
+  *                  or power reset.  
+  *            @arg PWR_FLAG_VOSRDY: This flag indicates that the Regulator voltage 
+  *                 scaling output selection is ready.
+  *            @arg PWR_FLAG_ODRDY: This flag indicates that the Over-drive mode
+  *                 is ready (STM32F42xxx/43xxx devices) 
+  *            @arg PWR_FLAG_ODSWRDY: This flag indicates that the Over-drive mode
+  *                 switcching is ready (STM32F42xxx/43xxx devices) 
+  *            @arg PWR_FLAG_UDRDY: This flag indicates that the Under-drive mode
+  *                 is enabled in Stop mode (STM32F42xxx/43xxx devices)
+  * @retval The new state of PWR_FLAG (SET or RESET).
+  */
+FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_PWR_GET_FLAG(PWR_FLAG));
+  
+  if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the PWR's pending flags.
+  * @param  PWR_FLAG: specifies the flag to clear.
+  *          This parameter can be one of the following values:
+  *            @arg PWR_FLAG_WU: Wake Up flag
+  *            @arg PWR_FLAG_SB: StandBy flag
+  *            @arg PWR_FLAG_UDRDY: Under-drive ready flag (STM32F42xxx/43xxx devices)
+  * @retval None
+  */
+void PWR_ClearFlag(uint32_t PWR_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG));
+  
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+  if (PWR_FLAG != PWR_FLAG_UDRDY)
+  {
+    PWR->CR |=  PWR_FLAG << 2;
+  }
+  else
+  {
+    PWR->CSR |= PWR_FLAG_UDRDY;
+  }
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+#if defined (STM32F40_41xxx) || defined (STM32F401xx) 
+  PWR->CR |=  PWR_FLAG << 2;
+#endif /* STM32F40_41xxx */
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c
new file mode 100644
index 0000000000000000000000000000000000000000..4c5b47b3fba78ca59a67759f72898242f82eb1b4
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c
@@ -0,0 +1,2217 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_rcc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Reset and clock control (RCC) peripheral:
+  *           + Internal/external clocks, PLL, CSS and MCO configuration
+  *           + System, AHB and APB busses clocks configuration
+  *           + Peripheral clocks configuration
+  *           + Interrupts and flags management
+  *
+ @verbatim                
+ ===============================================================================
+                      ##### RCC specific features #####
+ ===============================================================================
+    [..]  
+      After reset the device is running from Internal High Speed oscillator 
+      (HSI 16MHz) with Flash 0 wait state, Flash prefetch buffer, D-Cache 
+      and I-Cache are disabled, and all peripherals are off except internal
+      SRAM, Flash and JTAG.
+      (+) There is no prescaler on High speed (AHB) and Low speed (APB) busses;
+          all peripherals mapped on these busses are running at HSI speed.
+      (+) The clock for all peripherals is switched off, except the SRAM and FLASH.
+      (+) All GPIOs are in input floating state, except the JTAG pins which
+          are assigned to be used for debug purpose.
+    [..]          
+      Once the device started from reset, the user application has to:        
+      (+) Configure the clock source to be used to drive the System clock
+          (if the application needs higher frequency/performance)
+      (+) Configure the System clock frequency and Flash settings  
+      (+) Configure the AHB and APB busses prescalers
+      (+) Enable the clock for the peripheral(s) to be used
+      (+) Configure the clock source(s) for peripherals which clocks are not
+          derived from the System clock (I2S, RTC, ADC, USB OTG FS/SDIO/RNG)                                
+ @endverbatim    
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup RCC 
+  * @brief RCC driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ RCC registers bit address in the alias region ----------- */
+#define RCC_OFFSET                (RCC_BASE - PERIPH_BASE)
+/* --- CR Register ---*/
+/* Alias word address of HSION bit */
+#define CR_OFFSET                 (RCC_OFFSET + 0x00)
+#define HSION_BitNumber           0x00
+#define CR_HSION_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4))
+/* Alias word address of CSSON bit */
+#define CSSON_BitNumber           0x13
+#define CR_CSSON_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4))
+/* Alias word address of PLLON bit */
+#define PLLON_BitNumber           0x18
+#define CR_PLLON_BB               (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4))
+/* Alias word address of PLLI2SON bit */
+#define PLLI2SON_BitNumber        0x1A
+#define CR_PLLI2SON_BB            (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLI2SON_BitNumber * 4))
+
+/* Alias word address of PLLSAION bit */
+#define PLLSAION_BitNumber        0x1C
+#define CR_PLLSAION_BB            (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLSAION_BitNumber * 4))
+
+/* --- CFGR Register ---*/
+/* Alias word address of I2SSRC bit */
+#define CFGR_OFFSET               (RCC_OFFSET + 0x08)
+#define I2SSRC_BitNumber          0x17
+#define CFGR_I2SSRC_BB            (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (I2SSRC_BitNumber * 4))
+
+/* --- BDCR Register ---*/
+/* Alias word address of RTCEN bit */
+#define BDCR_OFFSET               (RCC_OFFSET + 0x70)
+#define RTCEN_BitNumber           0x0F
+#define BDCR_RTCEN_BB             (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4))
+/* Alias word address of BDRST bit */
+#define BDRST_BitNumber           0x10
+#define BDCR_BDRST_BB             (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4))
+
+/* --- CSR Register ---*/
+/* Alias word address of LSION bit */
+#define CSR_OFFSET                (RCC_OFFSET + 0x74)
+#define LSION_BitNumber           0x00
+#define CSR_LSION_BB              (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4))
+
+/* --- DCKCFGR Register ---*/
+/* Alias word address of TIMPRE bit */
+#define DCKCFGR_OFFSET            (RCC_OFFSET + 0x8C)
+#define TIMPRE_BitNumber          0x18
+#define DCKCFGR_TIMPRE_BB         (PERIPH_BB_BASE + (DCKCFGR_OFFSET * 32) + (TIMPRE_BitNumber * 4))
+/* ---------------------- RCC registers bit mask ------------------------ */
+/* CFGR register bit mask */
+#define CFGR_MCO2_RESET_MASK      ((uint32_t)0x07FFFFFF)
+#define CFGR_MCO1_RESET_MASK      ((uint32_t)0xF89FFFFF)
+
+/* RCC Flag Mask */
+#define FLAG_MASK                 ((uint8_t)0x1F)
+
+/* CR register byte 3 (Bits[23:16]) base address */
+#define CR_BYTE3_ADDRESS          ((uint32_t)0x40023802)
+
+/* CIR register byte 2 (Bits[15:8]) base address */
+#define CIR_BYTE2_ADDRESS         ((uint32_t)(RCC_BASE + 0x0C + 0x01))
+
+/* CIR register byte 3 (Bits[23:16]) base address */
+#define CIR_BYTE3_ADDRESS         ((uint32_t)(RCC_BASE + 0x0C + 0x02))
+
+/* BDCR register base address */
+#define BDCR_ADDRESS              (PERIPH_BASE + BDCR_OFFSET)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup RCC_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup RCC_Group1 Internal and external clocks, PLL, CSS and MCO configuration functions
+ *  @brief   Internal and external clocks, PLL, CSS and MCO configuration functions 
+ *
+@verbatim   
+ ===================================================================================
+ ##### Internal and  external clocks, PLL, CSS and MCO configuration functions #####
+ ===================================================================================  
+    [..]
+      This section provide functions allowing to configure the internal/external clocks,
+      PLLs, CSS and MCO pins.
+  
+      (#) HSI (high-speed internal), 16 MHz factory-trimmed RC used directly or through
+          the PLL as System clock source.
+
+      (#) LSI (low-speed internal), 32 KHz low consumption RC used as IWDG and/or RTC
+          clock source.
+
+      (#) HSE (high-speed external), 4 to 26 MHz crystal oscillator used directly or
+          through the PLL as System clock source. Can be used also as RTC clock source.
+
+      (#) LSE (low-speed external), 32 KHz oscillator used as RTC clock source.   
+
+      (#) PLL (clocked by HSI or HSE), featuring two different output clocks:
+        (++) The first output is used to generate the high speed system clock (up to 168 MHz)
+        (++) The second output is used to generate the clock for the USB OTG FS (48 MHz),
+             the random analog generator (<=48 MHz) and the SDIO (<= 48 MHz).
+
+      (#) PLLI2S (clocked by HSI or HSE), used to generate an accurate clock to achieve 
+          high-quality audio performance on the I2S interface or SAI interface in case 
+          of STM32F429x/439x devices.
+     
+      (#) PLLSAI clocked by (HSI or HSE), used to generate an accurate clock to SAI 
+          interface and LCD TFT controller available only for STM32F42xxx/43xxx devices.
+  
+      (#) CSS (Clock security system), once enable and if a HSE clock failure occurs 
+         (HSE used directly or through PLL as System clock source), the System clock
+         is automatically switched to HSI and an interrupt is generated if enabled. 
+         The interrupt is linked to the Cortex-M4 NMI (Non-Maskable Interrupt) 
+         exception vector.   
+
+      (#) MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL
+          clock (through a configurable prescaler) on PA8 pin.
+
+      (#) MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or PLLI2S
+          clock (through a configurable prescaler) on PC9 pin.
+ @endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Resets the RCC clock configuration to the default reset state.
+  * @note   The default reset state of the clock configuration is given below:
+  *            - HSI ON and used as system clock source
+  *            - HSE, PLL and PLLI2S OFF
+  *            - AHB, APB1 and APB2 prescaler set to 1.
+  *            - CSS, MCO1 and MCO2 OFF
+  *            - All interrupts disabled
+  * @note   This function doesn't modify the configuration of the
+  *            - Peripheral clocks  
+  *            - LSI, LSE and RTC clocks 
+  * @param  None
+  * @retval None
+  */
+void RCC_DeInit(void)
+{
+  /* Set HSION bit */
+  RCC->CR |= (uint32_t)0x00000001;
+
+  /* Reset CFGR register */
+  RCC->CFGR = 0x00000000;
+
+  /* Reset HSEON, CSSON, PLLON, PLLI2S and PLLSAI(STM32F42/43xxx devices) bits */
+  RCC->CR &= (uint32_t)0xEAF6FFFF;
+
+  /* Reset PLLCFGR register */
+  RCC->PLLCFGR = 0x24003010;
+
+  /* Reset PLLI2SCFGR register */
+  RCC->PLLI2SCFGR = 0x20003000;
+
+  /* Reset PLLSAICFGR register, only available for STM32F42/43xxx devices */
+  RCC->PLLSAICFGR = 0x24003000;
+ 
+  /* Reset HSEBYP bit */
+  RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+  /* Disable all interrupts */
+  RCC->CIR = 0x00000000;
+
+  /* Disable Timers clock prescalers selection, only available for STM32F42/43xxx devices */
+  RCC->DCKCFGR = 0x00000000; 
+
+}
+
+/**
+  * @brief  Configures the External High Speed oscillator (HSE).
+  * @note   After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application
+  *         software should wait on HSERDY flag to be set indicating that HSE clock
+  *         is stable and can be used to clock the PLL and/or system clock.
+  * @note   HSE state can not be changed if it is used directly or through the
+  *         PLL as system clock. In this case, you have to select another source
+  *         of the system clock then change the HSE state (ex. disable it).
+  * @note   The HSE is stopped by hardware when entering STOP and STANDBY modes.  
+  * @note   This function reset the CSSON bit, so if the Clock security system(CSS)
+  *         was previously enabled you have to enable it again after calling this
+  *         function.    
+  * @param  RCC_HSE: specifies the new state of the HSE.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after
+  *                              6 HSE oscillator clock cycles.
+  *            @arg RCC_HSE_ON: turn ON the HSE oscillator
+  *            @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock
+  * @retval None
+  */
+void RCC_HSEConfig(uint8_t RCC_HSE)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_HSE(RCC_HSE));
+
+  /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/
+  *(__IO uint8_t *) CR_BYTE3_ADDRESS = RCC_HSE_OFF;
+
+  /* Set the new HSE configuration -------------------------------------------*/
+  *(__IO uint8_t *) CR_BYTE3_ADDRESS = RCC_HSE;
+}
+
+/**
+  * @brief  Waits for HSE start-up.
+  * @note   This functions waits on HSERDY flag to be set and return SUCCESS if 
+  *         this flag is set, otherwise returns ERROR if the timeout is reached 
+  *         and this flag is not set. The timeout value is defined by the constant
+  *         HSE_STARTUP_TIMEOUT in stm32f4xx.h file. You can tailor it depending
+  *         on the HSE crystal used in your application. 
+  * @param  None
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: HSE oscillator is stable and ready to use
+  *          - ERROR: HSE oscillator not yet ready
+  */
+ErrorStatus RCC_WaitForHSEStartUp(void)
+{
+  __IO uint32_t startupcounter = 0;
+  ErrorStatus status = ERROR;
+  FlagStatus hsestatus = RESET;
+  /* Wait till HSE is ready and if Time out is reached exit */
+  do
+  {
+    hsestatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY);
+    startupcounter++;
+  } while((startupcounter != HSE_STARTUP_TIMEOUT) && (hsestatus == RESET));
+
+  if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET)
+  {
+    status = SUCCESS;
+  }
+  else
+  {
+    status = ERROR;
+  }
+  return (status);
+}
+
+/**
+  * @brief  Adjusts the Internal High Speed oscillator (HSI) calibration value.
+  * @note   The calibration is used to compensate for the variations in voltage
+  *         and temperature that influence the frequency of the internal HSI RC.
+  * @param  HSICalibrationValue: specifies the calibration trimming value.
+  *         This parameter must be a number between 0 and 0x1F.
+  * @retval None
+  */
+void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue));
+
+  tmpreg = RCC->CR;
+
+  /* Clear HSITRIM[4:0] bits */
+  tmpreg &= ~RCC_CR_HSITRIM;
+
+  /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */
+  tmpreg |= (uint32_t)HSICalibrationValue << 3;
+
+  /* Store the new value */
+  RCC->CR = tmpreg;
+}
+
+/**
+  * @brief  Enables or disables the Internal High Speed oscillator (HSI).
+  * @note   The HSI is stopped by hardware when entering STOP and STANDBY modes.
+  *         It is used (enabled by hardware) as system clock source after startup
+  *         from Reset, wakeup from STOP and STANDBY mode, or in case of failure
+  *         of the HSE used directly or indirectly as system clock (if the Clock
+  *         Security System CSS is enabled).             
+  * @note   HSI can not be stopped if it is used as system clock source. In this case,
+  *         you have to select another source of the system clock then stop the HSI.  
+  * @note   After enabling the HSI, the application software should wait on HSIRDY
+  *         flag to be set indicating that HSI clock is stable and can be used as
+  *         system clock source.  
+  * @param  NewState: new state of the HSI.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @note   When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator
+  *         clock cycles.  
+  * @retval None
+  */
+void RCC_HSICmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the External Low Speed oscillator (LSE).
+  * @note   As the LSE is in the Backup domain and write access is denied to
+  *         this domain after reset, you have to enable write access using 
+  *         PWR_BackupAccessCmd(ENABLE) function before to configure the LSE
+  *         (to be done once after reset).  
+  * @note   After enabling the LSE (RCC_LSE_ON or RCC_LSE_Bypass), the application
+  *         software should wait on LSERDY flag to be set indicating that LSE clock
+  *         is stable and can be used to clock the RTC.
+  * @param  RCC_LSE: specifies the new state of the LSE.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after
+  *                              6 LSE oscillator clock cycles.
+  *            @arg RCC_LSE_ON: turn ON the LSE oscillator
+  *            @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock
+  * @retval None
+  */
+void RCC_LSEConfig(uint8_t RCC_LSE)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_LSE(RCC_LSE));
+
+  /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/
+  /* Reset LSEON bit */
+  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;
+
+  /* Reset LSEBYP bit */
+  *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF;
+
+  /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */
+  switch (RCC_LSE)
+  {
+    case RCC_LSE_ON:
+      /* Set LSEON bit */
+      *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON;
+      break;
+    case RCC_LSE_Bypass:
+      /* Set LSEBYP and LSEON bits */
+      *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON;
+      break;
+    default:
+      break;
+  }
+}
+
+/**
+  * @brief  Enables or disables the Internal Low Speed oscillator (LSI).
+  * @note   After enabling the LSI, the application software should wait on 
+  *         LSIRDY flag to be set indicating that LSI clock is stable and can
+  *         be used to clock the IWDG and/or the RTC.
+  * @note   LSI can not be disabled if the IWDG is running.  
+  * @param  NewState: new state of the LSI.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @note   When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator
+  *         clock cycles. 
+  * @retval None
+  */
+void RCC_LSICmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the main PLL clock source, multiplication and division factors.
+  * @note   This function must be used only when the main PLL is disabled.
+  *  
+  * @param  RCC_PLLSource: specifies the PLL entry clock source.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_PLLSource_HSI: HSI oscillator clock selected as PLL clock entry
+  *            @arg RCC_PLLSource_HSE: HSE oscillator clock selected as PLL clock entry
+  * @note   This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S.  
+  *  
+  * @param  PLLM: specifies the division factor for PLL VCO input clock
+  *          This parameter must be a number between 0 and 63.
+  * @note   You have to set the PLLM parameter correctly to ensure that the VCO input
+  *         frequency ranges from 1 to 2 MHz. It is recommended to select a frequency
+  *         of 2 MHz to limit PLL jitter.
+  *  
+  * @param  PLLN: specifies the multiplication factor for PLL VCO output clock
+  *          This parameter must be a number between 192 and 432.
+  * @note   You have to set the PLLN parameter correctly to ensure that the VCO
+  *         output frequency is between 192 and 432 MHz.
+  *   
+  * @param  PLLP: specifies the division factor for main system clock (SYSCLK)
+  *          This parameter must be a number in the range {2, 4, 6, or 8}.
+  * @note   You have to set the PLLP parameter correctly to not exceed 168 MHz on
+  *         the System clock frequency.
+  *  
+  * @param  PLLQ: specifies the division factor for OTG FS, SDIO and RNG clocks
+  *          This parameter must be a number between 4 and 15.
+  * @note   If the USB OTG FS is used in your application, you have to set the
+  *         PLLQ parameter correctly to have 48 MHz clock for the USB. However,
+  *         the SDIO and RNG need a frequency lower than or equal to 48 MHz to work
+  *         correctly.
+  *   
+  * @retval None
+  */
+void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP, uint32_t PLLQ)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource));
+  assert_param(IS_RCC_PLLM_VALUE(PLLM));
+  assert_param(IS_RCC_PLLN_VALUE(PLLN));
+  assert_param(IS_RCC_PLLP_VALUE(PLLP));
+  assert_param(IS_RCC_PLLQ_VALUE(PLLQ));
+
+  RCC->PLLCFGR = PLLM | (PLLN << 6) | (((PLLP >> 1) -1) << 16) | (RCC_PLLSource) |
+                 (PLLQ << 24);
+}
+
+/**
+  * @brief  Enables or disables the main PLL.
+  * @note   After enabling the main PLL, the application software should wait on 
+  *         PLLRDY flag to be set indicating that PLL clock is stable and can
+  *         be used as system clock source.
+  * @note   The main PLL can not be disabled if it is used as system clock source
+  * @note   The main PLL is disabled by hardware when entering STOP and STANDBY modes.
+  * @param  NewState: new state of the main PLL. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_PLLCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState;
+}
+
+#if defined (STM32F40_41xxx) || defined (STM32F401xx)
+/**
+  * @brief  Configures the PLLI2S clock multiplication and division factors.
+  *  
+  * @note   This function can be used only for STM32F405xx/407xx, STM32F415xx/417xx 
+  *         or STM32F401xx devices. 
+  *    
+  * @note   This function must be used only when the PLLI2S is disabled.
+  * @note   PLLI2S clock source is common with the main PLL (configured in 
+  *         RCC_PLLConfig function )  
+  *             
+  * @param  PLLI2SN: specifies the multiplication factor for PLLI2S VCO output clock
+  *          This parameter must be a number between 192 and 432.
+  * @note   You have to set the PLLI2SN parameter correctly to ensure that the VCO 
+  *         output frequency is between 192 and 432 MHz.
+  *    
+  * @param  PLLI2SR: specifies the division factor for I2S clock
+  *          This parameter must be a number between 2 and 7.
+  * @note   You have to set the PLLI2SR parameter correctly to not exceed 192 MHz
+  *         on the I2S clock frequency.
+  *   
+  * @retval None
+  */
+void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SR)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SN));
+  assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SR));
+
+  RCC->PLLI2SCFGR = (PLLI2SN << 6) | (PLLI2SR << 28);
+}
+#endif /* STM32F40_41xxx || STM32F401xx */
+
+#if defined (STM32F427_437xx) || defined (STM32F429_439xx)
+/**
+  * @brief  Configures the PLLI2S clock multiplication and division factors.
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx devices 
+  *         
+  * @note   This function must be used only when the PLLI2S is disabled.
+  * @note   PLLI2S clock source is common with the main PLL (configured in 
+  *         RCC_PLLConfig function )  
+  *             
+  * @param  PLLI2SN: specifies the multiplication factor for PLLI2S VCO output clock
+  *          This parameter must be a number between 192 and 432.
+  * @note   You have to set the PLLI2SN parameter correctly to ensure that the VCO 
+  *         output frequency is between 192 and 432 MHz.
+  * 
+  * @param  PLLI2SQ: specifies the division factor for SAI1 clock
+  *          This parameter must be a number between 2 and 15.
+  *                 
+  * @param  PLLI2SR: specifies the division factor for I2S clock
+  *          This parameter must be a number between 2 and 7.
+  * @note   You have to set the PLLI2SR parameter correctly to not exceed 192 MHz
+  *         on the I2S clock frequency.
+  * @note   the PLLI2SR parameter is only available with STM32F42xxx/43xxx devices.  
+  *   
+  * @retval None
+  */
+void RCC_PLLI2SConfig(uint32_t PLLI2SN, uint32_t PLLI2SQ, uint32_t PLLI2SR)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_PLLI2SN_VALUE(PLLI2SN));
+  assert_param(IS_RCC_PLLI2SQ_VALUE(PLLI2SQ));
+  assert_param(IS_RCC_PLLI2SR_VALUE(PLLI2SR));
+
+  RCC->PLLI2SCFGR = (PLLI2SN << 6) | (PLLI2SQ << 24) | (PLLI2SR << 28);
+}
+#endif /* STM32F427_437xx ||  STM32F429_439xx */
+
+/**
+  * @brief  Enables or disables the PLLI2S. 
+  * @note   The PLLI2S is disabled by hardware when entering STOP and STANDBY modes.  
+  * @param  NewState: new state of the PLLI2S. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_PLLI2SCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_PLLI2SON_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the PLLSAI clock multiplication and division factors.
+  *
+  * @note   This function can be used only for STM32F42xxx/43xxx devices 
+  *        
+  * @note   This function must be used only when the PLLSAI is disabled.
+  * @note   PLLSAI clock source is common with the main PLL (configured in 
+  *         RCC_PLLConfig function )  
+  *             
+  * @param  PLLSAIN: specifies the multiplication factor for PLLSAI VCO output clock
+  *          This parameter must be a number between 192 and 432.
+  * @note   You have to set the PLLSAIN parameter correctly to ensure that the VCO 
+  *         output frequency is between 192 and 432 MHz.
+  *           
+  * @param  PLLSAIQ: specifies the division factor for SAI1 clock
+  *          This parameter must be a number between 2 and 15.
+  *            
+  * @param  PLLSAIR: specifies the division factor for LTDC clock
+  *          This parameter must be a number between 2 and 7.
+  *   
+  * @retval None
+  */
+void RCC_PLLSAIConfig(uint32_t PLLSAIN, uint32_t PLLSAIQ, uint32_t PLLSAIR)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_PLLSAIN_VALUE(PLLSAIN));
+  assert_param(IS_RCC_PLLSAIR_VALUE(PLLSAIR));
+
+  RCC->PLLSAICFGR = (PLLSAIN << 6) | (PLLSAIQ << 24) | (PLLSAIR << 28);
+}
+
+/**
+  * @brief  Enables or disables the PLLSAI. 
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx devices 
+  *       
+  * @note   The PLLSAI is disabled by hardware when entering STOP and STANDBY modes.  
+  * @param  NewState: new state of the PLLSAI. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_PLLSAICmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_PLLSAION_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the Clock Security System.
+  * @note   If a failure is detected on the HSE oscillator clock, this oscillator
+  *         is automatically disabled and an interrupt is generated to inform the
+  *         software about the failure (Clock Security System Interrupt, CSSI),
+  *         allowing the MCU to perform rescue operations. The CSSI is linked to 
+  *         the Cortex-M4 NMI (Non-Maskable Interrupt) exception vector.  
+  * @param  NewState: new state of the Clock Security System.
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_ClockSecuritySystemCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Selects the clock source to output on MCO1 pin(PA8).
+  * @note   PA8 should be configured in alternate function mode.
+  * @param  RCC_MCO1Source: specifies the clock source to output.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_MCO1Source_HSI: HSI clock selected as MCO1 source
+  *            @arg RCC_MCO1Source_LSE: LSE clock selected as MCO1 source
+  *            @arg RCC_MCO1Source_HSE: HSE clock selected as MCO1 source
+  *            @arg RCC_MCO1Source_PLLCLK: main PLL clock selected as MCO1 source
+  * @param  RCC_MCO1Div: specifies the MCO1 prescaler.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_MCO1Div_1: no division applied to MCO1 clock
+  *            @arg RCC_MCO1Div_2: division by 2 applied to MCO1 clock
+  *            @arg RCC_MCO1Div_3: division by 3 applied to MCO1 clock
+  *            @arg RCC_MCO1Div_4: division by 4 applied to MCO1 clock
+  *            @arg RCC_MCO1Div_5: division by 5 applied to MCO1 clock
+  * @retval None
+  */
+void RCC_MCO1Config(uint32_t RCC_MCO1Source, uint32_t RCC_MCO1Div)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_MCO1SOURCE(RCC_MCO1Source));
+  assert_param(IS_RCC_MCO1DIV(RCC_MCO1Div));  
+
+  tmpreg = RCC->CFGR;
+
+  /* Clear MCO1[1:0] and MCO1PRE[2:0] bits */
+  tmpreg &= CFGR_MCO1_RESET_MASK;
+
+  /* Select MCO1 clock source and prescaler */
+  tmpreg |= RCC_MCO1Source | RCC_MCO1Div;
+
+  /* Store the new value */
+  RCC->CFGR = tmpreg;  
+}
+
+/**
+  * @brief  Selects the clock source to output on MCO2 pin(PC9).
+  * @note   PC9 should be configured in alternate function mode.
+  * @param  RCC_MCO2Source: specifies the clock source to output.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_MCO2Source_SYSCLK: System clock (SYSCLK) selected as MCO2 source
+  *            @arg RCC_MCO2Source_PLLI2SCLK: PLLI2S clock selected as MCO2 source
+  *            @arg RCC_MCO2Source_HSE: HSE clock selected as MCO2 source
+  *            @arg RCC_MCO2Source_PLLCLK: main PLL clock selected as MCO2 source
+  * @param  RCC_MCO2Div: specifies the MCO2 prescaler.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_MCO2Div_1: no division applied to MCO2 clock
+  *            @arg RCC_MCO2Div_2: division by 2 applied to MCO2 clock
+  *            @arg RCC_MCO2Div_3: division by 3 applied to MCO2 clock
+  *            @arg RCC_MCO2Div_4: division by 4 applied to MCO2 clock
+  *            @arg RCC_MCO2Div_5: division by 5 applied to MCO2 clock
+  * @retval None
+  */
+void RCC_MCO2Config(uint32_t RCC_MCO2Source, uint32_t RCC_MCO2Div)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_MCO2SOURCE(RCC_MCO2Source));
+  assert_param(IS_RCC_MCO2DIV(RCC_MCO2Div));
+  
+  tmpreg = RCC->CFGR;
+  
+  /* Clear MCO2 and MCO2PRE[2:0] bits */
+  tmpreg &= CFGR_MCO2_RESET_MASK;
+
+  /* Select MCO2 clock source and prescaler */
+  tmpreg |= RCC_MCO2Source | RCC_MCO2Div;
+
+  /* Store the new value */
+  RCC->CFGR = tmpreg;  
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Group2 System AHB and APB busses clocks configuration functions
+ *  @brief   System, AHB and APB busses clocks configuration functions
+ *
+@verbatim   
+ ===============================================================================
+      ##### System, AHB and APB busses clocks configuration functions #####
+ ===============================================================================  
+    [..]
+      This section provide functions allowing to configure the System, AHB, APB1 and 
+      APB2 busses clocks.
+  
+      (#) Several clock sources can be used to drive the System clock (SYSCLK): HSI,
+          HSE and PLL.
+          The AHB clock (HCLK) is derived from System clock through configurable 
+          prescaler and used to clock the CPU, memory and peripherals mapped 
+          on AHB bus (DMA, GPIO...). APB1 (PCLK1) and APB2 (PCLK2) clocks are derived 
+          from AHB clock through configurable prescalers and used to clock 
+          the peripherals mapped on these busses. You can use 
+          "RCC_GetClocksFreq()" function to retrieve the frequencies of these clocks.  
+
+      -@- All the peripheral clocks are derived from the System clock (SYSCLK) except:
+        (+@) I2S: the I2S clock can be derived either from a specific PLL (PLLI2S) or
+             from an external clock mapped on the I2S_CKIN pin. 
+             You have to use RCC_I2SCLKConfig() function to configure this clock. 
+        (+@) RTC: the RTC clock can be derived either from the LSI, LSE or HSE clock
+             divided by 2 to 31. You have to use RCC_RTCCLKConfig() and RCC_RTCCLKCmd()
+             functions to configure this clock. 
+        (+@) USB OTG FS, SDIO and RTC: USB OTG FS require a frequency equal to 48 MHz
+             to work correctly, while the SDIO require a frequency equal or lower than
+             to 48. This clock is derived of the main PLL through PLLQ divider.
+        (+@) IWDG clock which is always the LSI clock.
+       
+      (#) For STM32F405xx/407xx and STM32F415xx/417xx devices, the maximum frequency 
+         of the SYSCLK and HCLK is 168 MHz, PCLK2 84 MHz and PCLK1 42 MHz. Depending 
+         on the device voltage range, the maximum frequency should be adapted accordingly:
+ +-------------------------------------------------------------------------------------+     
+ | Latency       |                HCLK clock frequency (MHz)                           |
+ |               |---------------------------------------------------------------------|     
+ |               | voltage range  | voltage range  | voltage range   | voltage range   |
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   |
+ |---------------|----------------|----------------|-----------------|-----------------|              
+ |0WS(1CPU cycle)|0 < HCLK <= 30  |0 < HCLK <= 24  |0 < HCLK <= 22   |0 < HCLK <= 20   |
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44  |20 < HCLK <= 40  | 
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |44 < HCLK <= 66  |40 < HCLK <= 60  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |66 < HCLK <= 88  |60 < HCLK <= 80  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|88 < HCLK <= 110 |80 < HCLK <= 100 |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |5WS(6CPU cycle)|150< HCLK <= 168|120< HCLK <= 144|110 < HCLK <= 132|100 < HCLK <= 120| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |6WS(7CPU cycle)|      NA        |144< HCLK <= 168|132 < HCLK <= 154|120 < HCLK <= 140| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |7WS(8CPU cycle)|      NA        |      NA        |154 < HCLK <= 168|140 < HCLK <= 160|
+ +---------------|----------------|----------------|-----------------|-----------------+ 
+      (#) For STM32F42xxx/43xxx devices, the maximum frequency of the SYSCLK and HCLK is 180 MHz, 
+          PCLK2 90 MHz and PCLK1 45 MHz. Depending on the device voltage range, the maximum 
+          frequency should be adapted accordingly:
+ +-------------------------------------------------------------------------------------+     
+ | Latency       |                HCLK clock frequency (MHz)                           |
+ |               |---------------------------------------------------------------------|     
+ |               | voltage range  | voltage range  | voltage range   | voltage range   |
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   |
+ |---------------|----------------|----------------|-----------------|-----------------|              
+ |0WS(1CPU cycle)|0 < HCLK <= 30  |0 < HCLK <= 24  |0 < HCLK <= 22   |0 < HCLK <= 20   |
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44  |20 < HCLK <= 40  | 
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |2WS(3CPU cycle)|60 < HCLK <= 90 |48 < HCLK <= 72 |44 < HCLK <= 66  |40 < HCLK <= 60  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |3WS(4CPU cycle)|90 < HCLK <= 120|72 < HCLK <= 96 |66 < HCLK <= 88  |60 < HCLK <= 80  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |4WS(5CPU cycle)|120< HCLK <= 150|96 < HCLK <= 120|88 < HCLK <= 110 |80 < HCLK <= 100 |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |5WS(6CPU cycle)|120< HCLK <= 180|120< HCLK <= 144|110 < HCLK <= 132|100 < HCLK <= 120| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |6WS(7CPU cycle)|      NA        |144< HCLK <= 168|132 < HCLK <= 154|120 < HCLK <= 140| 
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |7WS(8CPU cycle)|      NA        |168< HCLK <= 180|154 < HCLK <= 176|140 < HCLK <= 160|
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |8WS(9CPU cycle)|      NA        |      NA        |176 < HCLK <= 180|160 < HCLK <= 168|
+ +-------------------------------------------------------------------------------------+
+   
+      (#) For STM32F401xx devices, the maximum frequency of the SYSCLK and HCLK is 84 MHz, 
+          PCLK2 84 MHz and PCLK1 42 MHz. Depending on the device voltage range, the maximum 
+          frequency should be adapted accordingly:
+ +-------------------------------------------------------------------------------------+     
+ | Latency       |                HCLK clock frequency (MHz)                           |
+ |               |---------------------------------------------------------------------|     
+ |               | voltage range  | voltage range  | voltage range   | voltage range   |
+ |               | 2.7 V - 3.6 V  | 2.4 V - 2.7 V  | 2.1 V - 2.4 V   | 1.8 V - 2.1 V   |
+ |---------------|----------------|----------------|-----------------|-----------------|              
+ |0WS(1CPU cycle)|0 < HCLK <= 30  |0 < HCLK <= 24  |0 < HCLK <= 22   |0 < HCLK <= 20   |
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |1WS(2CPU cycle)|30 < HCLK <= 60 |24 < HCLK <= 48 |22 < HCLK <= 44  |20 < HCLK <= 40  | 
+ |---------------|----------------|----------------|-----------------|-----------------|   
+ |2WS(3CPU cycle)|60 < HCLK <= 84 |48 < HCLK <= 72 |44 < HCLK <= 66  |40 < HCLK <= 60  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |3WS(4CPU cycle)|      NA        |72 < HCLK <= 84 |66 < HCLK <= 84  |60 < HCLK <= 80  |
+ |---------------|----------------|----------------|-----------------|-----------------| 
+ |4WS(5CPU cycle)|      NA        |      NA        |      NA         |80 < HCLK <= 84  | 
+ +-------------------------------------------------------------------------------------+ 
+  
+      -@- On STM32F405xx/407xx and STM32F415xx/417xx devices: 
+           (++) when VOS = '0', the maximum value of fHCLK = 144MHz. 
+           (++) when VOS = '1', the maximum value of fHCLK = 168MHz. 
+          [..] 
+          On STM32F42xxx/43xxx devices:
+           (++) when VOS[1:0] = '0x01', the maximum value of fHCLK is 120MHz.
+           (++) when VOS[1:0] = '0x10', the maximum value of fHCLK is 144MHz.
+           (++) when VOS[1:0] = '0x11', the maximum value of f  is 168MHz 
+          [..]  
+          On STM32F401x devices:
+           (++) when VOS[1:0] = '0x01', the maximum value of fHCLK is 64MHz.
+           (++) when VOS[1:0] = '0x10', the maximum value of fHCLK is 84MHz.
+           You can use PWR_MainRegulatorModeConfig() function to control VOS bits.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the system clock (SYSCLK).
+  * @note   The HSI is used (enabled by hardware) as system clock source after
+  *         startup from Reset, wake-up from STOP and STANDBY mode, or in case
+  *         of failure of the HSE used directly or indirectly as system clock
+  *         (if the Clock Security System CSS is enabled).
+  * @note   A switch from one clock source to another occurs only if the target
+  *         clock source is ready (clock stable after startup delay or PLL locked). 
+  *         If a clock source which is not yet ready is selected, the switch will
+  *         occur when the clock source will be ready. 
+  *         You can use RCC_GetSYSCLKSource() function to know which clock is
+  *         currently used as system clock source. 
+  * @param  RCC_SYSCLKSource: specifies the clock source used as system clock.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_SYSCLKSource_HSI:    HSI selected as system clock source
+  *            @arg RCC_SYSCLKSource_HSE:    HSE selected as system clock source
+  *            @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock source
+  * @retval None
+  */
+void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource));
+
+  tmpreg = RCC->CFGR;
+
+  /* Clear SW[1:0] bits */
+  tmpreg &= ~RCC_CFGR_SW;
+
+  /* Set SW[1:0] bits according to RCC_SYSCLKSource value */
+  tmpreg |= RCC_SYSCLKSource;
+
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Returns the clock source used as system clock.
+  * @param  None
+  * @retval The clock source used as system clock. The returned value can be one
+  *         of the following:
+  *              - 0x00: HSI used as system clock
+  *              - 0x04: HSE used as system clock
+  *              - 0x08: PLL used as system clock
+  */
+uint8_t RCC_GetSYSCLKSource(void)
+{
+  return ((uint8_t)(RCC->CFGR & RCC_CFGR_SWS));
+}
+
+/**
+  * @brief  Configures the AHB clock (HCLK).
+  * @note   Depending on the device voltage range, the software has to set correctly
+  *         these bits to ensure that HCLK not exceed the maximum allowed frequency
+  *         (for more details refer to section above
+  *           "CPU, AHB and APB busses clocks configuration functions")
+  * @param  RCC_SYSCLK: defines the AHB clock divider. This clock is derived from 
+  *         the system clock (SYSCLK).
+  *          This parameter can be one of the following values:
+  *            @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK
+  *            @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2
+  *            @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4
+  *            @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8
+  *            @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16
+  *            @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64
+  *            @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128
+  *            @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256
+  *            @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512
+  * @retval None
+  */
+void RCC_HCLKConfig(uint32_t RCC_SYSCLK)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_HCLK(RCC_SYSCLK));
+
+  tmpreg = RCC->CFGR;
+
+  /* Clear HPRE[3:0] bits */
+  tmpreg &= ~RCC_CFGR_HPRE;
+
+  /* Set HPRE[3:0] bits according to RCC_SYSCLK value */
+  tmpreg |= RCC_SYSCLK;
+
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+
+/**
+  * @brief  Configures the Low Speed APB clock (PCLK1).
+  * @param  RCC_HCLK: defines the APB1 clock divider. This clock is derived from 
+  *         the AHB clock (HCLK).
+  *          This parameter can be one of the following values:
+  *            @arg RCC_HCLK_Div1:  APB1 clock = HCLK
+  *            @arg RCC_HCLK_Div2:  APB1 clock = HCLK/2
+  *            @arg RCC_HCLK_Div4:  APB1 clock = HCLK/4
+  *            @arg RCC_HCLK_Div8:  APB1 clock = HCLK/8
+  *            @arg RCC_HCLK_Div16: APB1 clock = HCLK/16
+  * @retval None
+  */
+void RCC_PCLK1Config(uint32_t RCC_HCLK)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_PCLK(RCC_HCLK));
+
+  tmpreg = RCC->CFGR;
+
+  /* Clear PPRE1[2:0] bits */
+  tmpreg &= ~RCC_CFGR_PPRE1;
+
+  /* Set PPRE1[2:0] bits according to RCC_HCLK value */
+  tmpreg |= RCC_HCLK;
+
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Configures the High Speed APB clock (PCLK2).
+  * @param  RCC_HCLK: defines the APB2 clock divider. This clock is derived from 
+  *         the AHB clock (HCLK).
+  *          This parameter can be one of the following values:
+  *            @arg RCC_HCLK_Div1:  APB2 clock = HCLK
+  *            @arg RCC_HCLK_Div2:  APB2 clock = HCLK/2
+  *            @arg RCC_HCLK_Div4:  APB2 clock = HCLK/4
+  *            @arg RCC_HCLK_Div8:  APB2 clock = HCLK/8
+  *            @arg RCC_HCLK_Div16: APB2 clock = HCLK/16
+  * @retval None
+  */
+void RCC_PCLK2Config(uint32_t RCC_HCLK)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_PCLK(RCC_HCLK));
+
+  tmpreg = RCC->CFGR;
+
+  /* Clear PPRE2[2:0] bits */
+  tmpreg &= ~RCC_CFGR_PPRE2;
+
+  /* Set PPRE2[2:0] bits according to RCC_HCLK value */
+  tmpreg |= RCC_HCLK << 3;
+
+  /* Store the new value */
+  RCC->CFGR = tmpreg;
+}
+
+/**
+  * @brief  Returns the frequencies of different on chip clocks; SYSCLK, HCLK, 
+  *         PCLK1 and PCLK2.       
+  * 
+  * @note   The system frequency computed by this function is not the real 
+  *         frequency in the chip. It is calculated based on the predefined 
+  *         constant and the selected clock source:
+  * @note     If SYSCLK source is HSI, function returns values based on HSI_VALUE(*)
+  * @note     If SYSCLK source is HSE, function returns values based on HSE_VALUE(**)
+  * @note     If SYSCLK source is PLL, function returns values based on HSE_VALUE(**) 
+  *           or HSI_VALUE(*) multiplied/divided by the PLL factors.         
+  * @note     (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
+  *               16 MHz) but the real value may vary depending on the variations
+  *               in voltage and temperature.
+  * @note     (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
+  *                25 MHz), user has to ensure that HSE_VALUE is same as the real
+  *                frequency of the crystal used. Otherwise, this function may
+  *                have wrong result.
+  *                
+  * @note   The result of this function could be not correct when using fractional
+  *         value for HSE crystal.
+  *   
+  * @param  RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold
+  *          the clocks frequencies.
+  *     
+  * @note   This function can be used by the user application to compute the 
+  *         baudrate for the communication peripherals or configure other parameters.
+  * @note   Each time SYSCLK, HCLK, PCLK1 and/or PCLK2 clock changes, this function
+  *         must be called to update the structure's field. Otherwise, any
+  *         configuration based on this function will be incorrect.
+  *    
+  * @retval None
+  */
+void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks)
+{
+  uint32_t tmp = 0, presc = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+
+  /* Get SYSCLK source -------------------------------------------------------*/
+  tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+  switch (tmp)
+  {
+    case 0x00:  /* HSI used as system clock source */
+      RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
+      break;
+    case 0x04:  /* HSE used as system clock  source */
+      RCC_Clocks->SYSCLK_Frequency = HSE_VALUE;
+      break;
+    case 0x08:  /* PLL used as system clock  source */
+
+      /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
+         SYSCLK = PLL_VCO / PLLP
+         */    
+      pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+      pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+      
+      if (pllsource != 0)
+      {
+        /* HSE used as PLL clock source */
+        pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+      }
+      else
+      {
+        /* HSI used as PLL clock source */
+        pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);      
+      }
+
+      pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+      RCC_Clocks->SYSCLK_Frequency = pllvco/pllp;
+      break;
+    default:
+      RCC_Clocks->SYSCLK_Frequency = HSI_VALUE;
+      break;
+  }
+  /* Compute HCLK, PCLK1 and PCLK2 clocks frequencies ------------------------*/
+
+  /* Get HCLK prescaler */
+  tmp = RCC->CFGR & RCC_CFGR_HPRE;
+  tmp = tmp >> 4;
+  presc = APBAHBPrescTable[tmp];
+  /* HCLK clock frequency */
+  RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc;
+
+  /* Get PCLK1 prescaler */
+  tmp = RCC->CFGR & RCC_CFGR_PPRE1;
+  tmp = tmp >> 10;
+  presc = APBAHBPrescTable[tmp];
+  /* PCLK1 clock frequency */
+  RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+
+  /* Get PCLK2 prescaler */
+  tmp = RCC->CFGR & RCC_CFGR_PPRE2;
+  tmp = tmp >> 13;
+  presc = APBAHBPrescTable[tmp];
+  /* PCLK2 clock frequency */
+  RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Group3 Peripheral clocks configuration functions
+ *  @brief   Peripheral clocks configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Peripheral clocks configuration functions #####
+ ===============================================================================  
+    [..] This section provide functions allowing to configure the Peripheral clocks. 
+  
+      (#) The RTC clock which is derived from the LSI, LSE or HSE clock divided 
+          by 2 to 31.
+     
+      (#) After restart from Reset or wakeup from STANDBY, all peripherals are off
+          except internal SRAM, Flash and JTAG. Before to start using a peripheral 
+          you have to enable its interface clock. You can do this using 
+          RCC_AHBPeriphClockCmd(), RCC_APB2PeriphClockCmd() and RCC_APB1PeriphClockCmd() functions.
+
+      (#) To reset the peripherals configuration (to the default state after device reset)
+          you can use RCC_AHBPeriphResetCmd(), RCC_APB2PeriphResetCmd() and 
+          RCC_APB1PeriphResetCmd() functions.
+     
+      (#) To further reduce power consumption in SLEEP mode the peripheral clocks 
+          can be disabled prior to executing the WFI or WFE instructions. 
+          You can do this using RCC_AHBPeriphClockLPModeCmd(), 
+          RCC_APB2PeriphClockLPModeCmd() and RCC_APB1PeriphClockLPModeCmd() functions.  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the RTC clock (RTCCLK).
+  * @note   As the RTC clock configuration bits are in the Backup domain and write
+  *         access is denied to this domain after reset, you have to enable write
+  *         access using PWR_BackupAccessCmd(ENABLE) function before to configure
+  *         the RTC clock source (to be done once after reset).    
+  * @note   Once the RTC clock is configured it can't be changed unless the  
+  *         Backup domain is reset using RCC_BackupResetCmd() function, or by
+  *         a Power On Reset (POR).
+  *    
+  * @param  RCC_RTCCLKSource: specifies the RTC clock source.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock
+  *            @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock
+  *            @arg RCC_RTCCLKSource_HSE_Divx: HSE clock divided by x selected
+  *                                            as RTC clock, where x:[2,31]
+  *  
+  * @note   If the LSE or LSI is used as RTC clock source, the RTC continues to
+  *         work in STOP and STANDBY modes, and can be used as wakeup source.
+  *         However, when the HSE clock is used as RTC clock source, the RTC
+  *         cannot be used in STOP and STANDBY modes.    
+  * @note   The maximum input clock frequency for RTC is 1MHz (when using HSE as
+  *         RTC clock source).
+  *  
+  * @retval None
+  */
+void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource));
+
+  if ((RCC_RTCCLKSource & 0x00000300) == 0x00000300)
+  { /* If HSE is selected as RTC clock source, configure HSE division factor for RTC clock */
+    tmpreg = RCC->CFGR;
+
+    /* Clear RTCPRE[4:0] bits */
+    tmpreg &= ~RCC_CFGR_RTCPRE;
+
+    /* Configure HSE division factor for RTC clock */
+    tmpreg |= (RCC_RTCCLKSource & 0xFFFFCFF);
+
+    /* Store the new value */
+    RCC->CFGR = tmpreg;
+  }
+    
+  /* Select the RTC clock source */
+  RCC->BDCR |= (RCC_RTCCLKSource & 0x00000FFF);
+}
+
+/**
+  * @brief  Enables or disables the RTC clock.
+  * @note   This function must be used only after the RTC clock source was selected
+  *         using the RCC_RTCCLKConfig function.
+  * @param  NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_RTCCLKCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Forces or releases the Backup domain reset.
+  * @note   This function resets the RTC peripheral (including the backup registers)
+  *         and the RTC clock source selection in RCC_CSR register.
+  * @note   The BKPSRAM is not affected by this reset.    
+  * @param  NewState: new state of the Backup domain reset.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_BackupResetCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Configures the I2S clock source (I2SCLK).
+  * @note   This function must be called before enabling the I2S APB clock.
+  * @param  RCC_I2SCLKSource: specifies the I2S clock source.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_I2S2CLKSource_PLLI2S: PLLI2S clock used as I2S clock source
+  *            @arg RCC_I2S2CLKSource_Ext: External clock mapped on the I2S_CKIN pin
+  *                                        used as I2S clock source
+  * @retval None
+  */
+void RCC_I2SCLKConfig(uint32_t RCC_I2SCLKSource)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_I2SCLK_SOURCE(RCC_I2SCLKSource));
+
+  *(__IO uint32_t *) CFGR_I2SSRC_BB = RCC_I2SCLKSource;
+}
+
+/**
+  * @brief  Configures the SAI clock Divider coming from PLLI2S.
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *   
+  * @note   This function must be called before enabling the PLLI2S.
+  *              
+  * @param  RCC_PLLI2SDivQ: specifies the PLLI2S division factor for SAI1 clock .
+  *          This parameter must be a number between 1 and 32.
+  *          SAI1 clock frequency = f(PLLI2S_Q) / RCC_PLLI2SDivQ 
+  *              
+  * @retval None
+  */
+void RCC_SAIPLLI2SClkDivConfig(uint32_t RCC_PLLI2SDivQ)  
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_PLLI2S_DIVQ_VALUE(RCC_PLLI2SDivQ));
+  
+  tmpreg = RCC->DCKCFGR;
+
+  /* Clear PLLI2SDIVQ[4:0] bits */
+  tmpreg &= ~(RCC_DCKCFGR_PLLI2SDIVQ);
+
+  /* Set PLLI2SDIVQ values */
+  tmpreg |= (RCC_PLLI2SDivQ - 1);
+
+  /* Store the new value */
+  RCC->DCKCFGR = tmpreg;
+}
+
+/**
+  * @brief  Configures the SAI clock Divider coming from PLLSAI.
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *        
+  * @note   This function must be called before enabling the PLLSAI.
+  *   
+  * @param  RCC_PLLSAIDivQ: specifies the PLLSAI division factor for SAI1 clock .
+  *          This parameter must be a number between 1 and 32.
+  *          SAI1 clock frequency = f(PLLSAI_Q) / RCC_PLLSAIDivQ  
+  *              
+  * @retval None
+  */
+void RCC_SAIPLLSAIClkDivConfig(uint32_t RCC_PLLSAIDivQ)  
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_PLLSAI_DIVQ_VALUE(RCC_PLLSAIDivQ));
+  
+  tmpreg = RCC->DCKCFGR;
+
+  /* Clear PLLI2SDIVQ[4:0] and PLLSAIDIVQ[4:0] bits */
+  tmpreg &= ~(RCC_DCKCFGR_PLLSAIDIVQ);
+
+  /* Set PLLSAIDIVQ values */
+  tmpreg |= ((RCC_PLLSAIDivQ - 1) << 8);
+
+  /* Store the new value */
+  RCC->DCKCFGR = tmpreg;
+}
+
+/**
+  * @brief  Configures SAI1BlockA clock source selection.
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *       
+  * @note   This function must be called before enabling PLLSAI, PLLI2S and  
+  *         the SAI clock.
+  * @param  RCC_SAIBlockACLKSource: specifies the SAI Block A clock source.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_SAIACLKSource_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used 
+  *                                           as SAI1 Block A clock 
+  *            @arg RCC_SAIACLKSource_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used 
+  *                                           as SAI1 Block A clock 
+  *            @arg RCC_SAIACLKSource_Ext: External clock mapped on the I2S_CKIN pin
+  *                                        used as SAI1 Block A clock
+  * @retval None
+  */
+void RCC_SAIBlockACLKConfig(uint32_t RCC_SAIBlockACLKSource)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_SAIACLK_SOURCE(RCC_SAIBlockACLKSource));
+  
+  tmpreg = RCC->DCKCFGR;
+
+  /* Clear RCC_DCKCFGR_SAI1ASRC[1:0] bits */
+  tmpreg &= ~RCC_DCKCFGR_SAI1ASRC;
+
+  /* Set SAI Block A source selection value */
+  tmpreg |= RCC_SAIBlockACLKSource;
+
+  /* Store the new value */
+  RCC->DCKCFGR = tmpreg;
+}
+
+/**
+  * @brief  Configures SAI1BlockB clock source selection.
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx devices.
+  *       
+  * @note   This function must be called before enabling PLLSAI, PLLI2S and  
+  *         the SAI clock.
+  * @param  RCC_SAIBlockBCLKSource: specifies the SAI Block B clock source.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_SAIBCLKSource_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used 
+  *                                           as SAI1 Block B clock 
+  *            @arg RCC_SAIBCLKSource_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used 
+  *                                           as SAI1 Block B clock 
+  *            @arg RCC_SAIBCLKSource_Ext: External clock mapped on the I2S_CKIN pin
+  *                                        used as SAI1 Block B clock
+  * @retval None
+  */
+void RCC_SAIBlockBCLKConfig(uint32_t RCC_SAIBlockBCLKSource)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_SAIBCLK_SOURCE(RCC_SAIBlockBCLKSource));
+  
+  tmpreg = RCC->DCKCFGR;
+
+  /* Clear RCC_DCKCFGR_SAI1BSRC[1:0] bits */
+  tmpreg &= ~RCC_DCKCFGR_SAI1BSRC;
+
+  /* Set SAI Block B source selection value */
+  tmpreg |= RCC_SAIBlockBCLKSource;
+
+  /* Store the new value */
+  RCC->DCKCFGR = tmpreg;
+}
+
+
+/**
+  * @brief  Configures the LTDC clock Divider coming from PLLSAI.
+  * 
+  * @note   The LTDC peripheral is only available with STM32F429xx/439xx Devices.
+  *      
+  * @note   This function must be called before enabling the PLLSAI.
+  *   
+  * @param  RCC_PLLSAIDivR: specifies the PLLSAI division factor for LTDC clock .
+  *          This parameter must be a number between 2 and 16.
+  *          LTDC clock frequency = f(PLLSAI_R) / RCC_PLLSAIDivR  
+  *            
+  * @retval None
+  */
+void RCC_LTDCCLKDivConfig(uint32_t RCC_PLLSAIDivR)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RCC_PLLSAI_DIVR_VALUE(RCC_PLLSAIDivR));
+  
+  tmpreg = RCC->DCKCFGR;
+
+  /* Clear PLLSAIDIVR[2:0] bits */
+  tmpreg &= ~RCC_DCKCFGR_PLLSAIDIVR;
+
+  /* Set PLLSAIDIVR values */
+  tmpreg |= RCC_PLLSAIDivR;
+
+  /* Store the new value */
+  RCC->DCKCFGR = tmpreg;
+}
+
+/**
+  * @brief  Configures the Timers clocks prescalers selection.
+  * 
+  * @note   This function can be used only for STM32F42xxx/43xxx and STM32F401xx devices. 
+  *   
+  * @param  RCC_TIMCLKPrescaler : specifies the Timers clocks prescalers selection
+  *         This parameter can be one of the following values:
+  *            @arg RCC_TIMPrescDesactivated: The Timers kernels clocks prescaler is 
+  *                 equal to HPRE if PPREx is corresponding to division by 1 or 2, 
+  *                 else it is equal to [(HPRE * PPREx) / 2] if PPREx is corresponding to 
+  *                 division by 4 or more.
+  *                   
+  *            @arg RCC_TIMPrescActivated: The Timers kernels clocks prescaler is 
+  *                 equal to HPRE if PPREx is corresponding to division by 1, 2 or 4, 
+  *                 else it is equal to [(HPRE * PPREx) / 4] if PPREx is corresponding 
+  *                 to division by 8 or more.
+  * @retval None
+  */
+void RCC_TIMCLKPresConfig(uint32_t RCC_TIMCLKPrescaler)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_TIMCLK_PRESCALER(RCC_TIMCLKPrescaler));
+
+  *(__IO uint32_t *) DCKCFGR_TIMPRE_BB = RCC_TIMCLKPrescaler;
+  
+}
+
+/**
+  * @brief  Enables or disables the AHB1 peripheral clock.
+  * @note   After reset, the peripheral clock (used for registers read/write access)
+  *         is disabled and the application software has to enable this clock before 
+  *         using it.   
+  * @param  RCC_AHBPeriph: specifies the AHB1 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_AHB1Periph_GPIOA:       GPIOA clock
+  *            @arg RCC_AHB1Periph_GPIOB:       GPIOB clock 
+  *            @arg RCC_AHB1Periph_GPIOC:       GPIOC clock
+  *            @arg RCC_AHB1Periph_GPIOD:       GPIOD clock
+  *            @arg RCC_AHB1Periph_GPIOE:       GPIOE clock
+  *            @arg RCC_AHB1Periph_GPIOF:       GPIOF clock
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock
+  *            @arg RCC_AHB1Periph_GPIOI:       GPIOI clock
+  *            @arg RCC_AHB1Periph_GPIOJ:       GPIOJ clock (STM32F42xxx/43xxx devices) 
+  *            @arg RCC_AHB1Periph_GPIOK:       GPIOK clock (STM32F42xxx/43xxx devices)  
+  *            @arg RCC_AHB1Periph_CRC:         CRC clock
+  *            @arg RCC_AHB1Periph_BKPSRAM:     BKPSRAM interface clock
+  *            @arg RCC_AHB1Periph_CCMDATARAMEN CCM data RAM interface clock
+  *            @arg RCC_AHB1Periph_DMA1:        DMA1 clock
+  *            @arg RCC_AHB1Periph_DMA2:        DMA2 clock
+  *            @arg RCC_AHB1Periph_DMA2D:       DMA2D clock (STM32F429xx/439xx devices)  
+  *            @arg RCC_AHB1Periph_ETH_MAC:     Ethernet MAC clock
+  *            @arg RCC_AHB1Periph_ETH_MAC_Tx:  Ethernet Transmission clock
+  *            @arg RCC_AHB1Periph_ETH_MAC_Rx:  Ethernet Reception clock
+  *            @arg RCC_AHB1Periph_ETH_MAC_PTP: Ethernet PTP clock
+  *            @arg RCC_AHB1Periph_OTG_HS:      USB OTG HS clock
+  *            @arg RCC_AHB1Periph_OTG_HS_ULPI: USB OTG HS ULPI clock
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB1PeriphClockCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB1_CLOCK_PERIPH(RCC_AHB1Periph));
+
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->AHB1ENR |= RCC_AHB1Periph;
+  }
+  else
+  {
+    RCC->AHB1ENR &= ~RCC_AHB1Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the AHB2 peripheral clock.
+  * @note   After reset, the peripheral clock (used for registers read/write access)
+  *         is disabled and the application software has to enable this clock before 
+  *         using it. 
+  * @param  RCC_AHBPeriph: specifies the AHB2 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_AHB2Periph_DCMI:   DCMI clock
+  *            @arg RCC_AHB2Periph_CRYP:   CRYP clock
+  *            @arg RCC_AHB2Periph_HASH:   HASH clock
+  *            @arg RCC_AHB2Periph_RNG:    RNG clock
+  *            @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB2PeriphClockCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->AHB2ENR |= RCC_AHB2Periph;
+  }
+  else
+  {
+    RCC->AHB2ENR &= ~RCC_AHB2Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the AHB3 peripheral clock.
+  * @note   After reset, the peripheral clock (used for registers read/write access)
+  *         is disabled and the application software has to enable this clock before 
+  *         using it. 
+  * @param  RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock.
+  *          This parameter must be: RCC_AHB3Periph_FSMC
+  *                                  or RCC_AHB3Periph_FMC (STM32F42xxx/43xxx devices)  
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB3PeriphClockCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph));  
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->AHB3ENR |= RCC_AHB3Periph;
+  }
+  else
+  {
+    RCC->AHB3ENR &= ~RCC_AHB3Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the Low Speed APB (APB1) peripheral clock.
+  * @note   After reset, the peripheral clock (used for registers read/write access)
+  *         is disabled and the application software has to enable this clock before 
+  *         using it. 
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_APB1Periph_TIM2:   TIM2 clock
+  *            @arg RCC_APB1Periph_TIM3:   TIM3 clock
+  *            @arg RCC_APB1Periph_TIM4:   TIM4 clock
+  *            @arg RCC_APB1Periph_TIM5:   TIM5 clock
+  *            @arg RCC_APB1Periph_TIM6:   TIM6 clock
+  *            @arg RCC_APB1Periph_TIM7:   TIM7 clock
+  *            @arg RCC_APB1Periph_TIM12:  TIM12 clock
+  *            @arg RCC_APB1Periph_TIM13:  TIM13 clock
+  *            @arg RCC_APB1Periph_TIM14:  TIM14 clock
+  *            @arg RCC_APB1Periph_WWDG:   WWDG clock
+  *            @arg RCC_APB1Periph_SPI2:   SPI2 clock
+  *            @arg RCC_APB1Periph_SPI3:   SPI3 clock
+  *            @arg RCC_APB1Periph_USART2: USART2 clock
+  *            @arg RCC_APB1Periph_USART3: USART3 clock
+  *            @arg RCC_APB1Periph_UART4:  UART4 clock
+  *            @arg RCC_APB1Periph_UART5:  UART5 clock
+  *            @arg RCC_APB1Periph_I2C1:   I2C1 clock
+  *            @arg RCC_APB1Periph_I2C2:   I2C2 clock
+  *            @arg RCC_APB1Periph_I2C3:   I2C3 clock
+  *            @arg RCC_APB1Periph_CAN1:   CAN1 clock
+  *            @arg RCC_APB1Periph_CAN2:   CAN2 clock
+  *            @arg RCC_APB1Periph_PWR:    PWR clock
+  *            @arg RCC_APB1Periph_DAC:    DAC clock
+  *            @arg RCC_APB1Periph_UART7:  UART7 clock
+  *            @arg RCC_APB1Periph_UART8:  UART8 clock
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));  
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->APB1ENR |= RCC_APB1Periph;
+  }
+  else
+  {
+    RCC->APB1ENR &= ~RCC_APB1Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the High Speed APB (APB2) peripheral clock.
+  * @note   After reset, the peripheral clock (used for registers read/write access)
+  *         is disabled and the application software has to enable this clock before 
+  *         using it.
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_APB2Periph_TIM1:   TIM1 clock
+  *            @arg RCC_APB2Periph_TIM8:   TIM8 clock
+  *            @arg RCC_APB2Periph_USART1: USART1 clock
+  *            @arg RCC_APB2Periph_USART6: USART6 clock
+  *            @arg RCC_APB2Periph_ADC1:   ADC1 clock
+  *            @arg RCC_APB2Periph_ADC2:   ADC2 clock
+  *            @arg RCC_APB2Periph_ADC3:   ADC3 clock
+  *            @arg RCC_APB2Periph_SDIO:   SDIO clock
+  *            @arg RCC_APB2Periph_SPI1:   SPI1 clock
+  *            @arg RCC_APB2Periph_SPI4:   SPI4 clock
+  *            @arg RCC_APB2Periph_SYSCFG: SYSCFG clock
+  *            @arg RCC_APB2Periph_TIM9:   TIM9 clock
+  *            @arg RCC_APB2Periph_TIM10:  TIM10 clock
+  *            @arg RCC_APB2Periph_TIM11:  TIM11 clock
+  *            @arg RCC_APB2Periph_SPI5:   SPI5 clock
+  *            @arg RCC_APB2Periph_SPI6:   SPI6 clock
+  *            @arg RCC_APB2Periph_SAI1:   SAI1 clock (STM32F42xxx/43xxx devices) 
+  *            @arg RCC_APB2Periph_LTDC:   LTDC clock (STM32F429xx/439xx devices) 
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->APB2ENR |= RCC_APB2Periph;
+  }
+  else
+  {
+    RCC->APB2ENR &= ~RCC_APB2Periph;
+  }
+}
+
+/**
+  * @brief  Forces or releases AHB1 peripheral reset.
+  * @param  RCC_AHB1Periph: specifies the AHB1 peripheral to reset.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_AHB1Periph_GPIOA:   GPIOA clock
+  *            @arg RCC_AHB1Periph_GPIOB:   GPIOB clock 
+  *            @arg RCC_AHB1Periph_GPIOC:   GPIOC clock
+  *            @arg RCC_AHB1Periph_GPIOD:   GPIOD clock
+  *            @arg RCC_AHB1Periph_GPIOE:   GPIOE clock
+  *            @arg RCC_AHB1Periph_GPIOF:   GPIOF clock
+  *            @arg RCC_AHB1Periph_GPIOG:   GPIOG clock
+  *            @arg RCC_AHB1Periph_GPIOG:   GPIOG clock
+  *            @arg RCC_AHB1Periph_GPIOI:   GPIOI clock
+  *            @arg RCC_AHB1Periph_GPIOJ:   GPIOJ clock (STM32F42xxx/43xxx devices) 
+  *            @arg RCC_AHB1Periph_GPIOK:   GPIOK clock (STM32F42xxx/43xxxdevices)   
+  *            @arg RCC_AHB1Periph_CRC:     CRC clock
+  *            @arg RCC_AHB1Periph_DMA1:    DMA1 clock
+  *            @arg RCC_AHB1Periph_DMA2:    DMA2 clock
+  *            @arg RCC_AHB1Periph_DMA2D:   DMA2D clock (STM32F429xx/439xx devices)   
+  *            @arg RCC_AHB1Periph_ETH_MAC: Ethernet MAC clock
+  *            @arg RCC_AHB1Periph_OTG_HS:  USB OTG HS clock
+  *                  
+  * @param  NewState: new state of the specified peripheral reset.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB1PeriphResetCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB1_RESET_PERIPH(RCC_AHB1Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->AHB1RSTR |= RCC_AHB1Periph;
+  }
+  else
+  {
+    RCC->AHB1RSTR &= ~RCC_AHB1Periph;
+  }
+}
+
+/**
+  * @brief  Forces or releases AHB2 peripheral reset.
+  * @param  RCC_AHB2Periph: specifies the AHB2 peripheral to reset.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_AHB2Periph_DCMI:   DCMI clock
+  *            @arg RCC_AHB2Periph_CRYP:   CRYP clock
+  *            @arg RCC_AHB2Periph_HASH:   HASH clock
+  *            @arg RCC_AHB2Periph_RNG:    RNG clock
+  *            @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock
+  * @param  NewState: new state of the specified peripheral reset.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB2PeriphResetCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->AHB2RSTR |= RCC_AHB2Periph;
+  }
+  else
+  {
+    RCC->AHB2RSTR &= ~RCC_AHB2Periph;
+  }
+}
+
+/**
+  * @brief  Forces or releases AHB3 peripheral reset.
+  * @param  RCC_AHB3Periph: specifies the AHB3 peripheral to reset.
+  *          This parameter must be: RCC_AHB3Periph_FSMC
+  *                                  or RCC_AHB3Periph_FMC (STM32F42xxx/43xxx devices)  
+  * @param  NewState: new state of the specified peripheral reset.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB3PeriphResetCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    RCC->AHB3RSTR |= RCC_AHB3Periph;
+  }
+  else
+  {
+    RCC->AHB3RSTR &= ~RCC_AHB3Periph;
+  }
+}
+
+/**
+  * @brief  Forces or releases Low Speed APB (APB1) peripheral reset.
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to reset.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_APB1Periph_TIM2:   TIM2 clock
+  *            @arg RCC_APB1Periph_TIM3:   TIM3 clock
+  *            @arg RCC_APB1Periph_TIM4:   TIM4 clock
+  *            @arg RCC_APB1Periph_TIM5:   TIM5 clock
+  *            @arg RCC_APB1Periph_TIM6:   TIM6 clock
+  *            @arg RCC_APB1Periph_TIM7:   TIM7 clock
+  *            @arg RCC_APB1Periph_TIM12:  TIM12 clock
+  *            @arg RCC_APB1Periph_TIM13:  TIM13 clock
+  *            @arg RCC_APB1Periph_TIM14:  TIM14 clock
+  *            @arg RCC_APB1Periph_WWDG:   WWDG clock
+  *            @arg RCC_APB1Periph_SPI2:   SPI2 clock
+  *            @arg RCC_APB1Periph_SPI3:   SPI3 clock
+  *            @arg RCC_APB1Periph_USART2: USART2 clock
+  *            @arg RCC_APB1Periph_USART3: USART3 clock
+  *            @arg RCC_APB1Periph_UART4:  UART4 clock
+  *            @arg RCC_APB1Periph_UART5:  UART5 clock
+  *            @arg RCC_APB1Periph_I2C1:   I2C1 clock
+  *            @arg RCC_APB1Periph_I2C2:   I2C2 clock
+  *            @arg RCC_APB1Periph_I2C3:   I2C3 clock
+  *            @arg RCC_APB1Periph_CAN1:   CAN1 clock
+  *            @arg RCC_APB1Periph_CAN2:   CAN2 clock
+  *            @arg RCC_APB1Periph_PWR:    PWR clock
+  *            @arg RCC_APB1Periph_DAC:    DAC clock
+  *            @arg RCC_APB1Periph_UART7:  UART7 clock
+  *            @arg RCC_APB1Periph_UART8:  UART8 clock  
+  * @param  NewState: new state of the specified peripheral reset.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB1RSTR |= RCC_APB1Periph;
+  }
+  else
+  {
+    RCC->APB1RSTR &= ~RCC_APB1Periph;
+  }
+}
+
+/**
+  * @brief  Forces or releases High Speed APB (APB2) peripheral reset.
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to reset.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_APB2Periph_TIM1:   TIM1 clock
+  *            @arg RCC_APB2Periph_TIM8:   TIM8 clock
+  *            @arg RCC_APB2Periph_USART1: USART1 clock
+  *            @arg RCC_APB2Periph_USART6: USART6 clock
+  *            @arg RCC_APB2Periph_ADC1:   ADC1 clock
+  *            @arg RCC_APB2Periph_ADC2:   ADC2 clock
+  *            @arg RCC_APB2Periph_ADC3:   ADC3 clock
+  *            @arg RCC_APB2Periph_SDIO:   SDIO clock
+  *            @arg RCC_APB2Periph_SPI1:   SPI1 clock
+  *            @arg RCC_APB2Periph_SPI4:   SPI4 clock  
+  *            @arg RCC_APB2Periph_SYSCFG: SYSCFG clock
+  *            @arg RCC_APB2Periph_TIM9:   TIM9 clock
+  *            @arg RCC_APB2Periph_TIM10:  TIM10 clock
+  *            @arg RCC_APB2Periph_TIM11:  TIM11 clock
+  *            @arg RCC_APB2Periph_SPI5:   SPI5 clock
+  *            @arg RCC_APB2Periph_SPI6:   SPI6 clock
+  *            @arg RCC_APB2Periph_SAI1:   SAI1 clock (STM32F42xxx/43xxx devices) 
+  *            @arg RCC_APB2Periph_LTDC:   LTDC clock (STM32F429xx/439xx devices)   
+  * @param  NewState: new state of the specified peripheral reset.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB2_RESET_PERIPH(RCC_APB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB2RSTR |= RCC_APB2Periph;
+  }
+  else
+  {
+    RCC->APB2RSTR &= ~RCC_APB2Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the AHB1 peripheral clock during Low Power (Sleep) mode.
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce
+  *         power consumption.
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.
+  * @param  RCC_AHBPeriph: specifies the AHB1 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_AHB1Periph_GPIOA:       GPIOA clock
+  *            @arg RCC_AHB1Periph_GPIOB:       GPIOB clock 
+  *            @arg RCC_AHB1Periph_GPIOC:       GPIOC clock
+  *            @arg RCC_AHB1Periph_GPIOD:       GPIOD clock
+  *            @arg RCC_AHB1Periph_GPIOE:       GPIOE clock
+  *            @arg RCC_AHB1Periph_GPIOF:       GPIOF clock
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock
+  *            @arg RCC_AHB1Periph_GPIOG:       GPIOG clock
+  *            @arg RCC_AHB1Periph_GPIOI:       GPIOI clock
+  *            @arg RCC_AHB1Periph_GPIOJ:       GPIOJ clock (STM32F42xxx/43xxx devices) 
+  *            @arg RCC_AHB1Periph_GPIOK:       GPIOK clock (STM32F42xxx/43xxx devices)   
+  *            @arg RCC_AHB1Periph_CRC:         CRC clock
+  *            @arg RCC_AHB1Periph_BKPSRAM:     BKPSRAM interface clock
+  *            @arg RCC_AHB1Periph_DMA1:        DMA1 clock
+  *            @arg RCC_AHB1Periph_DMA2:        DMA2 clock
+  *            @arg RCC_AHB1Periph_DMA2D:       DMA2D clock (STM32F429xx/439xx devices) 
+  *            @arg RCC_AHB1Periph_ETH_MAC:     Ethernet MAC clock
+  *            @arg RCC_AHB1Periph_ETH_MAC_Tx:  Ethernet Transmission clock
+  *            @arg RCC_AHB1Periph_ETH_MAC_Rx:  Ethernet Reception clock
+  *            @arg RCC_AHB1Periph_ETH_MAC_PTP: Ethernet PTP clock
+  *            @arg RCC_AHB1Periph_OTG_HS:      USB OTG HS clock
+  *            @arg RCC_AHB1Periph_OTG_HS_ULPI: USB OTG HS ULPI clock
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB1PeriphClockLPModeCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB1_LPMODE_PERIPH(RCC_AHB1Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->AHB1LPENR |= RCC_AHB1Periph;
+  }
+  else
+  {
+    RCC->AHB1LPENR &= ~RCC_AHB1Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the AHB2 peripheral clock during Low Power (Sleep) mode.
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce
+  *           power consumption.
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.
+  * @param  RCC_AHBPeriph: specifies the AHB2 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_AHB2Periph_DCMI:   DCMI clock
+  *            @arg RCC_AHB2Periph_CRYP:   CRYP clock
+  *            @arg RCC_AHB2Periph_HASH:   HASH clock
+  *            @arg RCC_AHB2Periph_RNG:    RNG clock
+  *            @arg RCC_AHB2Periph_OTG_FS: USB OTG FS clock  
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB2PeriphClockLPModeCmd(uint32_t RCC_AHB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB2_PERIPH(RCC_AHB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->AHB2LPENR |= RCC_AHB2Periph;
+  }
+  else
+  {
+    RCC->AHB2LPENR &= ~RCC_AHB2Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the AHB3 peripheral clock during Low Power (Sleep) mode.
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce
+  *         power consumption.
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.
+  * @param  RCC_AHBPeriph: specifies the AHB3 peripheral to gates its clock.
+  *          This parameter must be: RCC_AHB3Periph_FSMC
+  *                                  or RCC_AHB3Periph_FMC (STM32F429x/439x devices) 
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_AHB3PeriphClockLPModeCmd(uint32_t RCC_AHB3Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_AHB3_PERIPH(RCC_AHB3Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->AHB3LPENR |= RCC_AHB3Periph;
+  }
+  else
+  {
+    RCC->AHB3LPENR &= ~RCC_AHB3Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the APB1 peripheral clock during Low Power (Sleep) mode.
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce
+  *         power consumption.
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.
+  * @param  RCC_APB1Periph: specifies the APB1 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_APB1Periph_TIM2:   TIM2 clock
+  *            @arg RCC_APB1Periph_TIM3:   TIM3 clock
+  *            @arg RCC_APB1Periph_TIM4:   TIM4 clock
+  *            @arg RCC_APB1Periph_TIM5:   TIM5 clock
+  *            @arg RCC_APB1Periph_TIM6:   TIM6 clock
+  *            @arg RCC_APB1Periph_TIM7:   TIM7 clock
+  *            @arg RCC_APB1Periph_TIM12:  TIM12 clock
+  *            @arg RCC_APB1Periph_TIM13:  TIM13 clock
+  *            @arg RCC_APB1Periph_TIM14:  TIM14 clock
+  *            @arg RCC_APB1Periph_WWDG:   WWDG clock
+  *            @arg RCC_APB1Periph_SPI2:   SPI2 clock
+  *            @arg RCC_APB1Periph_SPI3:   SPI3 clock
+  *            @arg RCC_APB1Periph_USART2: USART2 clock
+  *            @arg RCC_APB1Periph_USART3: USART3 clock
+  *            @arg RCC_APB1Periph_UART4:  UART4 clock
+  *            @arg RCC_APB1Periph_UART5:  UART5 clock
+  *            @arg RCC_APB1Periph_I2C1:   I2C1 clock
+  *            @arg RCC_APB1Periph_I2C2:   I2C2 clock
+  *            @arg RCC_APB1Periph_I2C3:   I2C3 clock
+  *            @arg RCC_APB1Periph_CAN1:   CAN1 clock
+  *            @arg RCC_APB1Periph_CAN2:   CAN2 clock
+  *            @arg RCC_APB1Periph_PWR:    PWR clock
+  *            @arg RCC_APB1Periph_DAC:    DAC clock
+  *            @arg RCC_APB1Periph_UART7:  UART7 clock
+  *            @arg RCC_APB1Periph_UART8:  UART8 clock
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB1PeriphClockLPModeCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB1LPENR |= RCC_APB1Periph;
+  }
+  else
+  {
+    RCC->APB1LPENR &= ~RCC_APB1Periph;
+  }
+}
+
+/**
+  * @brief  Enables or disables the APB2 peripheral clock during Low Power (Sleep) mode.
+  * @note   Peripheral clock gating in SLEEP mode can be used to further reduce
+  *         power consumption.
+  * @note   After wakeup from SLEEP mode, the peripheral clock is enabled again.
+  * @note   By default, all peripheral clocks are enabled during SLEEP mode.
+  * @param  RCC_APB2Periph: specifies the APB2 peripheral to gates its clock.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_APB2Periph_TIM1:   TIM1 clock
+  *            @arg RCC_APB2Periph_TIM8:   TIM8 clock
+  *            @arg RCC_APB2Periph_USART1: USART1 clock
+  *            @arg RCC_APB2Periph_USART6: USART6 clock
+  *            @arg RCC_APB2Periph_ADC1:   ADC1 clock
+  *            @arg RCC_APB2Periph_ADC2:   ADC2 clock
+  *            @arg RCC_APB2Periph_ADC3:   ADC3 clock
+  *            @arg RCC_APB2Periph_SDIO:   SDIO clock
+  *            @arg RCC_APB2Periph_SPI1:   SPI1 clock
+  *            @arg RCC_APB2Periph_SPI4:   SPI4 clock
+  *            @arg RCC_APB2Periph_SYSCFG: SYSCFG clock
+  *            @arg RCC_APB2Periph_TIM9:   TIM9 clock
+  *            @arg RCC_APB2Periph_TIM10:  TIM10 clock
+  *            @arg RCC_APB2Periph_TIM11:  TIM11 clock
+  *            @arg RCC_APB2Periph_SPI5:   SPI5 clock
+  *            @arg RCC_APB2Periph_SPI6:   SPI6 clock
+  *            @arg RCC_APB2Periph_SAI1:   SAI1 clock (STM32F42xxx/43xxx devices) 
+  *            @arg RCC_APB2Periph_LTDC:   LTDC clock (STM32F429xx/439xx devices)   
+  * @param  NewState: new state of the specified peripheral clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_APB2PeriphClockLPModeCmd(uint32_t RCC_APB2Periph, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    RCC->APB2LPENR |= RCC_APB2Periph;
+  }
+  else
+  {
+    RCC->APB2LPENR &= ~RCC_APB2Periph;
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RCC_Group4 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions 
+ *
+@verbatim   
+ ===============================================================================
+                ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified RCC interrupts.
+  * @param  RCC_IT: specifies the RCC interrupt sources to be enabled or disabled.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *            @arg RCC_IT_LSERDY: LSE ready interrupt
+  *            @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *            @arg RCC_IT_HSERDY: HSE ready interrupt
+  *            @arg RCC_IT_PLLRDY: main PLL ready interrupt
+  *            @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt
+  *            @arg RCC_IT_PLLSAIRDY: PLLSAI ready interrupt (only for STM32F42xxx/43xxx devices)
+  * @param  NewState: new state of the specified RCC interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_IT(RCC_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Perform Byte access to RCC_CIR[14:8] bits to enable the selected interrupts */
+    *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT;
+  }
+  else
+  {
+    /* Perform Byte access to RCC_CIR[14:8] bits to disable the selected interrupts */
+    *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified RCC flag is set or not.
+  * @param  RCC_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready
+  *            @arg RCC_FLAG_HSERDY: HSE oscillator clock ready
+  *            @arg RCC_FLAG_PLLRDY: main PLL clock ready
+  *            @arg RCC_FLAG_PLLI2SRDY: PLLI2S clock ready
+  *            @arg RCC_FLAG_PLLSAIRDY: PLLSAI clock ready (only for STM32F42xxx/43xxx devices)
+  *            @arg RCC_FLAG_LSERDY: LSE oscillator clock ready
+  *            @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready
+  *            @arg RCC_FLAG_BORRST: POR/PDR or BOR reset
+  *            @arg RCC_FLAG_PINRST: Pin reset
+  *            @arg RCC_FLAG_PORRST: POR/PDR reset
+  *            @arg RCC_FLAG_SFTRST: Software reset
+  *            @arg RCC_FLAG_IWDGRST: Independent Watchdog reset
+  *            @arg RCC_FLAG_WWDGRST: Window Watchdog reset
+  *            @arg RCC_FLAG_LPWRRST: Low Power reset
+  * @retval The new state of RCC_FLAG (SET or RESET).
+  */
+FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG)
+{
+  uint32_t tmp = 0;
+  uint32_t statusreg = 0;
+  FlagStatus bitstatus = RESET;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_FLAG(RCC_FLAG));
+
+  /* Get the RCC register index */
+  tmp = RCC_FLAG >> 5;
+  if (tmp == 1)               /* The flag to check is in CR register */
+  {
+    statusreg = RCC->CR;
+  }
+  else if (tmp == 2)          /* The flag to check is in BDCR register */
+  {
+    statusreg = RCC->BDCR;
+  }
+  else                       /* The flag to check is in CSR register */
+  {
+    statusreg = RCC->CSR;
+  }
+
+  /* Get the flag position */
+  tmp = RCC_FLAG & FLAG_MASK;
+  if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the flag status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the RCC reset flags.
+  *         The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST,  RCC_FLAG_SFTRST,
+  *         RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST
+  * @param  None
+  * @retval None
+  */
+void RCC_ClearFlag(void)
+{
+  /* Set RMVF bit to clear the reset flags */
+  RCC->CSR |= RCC_CSR_RMVF;
+}
+
+/**
+  * @brief  Checks whether the specified RCC interrupt has occurred or not.
+  * @param  RCC_IT: specifies the RCC interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *            @arg RCC_IT_LSERDY: LSE ready interrupt
+  *            @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *            @arg RCC_IT_HSERDY: HSE ready interrupt
+  *            @arg RCC_IT_PLLRDY: main PLL ready interrupt
+  *            @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt           
+  *            @arg RCC_IT_PLLSAIRDY: PLLSAI clock ready interrupt (only for STM32F42xxx/43xxx devices)    
+  *            @arg RCC_IT_CSS: Clock Security System interrupt
+  * @retval The new state of RCC_IT (SET or RESET).
+  */
+ITStatus RCC_GetITStatus(uint8_t RCC_IT)
+{
+  ITStatus bitstatus = RESET;
+
+  /* Check the parameters */
+  assert_param(IS_RCC_GET_IT(RCC_IT));
+
+  /* Check the status of the specified RCC interrupt */
+  if ((RCC->CIR & RCC_IT) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  /* Return the RCC_IT status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the RCC's interrupt pending bits.
+  * @param  RCC_IT: specifies the interrupt pending bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg RCC_IT_LSIRDY: LSI ready interrupt
+  *            @arg RCC_IT_LSERDY: LSE ready interrupt
+  *            @arg RCC_IT_HSIRDY: HSI ready interrupt
+  *            @arg RCC_IT_HSERDY: HSE ready interrupt
+  *            @arg RCC_IT_PLLRDY: main PLL ready interrupt
+  *            @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt  
+  *            @arg RCC_IT_PLLSAIRDY: PLLSAI ready interrupt (only for STM32F42xxx/43xxx devices)   
+  *            @arg RCC_IT_CSS: Clock Security System interrupt
+  * @retval None
+  */
+void RCC_ClearITPendingBit(uint8_t RCC_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_RCC_CLEAR_IT(RCC_IT));
+
+  /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt
+     pending bits */
+  *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT;
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c
new file mode 100644
index 0000000000000000000000000000000000000000..4746dd6bda0f6f1fd9287a974f1b9b7cba1f07d7
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rng.c
@@ -0,0 +1,397 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_rng.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief This file provides firmware functions to manage the following 
+  *          functionalities of the Random Number Generator (RNG) peripheral:           
+  *           + Initialization and Configuration 
+  *           + Get 32 bit Random number      
+  *           + Interrupts and flags management       
+  *         
+@verbatim
+                                 
+ ===================================================================      
+                 ##### How to use this driver #####
+ ===================================================================          
+ [..]
+   (#) Enable The RNG controller clock using 
+       RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_RNG, ENABLE) function.
+                
+   (#) Activate the RNG peripheral using RNG_Cmd() function.
+            
+   (#) Wait until the 32 bit Random number Generator contains a valid  random data
+      (using polling/interrupt mode). For more details, refer to "Interrupts and 
+      flags management functions" module description.
+             
+   (#) Get the 32 bit Random number using RNG_GetRandomNumber() function
+            
+   (#) To get another 32 bit Random number, go to step 3.       
+         
+                
+@endverbatim
+  *         
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_rng.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup RNG 
+  * @brief RNG driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup RNG_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup RNG_Group1 Initialization and Configuration functions
+ *  @brief    Initialization and Configuration functions 
+ *
+@verbatim    
+ ===============================================================================
+             ##### Initialization and Configuration functions #####
+ ===============================================================================  
+ [..] This section provides functions allowing to 
+   (+) Initialize the RNG peripheral
+   (+) Enable or disable the RNG peripheral
+   
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initializes the RNG peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void RNG_DeInit(void)
+{
+  /* Enable RNG reset state */
+  RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_RNG, ENABLE);
+
+  /* Release RNG from reset state */
+  RCC_AHB2PeriphResetCmd(RCC_AHB2Periph_RNG, DISABLE);
+}
+
+/**
+  * @brief  Enables or disables the RNG peripheral.
+  * @param  NewState: new state of the RNG peripheral.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RNG_Cmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the RNG */
+    RNG->CR |= RNG_CR_RNGEN;
+  }
+  else
+  {
+    /* Disable the RNG */
+    RNG->CR &= ~RNG_CR_RNGEN;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup RNG_Group2 Get 32 bit Random number function
+ *  @brief    Get 32 bit Random number function 
+ *
+
+@verbatim    
+ ===============================================================================
+                 ##### Get 32 bit Random number function #####
+ ===============================================================================  
+ [..] This section provides a function allowing to get the 32 bit Random number  
+  
+   (@)  Before to call this function you have to wait till DRDY flag is set,
+        using RNG_GetFlagStatus(RNG_FLAG_DRDY) function. 
+   
+@endverbatim
+  * @{
+  */
+
+
+/**
+  * @brief  Returns a 32-bit random number.
+  *   
+  * @note   Before to call this function you have to wait till DRDY (data ready)
+  *         flag is set, using RNG_GetFlagStatus(RNG_FLAG_DRDY) function.
+  * @note   Each time the the Random number data is read (using RNG_GetRandomNumber()
+  *         function), the RNG_FLAG_DRDY flag is automatically cleared.
+  * @note   In the case of a seed error, the generation of random numbers is 
+  *         interrupted for as long as the SECS bit is '1'. If a number is 
+  *         available in the RNG_DR register, it must not be used because it may 
+  *         not have enough entropy. In this case, it is recommended to clear the 
+  *         SEIS bit(using RNG_ClearFlag(RNG_FLAG_SECS) function), then disable 
+  *         and enable the RNG peripheral (using RNG_Cmd() function) to 
+  *         reinitialize and restart the RNG.
+  * @note   In the case of a clock error, the RNG is no more able to generate 
+  *         random numbers because the PLL48CLK clock is not correct. User have 
+  *         to check that the clock controller is correctly configured to provide
+  *         the RNG clock and clear the CEIS bit (using RNG_ClearFlag(RNG_FLAG_CECS) 
+  *         function) . The clock error has no impact on the previously generated 
+  *         random numbers, and the RNG_DR register contents can be used.
+  *         
+  * @param  None
+  * @retval 32-bit random number.
+  */
+uint32_t RNG_GetRandomNumber(void)
+{
+  /* Return the 32 bit random number from the DR register */
+  return RNG->DR;
+}
+
+
+/**
+  * @}
+  */
+
+/** @defgroup RNG_Group3 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+ *
+@verbatim   
+ ===============================================================================
+             ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+ [..] This section provides functions allowing to configure the RNG Interrupts and 
+      to get the status and clear flags and Interrupts pending bits.
+  
+ [..] The RNG provides 3 Interrupts sources and 3 Flags:
+  
+ *** Flags : ***
+ ===============
+ [..] 
+    (#) RNG_FLAG_DRDY :  In the case of the RNG_DR register contains valid 
+        random data. it is cleared by reading the valid data(using 
+        RNG_GetRandomNumber() function).
+
+    (#) RNG_FLAG_CECS : In the case of a seed error detection. 
+      
+    (#) RNG_FLAG_SECS : In the case of a clock error detection.
+              
+ *** Interrupts ***
+ ==================
+ [..] If enabled, an RNG interrupt is pending :
+    
+   (#) In the case of the RNG_DR register contains valid random data. 
+       This interrupt source is cleared once the RNG_DR register has been read 
+       (using RNG_GetRandomNumber() function) until a new valid value is 
+       computed; or 
+   (#) In the case of a seed error : One of the following faulty sequences has 
+       been detected:
+       (++) More than 64 consecutive bits at the same value (0 or 1)
+       (++) More than 32 consecutive alternance of 0 and 1 (0101010101...01)
+       This interrupt source is cleared using RNG_ClearITPendingBit(RNG_IT_SEI)
+       function; or
+   (#) In the case of a clock error : the PLL48CLK (RNG peripheral clock source) 
+       was not correctly detected (fPLL48CLK< fHCLK/16). This interrupt source is
+       cleared using RNG_ClearITPendingBit(RNG_IT_CEI) function.
+       -@- note In this case, User have to check that the clock controller is 
+           correctly configured to provide the RNG clock. 
+
+ *** Managing the RNG controller events : ***
+ ============================================
+ [..] The user should identify which mode will be used in his application to manage 
+      the RNG controller events: Polling mode or Interrupt mode.
+  
+   (#) In the Polling Mode it is advised to use the following functions:
+       (++) RNG_GetFlagStatus() : to check if flags events occur. 
+       (++) RNG_ClearFlag()     : to clear the flags events.
+  
+       -@@- RNG_FLAG_DRDY can not be cleared by RNG_ClearFlag(). it is cleared only 
+            by reading the Random number data.      
+  
+   (#)  In the Interrupt Mode it is advised to use the following functions:
+        (++) RNG_ITConfig()       : to enable or disable the interrupt source.
+        (++) RNG_GetITStatus()    : to check if Interrupt occurs.
+        (++) RNG_ClearITPendingBit() : to clear the Interrupt pending Bit 
+             (corresponding Flag). 
+  
+@endverbatim
+  * @{
+  */ 
+
+/**
+  * @brief  Enables or disables the RNG interrupt.
+  * @note   The RNG provides 3 interrupt sources,
+  *           - Computed data is ready event (DRDY), and           
+  *           - Seed error Interrupt (SEI) and 
+  *           - Clock error Interrupt (CEI), 
+  *         all these interrupts sources are enabled by setting the IE bit in 
+  *         CR register. However, each interrupt have its specific status bit
+  *         (see RNG_GetITStatus() function) and clear bit except the DRDY event
+  *         (see RNG_ClearITPendingBit() function).
+  * @param  NewState: new state of the RNG interrupt.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RNG_ITConfig(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the RNG interrupt */
+    RNG->CR |= RNG_CR_IE;
+  }
+  else
+  {
+    /* Disable the RNG interrupt */
+    RNG->CR &= ~RNG_CR_IE;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified RNG flag is set or not.
+  * @param  RNG_FLAG: specifies the RNG flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg RNG_FLAG_DRDY: Data Ready flag.
+  *            @arg RNG_FLAG_CECS: Clock Error Current flag.
+  *            @arg RNG_FLAG_SECS: Seed Error Current flag.
+  * @retval The new state of RNG_FLAG (SET or RESET).
+  */
+FlagStatus RNG_GetFlagStatus(uint8_t RNG_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_RNG_GET_FLAG(RNG_FLAG));
+
+  /* Check the status of the specified RNG flag */
+  if ((RNG->SR & RNG_FLAG) != (uint8_t)RESET)
+  {
+    /* RNG_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* RNG_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the RNG_FLAG status */
+  return  bitstatus;
+}
+
+
+/**
+  * @brief  Clears the RNG flags.
+  * @param  RNG_FLAG: specifies the flag to clear. 
+  *          This parameter can be any combination of the following values:
+  *            @arg RNG_FLAG_CECS: Clock Error Current flag.
+  *            @arg RNG_FLAG_SECS: Seed Error Current flag.
+  * @note   RNG_FLAG_DRDY can not be cleared by RNG_ClearFlag() function. 
+  *         This flag is cleared only by reading the Random number data (using 
+  *         RNG_GetRandomNumber() function).                           
+  * @retval None
+  */
+void RNG_ClearFlag(uint8_t RNG_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_RNG_CLEAR_FLAG(RNG_FLAG));
+  /* Clear the selected RNG flags */
+  RNG->SR = ~(uint32_t)(((uint32_t)RNG_FLAG) << 4);
+}
+
+/**
+  * @brief  Checks whether the specified RNG interrupt has occurred or not.
+  * @param  RNG_IT: specifies the RNG interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg RNG_IT_CEI: Clock Error Interrupt.
+  *            @arg RNG_IT_SEI: Seed Error Interrupt.                   
+  * @retval The new state of RNG_IT (SET or RESET).
+  */
+ITStatus RNG_GetITStatus(uint8_t RNG_IT)
+{
+  ITStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_RNG_GET_IT(RNG_IT));
+
+  /* Check the status of the specified RNG interrupt */
+  if ((RNG->SR & RNG_IT) != (uint8_t)RESET)
+  {
+    /* RNG_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* RNG_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the RNG_IT status */
+  return bitstatus;
+}
+
+
+/**
+  * @brief  Clears the RNG interrupt pending bit(s).
+  * @param  RNG_IT: specifies the RNG interrupt pending bit(s) to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg RNG_IT_CEI: Clock Error Interrupt.
+  *            @arg RNG_IT_SEI: Seed Error Interrupt.
+  * @retval None
+  */
+void RNG_ClearITPendingBit(uint8_t RNG_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_RNG_IT(RNG_IT));
+
+  /* Clear the selected RNG interrupt pending bit */
+  RNG->SR = (uint8_t)~RNG_IT;
+}
+/**
+  * @}
+  */ 
+  
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c
new file mode 100644
index 0000000000000000000000000000000000000000..5d96db5a3a607d5466eac7c04331ad144cd99f2a
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rtc.c
@@ -0,0 +1,2761 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_rtc.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Real-Time Clock (RTC) peripheral:
+  *           + Initialization
+  *           + Calendar (Time and Date) configuration
+  *           + Alarms (Alarm A and Alarm B) configuration
+  *           + WakeUp Timer configuration
+  *           + Daylight Saving configuration
+  *           + Output pin Configuration
+  *           + Coarse digital Calibration configuration
+  *           + Smooth digital Calibration configuration
+  *           + TimeStamp configuration
+  *           + Tampers configuration
+  *           + Backup Data Registers configuration
+  *           + Shift control synchronisation    
+  *           + RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration
+  *           + Interrupts and flags management
+  *
+@verbatim
+
+ ===================================================================
+              ##### Backup Domain Operating Condition #####
+ ===================================================================
+ [..] The real-time clock (RTC), the RTC backup registers, and the backup 
+      SRAM (BKP SRAM) can be powered from the VBAT voltage when the main 
+      VDD supply is powered off.
+      To retain the content of the RTC backup registers, backup SRAM, and supply 
+      the RTC when VDD is turned off, VBAT pin can be connected to an optional 
+      standby voltage supplied by a battery or by another source.
+
+ [..] To allow the RTC to operate even when the main digital supply (VDD) is turned
+      off, the VBAT pin powers the following blocks:
+   (#) The RTC
+   (#) The LSE oscillator
+   (#) The backup SRAM when the low power backup regulator is enabled
+   (#) PC13 to PC15 I/Os, plus PI8 I/O (when available)
+  
+ [..] When the backup domain is supplied by VDD (analog switch connected to VDD),
+      the following functions are available:
+   (#) PC14 and PC15 can be used as either GPIO or LSE pins
+   (#) PC13 can be used as a GPIO or as the RTC_AF1 pin
+   (#) PI8 can be used as a GPIO or as the RTC_AF2 pin
+  
+ [..] When the backup domain is supplied by VBAT (analog switch connected to VBAT 
+      because VDD is not present), the following functions are available:
+   (#) PC14 and PC15 can be used as LSE pins only
+   (#) PC13 can be used as the RTC_AF1 pin 
+   (#) PI8 can be used as the RTC_AF2 pin
+  
+            
+                   ##### Backup Domain Reset #####
+ ===================================================================
+ [..] The backup domain reset sets all RTC registers and the RCC_BDCR register 
+      to their reset values. The BKPSRAM is not affected by this reset. The only
+      way of resetting the BKPSRAM is through the Flash interface by requesting 
+      a protection level change from 1 to 0.
+ [..] A backup domain reset is generated when one of the following events occurs:
+   (#) Software reset, triggered by setting the BDRST bit in the 
+       RCC Backup domain control register (RCC_BDCR). You can use the
+       RCC_BackupResetCmd().
+   (#) VDD or VBAT power on, if both supplies have previously been powered off.
+  
+
+                   ##### Backup Domain Access #####
+ ===================================================================
+ [..] After reset, the backup domain (RTC registers, RTC backup data 
+      registers and backup SRAM) is protected against possible unwanted write 
+      accesses. 
+ [..] To enable access to the RTC Domain and RTC registers, proceed as follows:
+   (+) Enable the Power Controller (PWR) APB1 interface clock using the
+       RCC_APB1PeriphClockCmd() function.
+   (+) Enable access to RTC domain using the PWR_BackupAccessCmd() function.
+   (+) Select the RTC clock source using the RCC_RTCCLKConfig() function.
+   (+) Enable RTC Clock using the RCC_RTCCLKCmd() function.
+  
+  
+                  ##### How to use RTC Driver #####
+ ===================================================================
+ [..] 
+   (+) Enable the RTC domain access (see description in the section above)
+   (+) Configure the RTC Prescaler (Asynchronous and Synchronous) and RTC hour 
+       format using the RTC_Init() function.
+  
+ *** Time and Date configuration ***
+ ===================================
+ [..] 
+   (+) To configure the RTC Calendar (Time and Date) use the RTC_SetTime()
+       and RTC_SetDate() functions.
+   (+) To read the RTC Calendar, use the RTC_GetTime() and RTC_GetDate() functions.
+   (+) Use the RTC_DayLightSavingConfig() function to add or sub one
+       hour to the RTC Calendar.    
+  
+ *** Alarm configuration ***
+ ===========================
+ [..]
+   (+) To configure the RTC Alarm use the RTC_SetAlarm() function.
+   (+) Enable the selected RTC Alarm using the RTC_AlarmCmd() function
+   (+) To read the RTC Alarm, use the RTC_GetAlarm() function.
+   (+) To read the RTC alarm SubSecond, use the RTC_GetAlarmSubSecond() function.
+  
+ *** RTC Wakeup configuration ***
+ ================================
+ [..] 
+   (+) Configure the RTC Wakeup Clock source use the RTC_WakeUpClockConfig()
+       function.
+   (+) Configure the RTC WakeUp Counter using the RTC_SetWakeUpCounter() function  
+   (+) Enable the RTC WakeUp using the RTC_WakeUpCmd() function  
+   (+) To read the RTC WakeUp Counter register, use the RTC_GetWakeUpCounter() 
+       function.
+  
+ *** Outputs configuration ***
+ =============================
+ [..] The RTC has 2 different outputs:
+   (+) AFO_ALARM: this output is used to manage the RTC Alarm A, Alarm B
+       and WaKeUp signals. To output the selected RTC signal on RTC_AF1 pin, use the 
+       RTC_OutputConfig() function.                
+   (+) AFO_CALIB: this output is 512Hz signal or 1Hz. To output the RTC Clock on 
+       RTC_AF1 pin, use the RTC_CalibOutputCmd() function.
+  
+ *** Smooth digital Calibration configuration ***
+ ================================================    
+ [..]
+   (+) Configure the RTC Original Digital Calibration Value and the corresponding
+       calibration cycle period (32s,16s and 8s) using the RTC_SmoothCalibConfig() 
+       function.
+  
+ *** Coarse digital Calibration configuration ***
+ ================================================
+ [..]
+   (+) Configure the RTC Coarse Calibration Value and the corresponding
+       sign using the RTC_CoarseCalibConfig() function.
+   (+) Enable the RTC Coarse Calibration using the RTC_CoarseCalibCmd() function  
+  
+ *** TimeStamp configuration ***
+ ===============================
+ [..]
+   (+) Configure the RTC_AF1 trigger and enables the RTC TimeStamp using the RTC
+      _TimeStampCmd() function.
+   (+) To read the RTC TimeStamp Time and Date register, use the RTC_GetTimeStamp()
+       function.
+   (+) To read the RTC TimeStamp SubSecond register, use the 
+       RTC_GetTimeStampSubSecond() function.
+   (+) The TAMPER1 alternate function can be mapped either to RTC_AF1(PC13)
+       or RTC_AF2 (PI8) depending on the value of TAMP1INSEL bit in 
+       RTC_TAFCR register. You can use the  RTC_TamperPinSelection() function to
+       select the corresponding pin.     
+  
+ *** Tamper configuration ***
+ ============================
+ [..]
+   (+) Enable the RTC Tamper using the RTC_TamperCmd() function.
+   (+) Configure the Tamper filter count using RTC_TamperFilterConfig()
+       function. 
+   (+) Configure the RTC Tamper trigger Edge or Level according to the Tamper 
+       filter (if equal to 0 Edge else Level) value using the RTC_TamperConfig() 
+       function.
+   (+) Configure the Tamper sampling frequency using RTC_TamperSamplingFreqConfig()
+       function.
+   (+) Configure the Tamper precharge or discharge duration using 
+       RTC_TamperPinsPrechargeDuration() function.
+   (+) Enable the Tamper Pull-UP using RTC_TamperPullUpDisableCmd() function.
+   (+) Enable the Time stamp on Tamper detection event using  
+       TC_TSOnTamperDetecCmd() function.
+   (+) The TIMESTAMP alternate function can be mapped to either RTC_AF1 
+       or RTC_AF2 depending on the value of the TSINSEL bit in the RTC_TAFCR 
+       register. You can use the  RTC_TimeStampPinSelection() function to select 
+       the corresponding pin. 
+  
+ *** Backup Data Registers configuration ***
+ ===========================================
+ [..]
+   (+) To write to the RTC Backup Data registers, use the RTC_WriteBackupRegister()
+       function.  
+   (+) To read the RTC Backup Data registers, use the RTC_ReadBackupRegister()
+       function.
+   
+
+                  ##### RTC and low power modes #####
+ ===================================================================
+ [..] The MCU can be woken up from a low power mode by an RTC alternate 
+      function.
+ [..] The RTC alternate functions are the RTC alarms (Alarm A and Alarm B), 
+      RTC wakeup, RTC tamper event detection and RTC time stamp event detection.
+      These RTC alternate functions can wake up the system from the Stop and 
+      Standby lowpower modes.
+ [..] The system can also wake up from low power modes without depending 
+      on an external interrupt (Auto-wakeup mode), by using the RTC alarm 
+      or the RTC wakeup events.
+ [..] The RTC provides a programmable time base for waking up from the 
+      Stop or Standby mode at regular intervals.
+      Wakeup from STOP and Standby modes is possible only when the RTC clock source
+      is LSE or LSI.
+  
+
+          ##### Selection of RTC_AF1 alternate functions #####
+ ===================================================================
+ [..] The RTC_AF1 pin (PC13) can be used for the following purposes:
+   (+) AFO_ALARM output
+   (+) AFO_CALIB output
+   (+) AFI_TAMPER
+   (+) AFI_TIMESTAMP
+ 
+ [..]   
+   +-------------------------------------------------------------------------------------------------------------+
+   |     Pin         |AFO_ALARM |AFO_CALIB |AFI_TAMPER |AFI_TIMESTAMP | TAMP1INSEL |   TSINSEL    |ALARMOUTTYPE  |
+   |  configuration  | ENABLED  | ENABLED  |  ENABLED  |   ENABLED    |TAMPER1 pin |TIMESTAMP pin |  AFO_ALARM   |
+   |  and function   |          |          |           |              | selection  |  selection   |Configuration |
+   |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------|
+   |   Alarm out     |          |          |           |              |    Don't   |     Don't    |              |
+   |   output OD     |     1    |Don't care|Don't care | Don't care   |    care    |     care     |      0       |
+   |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------|
+   |   Alarm out     |          |          |           |              |    Don't   |     Don't    |              |
+   |   output PP     |     1    |Don't care|Don't care | Don't care   |    care    |     care     |      1       |
+   |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------|
+   | Calibration out |          |          |           |              |    Don't   |     Don't    |              |
+   |   output PP     |     0    |    1     |Don't care | Don't care   |    care    |     care     |  Don't care  |
+   |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------|
+   |  TAMPER input   |          |          |           |              |            |     Don't    |              |
+   |   floating      |     0    |    0     |     1     |      0       |      0     |     care     |  Don't care  |
+   |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------|
+   |  TIMESTAMP and  |          |          |           |              |            |              |              |
+   |  TAMPER input   |     0    |    0     |     1     |      1       |      0     |      0       |  Don't care  |
+   |   floating      |          |          |           |              |            |              |              |
+   |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------|
+   | TIMESTAMP input |          |          |           |              |    Don't   |              |              |
+   |    floating     |     0    |    0     |     0     |      1       |    care    |      0       |  Don't care  |
+   |-----------------|----------|----------|-----------|--------------|------------|--------------|--------------|
+   |  Standard GPIO  |     0    |    0     |     0     |      0       | Don't care |  Don't care  |  Don't care  |
+   +-------------------------------------------------------------------------------------------------------------+
+
+            
+        #####  Selection of RTC_AF2 alternate functions #####
+ ===================================================================
+ [..] The RTC_AF2 pin (PI8) can be used for the following purposes:
+   (+) AFI_TAMPER
+   (+) AFI_TIMESTAMP
+ [..]
+   +---------------------------------------------------------------------------------------+
+   |     Pin         |AFI_TAMPER |AFI_TIMESTAMP | TAMP1INSEL |   TSINSEL    |ALARMOUTTYPE  |
+   |  configuration  |  ENABLED  |   ENABLED    |TAMPER1 pin |TIMESTAMP pin |  AFO_ALARM   |
+   |  and function   |           |              | selection  |  selection   |Configuration |
+   |-----------------|-----------|--------------|------------|--------------|--------------|
+   |  TAMPER input   |           |              |            |     Don't    |              |
+   |   floating      |     1     |      0       |      1     |     care     |  Don't care  |
+   |-----------------|-----------|--------------|------------|--------------|--------------|
+   |  TIMESTAMP and  |           |              |            |              |              |
+   |  TAMPER input   |     1     |      1       |      1     |      1       |  Don't care  |
+   |   floating      |           |              |            |              |              |
+   |-----------------|-----------|--------------|------------|--------------|--------------|
+   | TIMESTAMP input |           |              |    Don't   |              |              |
+   |    floating     |     0     |      1       |    care    |      1       |  Don't care  |
+   |-----------------|-----------|--------------|------------|--------------|--------------|
+   |  Standard GPIO  |     0     |      0       | Don't care |  Don't care  |  Don't care  |
+   +---------------------------------------------------------------------------------------+   
+ 
+     
+@endverbatim
+  
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_rtc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup RTC 
+  * @brief RTC driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* Masks Definition */
+#define RTC_TR_RESERVED_MASK    ((uint32_t)0x007F7F7F)
+#define RTC_DR_RESERVED_MASK    ((uint32_t)0x00FFFF3F) 
+#define RTC_INIT_MASK           ((uint32_t)0xFFFFFFFF)  
+#define RTC_RSF_MASK            ((uint32_t)0xFFFFFF5F)
+#define RTC_FLAGS_MASK          ((uint32_t)(RTC_FLAG_TSOVF | RTC_FLAG_TSF | RTC_FLAG_WUTF | \
+                                            RTC_FLAG_ALRBF | RTC_FLAG_ALRAF | RTC_FLAG_INITF | \
+                                            RTC_FLAG_RSF | RTC_FLAG_INITS | RTC_FLAG_WUTWF | \
+                                            RTC_FLAG_ALRBWF | RTC_FLAG_ALRAWF | RTC_FLAG_TAMP1F | \
+                                            RTC_FLAG_RECALPF | RTC_FLAG_SHPF))
+
+#define INITMODE_TIMEOUT         ((uint32_t) 0x00010000)
+#define SYNCHRO_TIMEOUT          ((uint32_t) 0x00020000)
+#define RECALPF_TIMEOUT          ((uint32_t) 0x00020000)
+#define SHPF_TIMEOUT             ((uint32_t) 0x00001000)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static uint8_t RTC_ByteToBcd2(uint8_t Value);
+static uint8_t RTC_Bcd2ToByte(uint8_t Value);
+
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup RTC_Private_Functions
+  * @{
+  */ 
+
+/** @defgroup RTC_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+             ##### Initialization and Configuration functions #####
+ ===============================================================================
+ 
+ [..] This section provide functions allowing to initialize and configure the RTC
+      Prescaler (Synchronous and Asynchronous), RTC Hour format, disable RTC registers
+      Write protection, enter and exit the RTC initialization mode, RTC registers
+      synchronization check and reference clock detection enable.
+  
+   (#) The RTC Prescaler is programmed to generate the RTC 1Hz time base. It is
+       split into 2 programmable prescalers to minimize power consumption.
+       (++) A 7-bit asynchronous prescaler and A 13-bit synchronous prescaler.
+       (++) When both prescalers are used, it is recommended to configure the 
+            asynchronous prescaler to a high value to minimize consumption.
+
+   (#) All RTC registers are Write protected. Writing to the RTC registers
+       is enabled by writing a key into the Write Protection register, RTC_WPR.
+
+   (#) To Configure the RTC Calendar, user application should enter initialization
+       mode. In this mode, the calendar counter is stopped and its value can be 
+       updated. When the initialization sequence is complete, the calendar restarts 
+       counting after 4 RTCCLK cycles.
+
+   (#) To read the calendar through the shadow registers after Calendar initialization,
+       calendar update or after wakeup from low power modes the software must first 
+       clear the RSF flag. The software must then wait until it is set again before 
+       reading the calendar, which means that the calendar registers have been 
+       correctly copied into the RTC_TR and RTC_DR shadow registers.
+       The RTC_WaitForSynchro() function implements the above software sequence 
+       (RSF clear and RSF check).
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the RTC registers to their default reset values.
+  * @note   This function doesn't reset the RTC Clock source and RTC Backup Data
+  *         registers.       
+  * @param  None
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC registers are deinitialized
+  *          - ERROR: RTC registers are not deinitialized
+  */
+ErrorStatus RTC_DeInit(void)
+{
+  __IO uint32_t wutcounter = 0x00;
+  uint32_t wutwfstatus = 0x00;
+  ErrorStatus status = ERROR;
+  
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Set Initialization mode */
+  if (RTC_EnterInitMode() == ERROR)
+  {
+    status = ERROR;
+  }  
+  else
+  {
+    /* Reset TR, DR and CR registers */
+    RTC->TR = (uint32_t)0x00000000;
+    RTC->DR = (uint32_t)0x00002101;
+    /* Reset All CR bits except CR[2:0] */
+    RTC->CR &= (uint32_t)0x00000007;
+  
+    /* Wait till RTC WUTWF flag is set and if Time out is reached exit */
+    do
+    {
+      wutwfstatus = RTC->ISR & RTC_ISR_WUTWF;
+      wutcounter++;  
+    } while((wutcounter != INITMODE_TIMEOUT) && (wutwfstatus == 0x00));
+    
+    if ((RTC->ISR & RTC_ISR_WUTWF) == RESET)
+    {
+      status = ERROR;
+    }
+    else
+    {
+      /* Reset all RTC CR register bits */
+      RTC->CR &= (uint32_t)0x00000000;
+      RTC->WUTR = (uint32_t)0x0000FFFF;
+      RTC->PRER = (uint32_t)0x007F00FF;
+      RTC->CALIBR = (uint32_t)0x00000000;
+      RTC->ALRMAR = (uint32_t)0x00000000;        
+      RTC->ALRMBR = (uint32_t)0x00000000;
+      RTC->SHIFTR = (uint32_t)0x00000000;
+      RTC->CALR = (uint32_t)0x00000000;
+      RTC->ALRMASSR = (uint32_t)0x00000000;
+      RTC->ALRMBSSR = (uint32_t)0x00000000;
+      
+      /* Reset ISR register and exit initialization mode */
+      RTC->ISR = (uint32_t)0x00000000;
+      
+      /* Reset Tamper and alternate functions configuration register */
+      RTC->TAFCR = 0x00000000;
+  
+      if(RTC_WaitForSynchro() == ERROR)
+      {
+        status = ERROR;
+      }
+      else
+      {
+        status = SUCCESS;      
+      }
+    }
+  }
+  
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;  
+  
+  return status;
+}
+
+/**
+  * @brief  Initializes the RTC registers according to the specified parameters 
+  *         in RTC_InitStruct.
+  * @param  RTC_InitStruct: pointer to a RTC_InitTypeDef structure that contains 
+  *         the configuration information for the RTC peripheral.
+  * @note   The RTC Prescaler register is write protected and can be written in 
+  *         initialization mode only.  
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC registers are initialized
+  *          - ERROR: RTC registers are not initialized  
+  */
+ErrorStatus RTC_Init(RTC_InitTypeDef* RTC_InitStruct)
+{
+  ErrorStatus status = ERROR;
+  
+  /* Check the parameters */
+  assert_param(IS_RTC_HOUR_FORMAT(RTC_InitStruct->RTC_HourFormat));
+  assert_param(IS_RTC_ASYNCH_PREDIV(RTC_InitStruct->RTC_AsynchPrediv));
+  assert_param(IS_RTC_SYNCH_PREDIV(RTC_InitStruct->RTC_SynchPrediv));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Set Initialization mode */
+  if (RTC_EnterInitMode() == ERROR)
+  {
+    status = ERROR;
+  } 
+  else
+  {
+    /* Clear RTC CR FMT Bit */
+    RTC->CR &= ((uint32_t)~(RTC_CR_FMT));
+    /* Set RTC_CR register */
+    RTC->CR |=  ((uint32_t)(RTC_InitStruct->RTC_HourFormat));
+  
+    /* Configure the RTC PRER */
+    RTC->PRER = (uint32_t)(RTC_InitStruct->RTC_SynchPrediv);
+    RTC->PRER |= (uint32_t)(RTC_InitStruct->RTC_AsynchPrediv << 16);
+
+    /* Exit Initialization mode */
+    RTC_ExitInitMode();
+
+    status = SUCCESS;    
+  }
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+  
+  return status;
+}
+
+/**
+  * @brief  Fills each RTC_InitStruct member with its default value.
+  * @param  RTC_InitStruct: pointer to a RTC_InitTypeDef structure which will be 
+  *         initialized.
+  * @retval None
+  */
+void RTC_StructInit(RTC_InitTypeDef* RTC_InitStruct)
+{
+  /* Initialize the RTC_HourFormat member */
+  RTC_InitStruct->RTC_HourFormat = RTC_HourFormat_24;
+    
+  /* Initialize the RTC_AsynchPrediv member */
+  RTC_InitStruct->RTC_AsynchPrediv = (uint32_t)0x7F;
+
+  /* Initialize the RTC_SynchPrediv member */
+  RTC_InitStruct->RTC_SynchPrediv = (uint32_t)0xFF; 
+}
+
+/**
+  * @brief  Enables or disables the RTC registers write protection.
+  * @note   All the RTC registers are write protected except for RTC_ISR[13:8], 
+  *         RTC_TAFCR and RTC_BKPxR.
+  * @note   Writing a wrong key reactivates the write protection.
+  * @note   The protection mechanism is not affected by system reset.  
+  * @param  NewState: new state of the write protection.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RTC_WriteProtectionCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  if (NewState != DISABLE)
+  {
+    /* Enable the write protection for RTC registers */
+    RTC->WPR = 0xFF;   
+  }
+  else
+  {
+    /* Disable the write protection for RTC registers */
+    RTC->WPR = 0xCA;
+    RTC->WPR = 0x53;    
+  }
+}
+
+/**
+  * @brief  Enters the RTC Initialization mode.
+  * @note   The RTC Initialization mode is write protected, use the 
+  *         RTC_WriteProtectionCmd(DISABLE) before calling this function.    
+  * @param  None
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC is in Init mode
+  *          - ERROR: RTC is not in Init mode  
+  */
+ErrorStatus RTC_EnterInitMode(void)
+{
+  __IO uint32_t initcounter = 0x00;
+  ErrorStatus status = ERROR;
+  uint32_t initstatus = 0x00;
+     
+  /* Check if the Initialization mode is set */
+  if ((RTC->ISR & RTC_ISR_INITF) == (uint32_t)RESET)
+  {
+    /* Set the Initialization mode */
+    RTC->ISR = (uint32_t)RTC_INIT_MASK;
+    
+    /* Wait till RTC is in INIT state and if Time out is reached exit */
+    do
+    {
+      initstatus = RTC->ISR & RTC_ISR_INITF;
+      initcounter++;  
+    } while((initcounter != INITMODE_TIMEOUT) && (initstatus == 0x00));
+    
+    if ((RTC->ISR & RTC_ISR_INITF) != RESET)
+    {
+      status = SUCCESS;
+    }
+    else
+    {
+      status = ERROR;
+    }        
+  }
+  else
+  {
+    status = SUCCESS;  
+  } 
+    
+  return (status);  
+}
+
+/**
+  * @brief  Exits the RTC Initialization mode.
+  * @note   When the initialization sequence is complete, the calendar restarts 
+  *         counting after 4 RTCCLK cycles.  
+  * @note   The RTC Initialization mode is write protected, use the 
+  *         RTC_WriteProtectionCmd(DISABLE) before calling this function.      
+  * @param  None
+  * @retval None
+  */
+void RTC_ExitInitMode(void)
+{ 
+  /* Exit Initialization mode */
+  RTC->ISR &= (uint32_t)~RTC_ISR_INIT;  
+}
+
+/**
+  * @brief  Waits until the RTC Time and Date registers (RTC_TR and RTC_DR) are 
+  *         synchronized with RTC APB clock.
+  * @note   The RTC Resynchronization mode is write protected, use the 
+  *         RTC_WriteProtectionCmd(DISABLE) before calling this function. 
+  * @note   To read the calendar through the shadow registers after Calendar 
+  *         initialization, calendar update or after wakeup from low power modes 
+  *         the software must first clear the RSF flag. 
+  *         The software must then wait until it is set again before reading 
+  *         the calendar, which means that the calendar registers have been 
+  *         correctly copied into the RTC_TR and RTC_DR shadow registers.   
+  * @param  None
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC registers are synchronised
+  *          - ERROR: RTC registers are not synchronised
+  */
+ErrorStatus RTC_WaitForSynchro(void)
+{
+  __IO uint32_t synchrocounter = 0;
+  ErrorStatus status = ERROR;
+  uint32_t synchrostatus = 0x00;
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+    
+  /* Clear RSF flag */
+  RTC->ISR &= (uint32_t)RTC_RSF_MASK;
+    
+  /* Wait the registers to be synchronised */
+  do
+  {
+    synchrostatus = RTC->ISR & RTC_ISR_RSF;
+    synchrocounter++;  
+  } while((synchrocounter != SYNCHRO_TIMEOUT) && (synchrostatus == 0x00));
+    
+  if ((RTC->ISR & RTC_ISR_RSF) != RESET)
+  {
+    status = SUCCESS;
+  }
+  else
+  {
+    status = ERROR;
+  }        
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+    
+  return (status); 
+}
+
+/**
+  * @brief  Enables or disables the RTC reference clock detection.
+  * @param  NewState: new state of the RTC reference clock.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC reference clock detection is enabled
+  *          - ERROR: RTC reference clock detection is disabled  
+  */
+ErrorStatus RTC_RefClockCmd(FunctionalState NewState)
+{ 
+  ErrorStatus status = ERROR;
+  
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+    
+  /* Set Initialization mode */
+  if (RTC_EnterInitMode() == ERROR)
+  {
+    status = ERROR;
+  } 
+  else
+  {  
+    if (NewState != DISABLE)
+    {
+      /* Enable the RTC reference clock detection */
+      RTC->CR |= RTC_CR_REFCKON;   
+    }
+    else
+    {
+      /* Disable the RTC reference clock detection */
+      RTC->CR &= ~RTC_CR_REFCKON;    
+    }
+    /* Exit Initialization mode */
+    RTC_ExitInitMode();
+    
+    status = SUCCESS;
+  }
+  
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;  
+  
+  return status; 
+}
+
+/**
+  * @brief  Enables or Disables the Bypass Shadow feature.
+  * @note   When the Bypass Shadow is enabled the calendar value are taken 
+  *         directly from the Calendar counter.
+  * @param  NewState: new state of the Bypass Shadow feature.
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+*/
+void RTC_BypassShadowCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  if (NewState != DISABLE)
+  {
+    /* Set the BYPSHAD bit */
+    RTC->CR |= (uint8_t)RTC_CR_BYPSHAD;
+  }
+  else
+  {
+    /* Reset the BYPSHAD bit */
+    RTC->CR &= (uint8_t)~RTC_CR_BYPSHAD;
+  }
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group2 Time and Date configuration functions
+ *  @brief   Time and Date configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+                 ##### Time and Date configuration functions #####
+ ===============================================================================  
+ 
+ [..] This section provide functions allowing to program and read the RTC Calendar
+      (Time and Date).
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Set the RTC current time.
+  * @param  RTC_Format: specifies the format of the entered parameters.
+  *          This parameter can be  one of the following values:
+  *            @arg RTC_Format_BIN:  Binary data format 
+  *            @arg RTC_Format_BCD:  BCD data format
+  * @param  RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure that contains 
+  *                        the time configuration information for the RTC.     
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC Time register is configured
+  *          - ERROR: RTC Time register is not configured
+  */
+ErrorStatus RTC_SetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct)
+{
+  uint32_t tmpreg = 0;
+  ErrorStatus status = ERROR;
+    
+  /* Check the parameters */
+  assert_param(IS_RTC_FORMAT(RTC_Format));
+  
+  if (RTC_Format == RTC_Format_BIN)
+  {
+    if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET)
+    {
+      assert_param(IS_RTC_HOUR12(RTC_TimeStruct->RTC_Hours));
+      assert_param(IS_RTC_H12(RTC_TimeStruct->RTC_H12));
+    } 
+    else
+    {
+      RTC_TimeStruct->RTC_H12 = 0x00;
+      assert_param(IS_RTC_HOUR24(RTC_TimeStruct->RTC_Hours));
+    }
+    assert_param(IS_RTC_MINUTES(RTC_TimeStruct->RTC_Minutes));
+    assert_param(IS_RTC_SECONDS(RTC_TimeStruct->RTC_Seconds));
+  }
+  else
+  {
+    if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET)
+    {
+      tmpreg = RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours);
+      assert_param(IS_RTC_HOUR12(tmpreg));
+      assert_param(IS_RTC_H12(RTC_TimeStruct->RTC_H12)); 
+    } 
+    else
+    {
+      RTC_TimeStruct->RTC_H12 = 0x00;
+      assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours)));
+    }
+    assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Minutes)));
+    assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Seconds)));
+  }
+  
+  /* Check the input parameters format */
+  if (RTC_Format != RTC_Format_BIN)
+  {
+    tmpreg = (((uint32_t)(RTC_TimeStruct->RTC_Hours) << 16) | \
+             ((uint32_t)(RTC_TimeStruct->RTC_Minutes) << 8) | \
+             ((uint32_t)RTC_TimeStruct->RTC_Seconds) | \
+             ((uint32_t)(RTC_TimeStruct->RTC_H12) << 16)); 
+  }  
+  else
+  {
+    tmpreg = (uint32_t)(((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Hours) << 16) | \
+                   ((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Minutes) << 8) | \
+                   ((uint32_t)RTC_ByteToBcd2(RTC_TimeStruct->RTC_Seconds)) | \
+                   (((uint32_t)RTC_TimeStruct->RTC_H12) << 16));
+  }  
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Set Initialization mode */
+  if (RTC_EnterInitMode() == ERROR)
+  {
+    status = ERROR;
+  } 
+  else
+  {
+    /* Set the RTC_TR register */
+    RTC->TR = (uint32_t)(tmpreg & RTC_TR_RESERVED_MASK);
+
+    /* Exit Initialization mode */
+    RTC_ExitInitMode(); 
+
+    /* If  RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */
+    if ((RTC->CR & RTC_CR_BYPSHAD) == RESET)
+    {
+    if(RTC_WaitForSynchro() == ERROR)
+    {
+      status = ERROR;
+    }
+    else
+    {
+      status = SUCCESS;
+    }
+  }
+    else
+    {
+      status = SUCCESS;
+    }
+  }
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+    
+  return status;
+}
+
+/**
+  * @brief  Fills each RTC_TimeStruct member with its default value
+  *         (Time = 00h:00min:00sec).
+  * @param  RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure which will be 
+  *         initialized.
+  * @retval None
+  */
+void RTC_TimeStructInit(RTC_TimeTypeDef* RTC_TimeStruct)
+{
+  /* Time = 00h:00min:00sec */
+  RTC_TimeStruct->RTC_H12 = RTC_H12_AM;
+  RTC_TimeStruct->RTC_Hours = 0;
+  RTC_TimeStruct->RTC_Minutes = 0;
+  RTC_TimeStruct->RTC_Seconds = 0; 
+}
+
+/**
+  * @brief  Get the RTC current Time.
+  * @param  RTC_Format: specifies the format of the returned parameters.
+  *          This parameter can be  one of the following values:
+  *            @arg RTC_Format_BIN:  Binary data format 
+  *            @arg RTC_Format_BCD:  BCD data format
+  * @param  RTC_TimeStruct: pointer to a RTC_TimeTypeDef structure that will 
+  *                        contain the returned current time configuration.     
+  * @retval None
+  */
+void RTC_GetTime(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_FORMAT(RTC_Format));
+
+  /* Get the RTC_TR register */
+  tmpreg = (uint32_t)(RTC->TR & RTC_TR_RESERVED_MASK); 
+  
+  /* Fill the structure fields with the read parameters */
+  RTC_TimeStruct->RTC_Hours = (uint8_t)((tmpreg & (RTC_TR_HT | RTC_TR_HU)) >> 16);
+  RTC_TimeStruct->RTC_Minutes = (uint8_t)((tmpreg & (RTC_TR_MNT | RTC_TR_MNU)) >>8);
+  RTC_TimeStruct->RTC_Seconds = (uint8_t)(tmpreg & (RTC_TR_ST | RTC_TR_SU));
+  RTC_TimeStruct->RTC_H12 = (uint8_t)((tmpreg & (RTC_TR_PM)) >> 16);  
+
+  /* Check the input parameters format */
+  if (RTC_Format == RTC_Format_BIN)
+  {
+    /* Convert the structure parameters to Binary format */
+    RTC_TimeStruct->RTC_Hours = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Hours);
+    RTC_TimeStruct->RTC_Minutes = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Minutes);
+    RTC_TimeStruct->RTC_Seconds = (uint8_t)RTC_Bcd2ToByte(RTC_TimeStruct->RTC_Seconds);   
+  }
+}
+
+/**
+  * @brief  Gets the RTC current Calendar Sub seconds value.
+  * @note   This function freeze the Time and Date registers after reading the 
+  *         SSR register.
+  * @param  None
+  * @retval RTC current Calendar Sub seconds value.
+  */
+uint32_t RTC_GetSubSecond(void)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Get sub seconds values from the correspondent registers*/
+  tmpreg = (uint32_t)(RTC->SSR);
+  
+  /* Read DR register to unfroze calendar registers */
+  (void) (RTC->DR);
+  
+  return (tmpreg);
+}
+
+/**
+  * @brief  Set the RTC current date.
+  * @param  RTC_Format: specifies the format of the entered parameters.
+  *          This parameter can be  one of the following values:
+  *            @arg RTC_Format_BIN:  Binary data format 
+  *            @arg RTC_Format_BCD:  BCD data format
+  * @param  RTC_DateStruct: pointer to a RTC_DateTypeDef structure that contains 
+  *                         the date configuration information for the RTC.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC Date register is configured
+  *          - ERROR: RTC Date register is not configured
+  */
+ErrorStatus RTC_SetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct)
+{
+  uint32_t tmpreg = 0;
+  ErrorStatus status = ERROR;
+  
+  /* Check the parameters */
+  assert_param(IS_RTC_FORMAT(RTC_Format));
+
+  if ((RTC_Format == RTC_Format_BIN) && ((RTC_DateStruct->RTC_Month & 0x10) == 0x10))
+  {
+    RTC_DateStruct->RTC_Month = (RTC_DateStruct->RTC_Month & (uint32_t)~(0x10)) + 0x0A;
+  }  
+  if (RTC_Format == RTC_Format_BIN)
+  {
+    assert_param(IS_RTC_YEAR(RTC_DateStruct->RTC_Year));
+    assert_param(IS_RTC_MONTH(RTC_DateStruct->RTC_Month));
+    assert_param(IS_RTC_DATE(RTC_DateStruct->RTC_Date));
+  }
+  else
+  {
+    assert_param(IS_RTC_YEAR(RTC_Bcd2ToByte(RTC_DateStruct->RTC_Year)));
+    tmpreg = RTC_Bcd2ToByte(RTC_DateStruct->RTC_Month);
+    assert_param(IS_RTC_MONTH(tmpreg));
+    tmpreg = RTC_Bcd2ToByte(RTC_DateStruct->RTC_Date);
+    assert_param(IS_RTC_DATE(tmpreg));
+  }
+  assert_param(IS_RTC_WEEKDAY(RTC_DateStruct->RTC_WeekDay));
+
+  /* Check the input parameters format */
+  if (RTC_Format != RTC_Format_BIN)
+  {
+    tmpreg = ((((uint32_t)RTC_DateStruct->RTC_Year) << 16) | \
+              (((uint32_t)RTC_DateStruct->RTC_Month) << 8) | \
+              ((uint32_t)RTC_DateStruct->RTC_Date) | \
+              (((uint32_t)RTC_DateStruct->RTC_WeekDay) << 13)); 
+  }  
+  else
+  {
+    tmpreg = (((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Year) << 16) | \
+              ((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Month) << 8) | \
+              ((uint32_t)RTC_ByteToBcd2(RTC_DateStruct->RTC_Date)) | \
+              ((uint32_t)RTC_DateStruct->RTC_WeekDay << 13));
+  }
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Set Initialization mode */
+  if (RTC_EnterInitMode() == ERROR)
+  {
+    status = ERROR;
+  } 
+  else
+  {
+    /* Set the RTC_DR register */
+    RTC->DR = (uint32_t)(tmpreg & RTC_DR_RESERVED_MASK);
+
+    /* Exit Initialization mode */
+    RTC_ExitInitMode(); 
+
+    /* If  RTC_CR_BYPSHAD bit = 0, wait for synchro else this check is not needed */
+    if ((RTC->CR & RTC_CR_BYPSHAD) == RESET)
+    {
+    if(RTC_WaitForSynchro() == ERROR)
+    {
+      status = ERROR;
+    }
+    else
+    {
+      status = SUCCESS;
+    }
+  }
+    else
+    {
+      status = SUCCESS;
+    }
+  }
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;   
+  
+  return status;
+}
+
+/**
+  * @brief  Fills each RTC_DateStruct member with its default value
+  *         (Monday, January 01 xx00).
+  * @param  RTC_DateStruct: pointer to a RTC_DateTypeDef structure which will be 
+  *         initialized.
+  * @retval None
+  */
+void RTC_DateStructInit(RTC_DateTypeDef* RTC_DateStruct)
+{
+  /* Monday, January 01 xx00 */
+  RTC_DateStruct->RTC_WeekDay = RTC_Weekday_Monday;
+  RTC_DateStruct->RTC_Date = 1;
+  RTC_DateStruct->RTC_Month = RTC_Month_January;
+  RTC_DateStruct->RTC_Year = 0;
+}
+
+/**
+  * @brief  Get the RTC current date. 
+  * @param  RTC_Format: specifies the format of the returned parameters.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_Format_BIN: Binary data format 
+  *            @arg RTC_Format_BCD: BCD data format
+  * @param RTC_DateStruct: pointer to a RTC_DateTypeDef structure that will 
+  *                        contain the returned current date configuration.     
+  * @retval None
+  */
+void RTC_GetDate(uint32_t RTC_Format, RTC_DateTypeDef* RTC_DateStruct)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_FORMAT(RTC_Format));
+  
+  /* Get the RTC_TR register */
+  tmpreg = (uint32_t)(RTC->DR & RTC_DR_RESERVED_MASK); 
+
+  /* Fill the structure fields with the read parameters */
+  RTC_DateStruct->RTC_Year = (uint8_t)((tmpreg & (RTC_DR_YT | RTC_DR_YU)) >> 16);
+  RTC_DateStruct->RTC_Month = (uint8_t)((tmpreg & (RTC_DR_MT | RTC_DR_MU)) >> 8);
+  RTC_DateStruct->RTC_Date = (uint8_t)(tmpreg & (RTC_DR_DT | RTC_DR_DU));
+  RTC_DateStruct->RTC_WeekDay = (uint8_t)((tmpreg & (RTC_DR_WDU)) >> 13);
+
+  /* Check the input parameters format */
+  if (RTC_Format == RTC_Format_BIN)
+  {
+    /* Convert the structure parameters to Binary format */
+    RTC_DateStruct->RTC_Year = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Year);
+    RTC_DateStruct->RTC_Month = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Month);
+    RTC_DateStruct->RTC_Date = (uint8_t)RTC_Bcd2ToByte(RTC_DateStruct->RTC_Date);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group3 Alarms configuration functions
+ *  @brief   Alarms (Alarm A and Alarm B) configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+         ##### Alarms A and B configuration functions #####
+ ===============================================================================  
+ 
+ [..] This section provide functions allowing to program and read the RTC Alarms.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Set the specified RTC Alarm.
+  * @note   The Alarm register can only be written when the corresponding Alarm
+  *         is disabled (Use the RTC_AlarmCmd(DISABLE)).    
+  * @param  RTC_Format: specifies the format of the returned parameters.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_Format_BIN: Binary data format 
+  *            @arg RTC_Format_BCD: BCD data format
+  * @param  RTC_Alarm: specifies the alarm to be configured.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_Alarm_A: to select Alarm A
+  *            @arg RTC_Alarm_B: to select Alarm B  
+  * @param  RTC_AlarmStruct: pointer to a RTC_AlarmTypeDef structure that 
+  *                          contains the alarm configuration parameters.     
+  * @retval None
+  */
+void RTC_SetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RTC_FORMAT(RTC_Format));
+  assert_param(IS_RTC_ALARM(RTC_Alarm));
+  assert_param(IS_ALARM_MASK(RTC_AlarmStruct->RTC_AlarmMask));
+  assert_param(IS_RTC_ALARM_DATE_WEEKDAY_SEL(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel));
+
+  if (RTC_Format == RTC_Format_BIN)
+  {
+    if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET)
+    {
+      assert_param(IS_RTC_HOUR12(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours));
+      assert_param(IS_RTC_H12(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12));
+    } 
+    else
+    {
+      RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = 0x00;
+      assert_param(IS_RTC_HOUR24(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours));
+    }
+    assert_param(IS_RTC_MINUTES(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes));
+    assert_param(IS_RTC_SECONDS(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds));
+    
+    if(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel == RTC_AlarmDateWeekDaySel_Date)
+    {
+      assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(RTC_AlarmStruct->RTC_AlarmDateWeekDay));
+    }
+    else
+    {
+      assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(RTC_AlarmStruct->RTC_AlarmDateWeekDay));
+    }
+  }
+  else
+  {
+    if ((RTC->CR & RTC_CR_FMT) != (uint32_t)RESET)
+    {
+      tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours);
+      assert_param(IS_RTC_HOUR12(tmpreg));
+      assert_param(IS_RTC_H12(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12));
+    } 
+    else
+    {
+      RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = 0x00;
+      assert_param(IS_RTC_HOUR24(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours)));
+    }
+    
+    assert_param(IS_RTC_MINUTES(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes)));
+    assert_param(IS_RTC_SECONDS(RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds)));
+    
+    if(RTC_AlarmStruct->RTC_AlarmDateWeekDaySel == RTC_AlarmDateWeekDaySel_Date)
+    {
+      tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay);
+      assert_param(IS_RTC_ALARM_DATE_WEEKDAY_DATE(tmpreg));    
+    }
+    else
+    {
+      tmpreg = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay);
+      assert_param(IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(tmpreg));      
+    }    
+  }
+
+  /* Check the input parameters format */
+  if (RTC_Format != RTC_Format_BIN)
+  {
+    tmpreg = (((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours) << 16) | \
+              ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes) << 8) | \
+              ((uint32_t)RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds) | \
+              ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12) << 16) | \
+              ((uint32_t)(RTC_AlarmStruct->RTC_AlarmDateWeekDay) << 24) | \
+              ((uint32_t)RTC_AlarmStruct->RTC_AlarmDateWeekDaySel) | \
+              ((uint32_t)RTC_AlarmStruct->RTC_AlarmMask)); 
+  }  
+  else
+  {
+    tmpreg = (((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours) << 16) | \
+              ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes) << 8) | \
+              ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds)) | \
+              ((uint32_t)(RTC_AlarmStruct->RTC_AlarmTime.RTC_H12) << 16) | \
+              ((uint32_t)RTC_ByteToBcd2(RTC_AlarmStruct->RTC_AlarmDateWeekDay) << 24) | \
+              ((uint32_t)RTC_AlarmStruct->RTC_AlarmDateWeekDaySel) | \
+              ((uint32_t)RTC_AlarmStruct->RTC_AlarmMask)); 
+  } 
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Configure the Alarm register */
+  if (RTC_Alarm == RTC_Alarm_A)
+  {
+    RTC->ALRMAR = (uint32_t)tmpreg;
+  }
+  else
+  {
+    RTC->ALRMBR = (uint32_t)tmpreg;
+  }
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;   
+}
+
+/**
+  * @brief  Fills each RTC_AlarmStruct member with its default value
+  *         (Time = 00h:00mn:00sec / Date = 1st day of the month/Mask =
+  *         all fields are masked).
+  * @param  RTC_AlarmStruct: pointer to a @ref RTC_AlarmTypeDef structure which
+  *         will be initialized.
+  * @retval None
+  */
+void RTC_AlarmStructInit(RTC_AlarmTypeDef* RTC_AlarmStruct)
+{
+  /* Alarm Time Settings : Time = 00h:00mn:00sec */
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = RTC_H12_AM;
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = 0;
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = 0;
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = 0;
+
+  /* Alarm Date Settings : Date = 1st day of the month */
+  RTC_AlarmStruct->RTC_AlarmDateWeekDaySel = RTC_AlarmDateWeekDaySel_Date;
+  RTC_AlarmStruct->RTC_AlarmDateWeekDay = 1;
+
+  /* Alarm Masks Settings : Mask =  all fields are not masked */
+  RTC_AlarmStruct->RTC_AlarmMask = RTC_AlarmMask_None;
+}
+
+/**
+  * @brief  Get the RTC Alarm value and masks.
+  * @param  RTC_Format: specifies the format of the output parameters.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_Format_BIN: Binary data format 
+  *            @arg RTC_Format_BCD: BCD data format
+  * @param  RTC_Alarm: specifies the alarm to be read.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_Alarm_A: to select Alarm A
+  *            @arg RTC_Alarm_B: to select Alarm B  
+  * @param  RTC_AlarmStruct: pointer to a RTC_AlarmTypeDef structure that will 
+  *                          contains the output alarm configuration values.     
+  * @retval None
+  */
+void RTC_GetAlarm(uint32_t RTC_Format, uint32_t RTC_Alarm, RTC_AlarmTypeDef* RTC_AlarmStruct)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_FORMAT(RTC_Format));
+  assert_param(IS_RTC_ALARM(RTC_Alarm)); 
+
+  /* Get the RTC_ALRMxR register */
+  if (RTC_Alarm == RTC_Alarm_A)
+  {
+    tmpreg = (uint32_t)(RTC->ALRMAR);
+  }
+  else
+  {
+    tmpreg = (uint32_t)(RTC->ALRMBR);
+  }
+
+  /* Fill the structure with the read parameters */
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = (uint32_t)((tmpreg & (RTC_ALRMAR_HT | \
+                                                     RTC_ALRMAR_HU)) >> 16);
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = (uint32_t)((tmpreg & (RTC_ALRMAR_MNT | \
+                                                     RTC_ALRMAR_MNU)) >> 8);
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = (uint32_t)(tmpreg & (RTC_ALRMAR_ST | \
+                                                     RTC_ALRMAR_SU));
+  RTC_AlarmStruct->RTC_AlarmTime.RTC_H12 = (uint32_t)((tmpreg & RTC_ALRMAR_PM) >> 16);
+  RTC_AlarmStruct->RTC_AlarmDateWeekDay = (uint32_t)((tmpreg & (RTC_ALRMAR_DT | RTC_ALRMAR_DU)) >> 24);
+  RTC_AlarmStruct->RTC_AlarmDateWeekDaySel = (uint32_t)(tmpreg & RTC_ALRMAR_WDSEL);
+  RTC_AlarmStruct->RTC_AlarmMask = (uint32_t)(tmpreg & RTC_AlarmMask_All);
+
+  if (RTC_Format == RTC_Format_BIN)
+  {
+    RTC_AlarmStruct->RTC_AlarmTime.RTC_Hours = RTC_Bcd2ToByte(RTC_AlarmStruct-> \
+                                                        RTC_AlarmTime.RTC_Hours);
+    RTC_AlarmStruct->RTC_AlarmTime.RTC_Minutes = RTC_Bcd2ToByte(RTC_AlarmStruct-> \
+                                                        RTC_AlarmTime.RTC_Minutes);
+    RTC_AlarmStruct->RTC_AlarmTime.RTC_Seconds = RTC_Bcd2ToByte(RTC_AlarmStruct-> \
+                                                        RTC_AlarmTime.RTC_Seconds);
+    RTC_AlarmStruct->RTC_AlarmDateWeekDay = RTC_Bcd2ToByte(RTC_AlarmStruct->RTC_AlarmDateWeekDay);
+  }  
+}
+
+/**
+  * @brief  Enables or disables the specified RTC Alarm.
+  * @param  RTC_Alarm: specifies the alarm to be configured.
+  *          This parameter can be any combination of the following values:
+  *            @arg RTC_Alarm_A: to select Alarm A
+  *            @arg RTC_Alarm_B: to select Alarm B  
+  * @param  NewState: new state of the specified alarm.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC Alarm is enabled/disabled
+  *          - ERROR: RTC Alarm is not enabled/disabled  
+  */
+ErrorStatus RTC_AlarmCmd(uint32_t RTC_Alarm, FunctionalState NewState)
+{
+  __IO uint32_t alarmcounter = 0x00;
+  uint32_t alarmstatus = 0x00;
+  ErrorStatus status = ERROR;
+    
+  /* Check the parameters */
+  assert_param(IS_RTC_CMD_ALARM(RTC_Alarm));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Configure the Alarm state */
+  if (NewState != DISABLE)
+  {
+    RTC->CR |= (uint32_t)RTC_Alarm;
+
+    status = SUCCESS;    
+  }
+  else
+  { 
+    /* Disable the Alarm in RTC_CR register */
+    RTC->CR &= (uint32_t)~RTC_Alarm;
+   
+    /* Wait till RTC ALRxWF flag is set and if Time out is reached exit */
+    do
+    {
+      alarmstatus = RTC->ISR & (RTC_Alarm >> 8);
+      alarmcounter++;  
+    } while((alarmcounter != INITMODE_TIMEOUT) && (alarmstatus == 0x00));
+    
+    if ((RTC->ISR & (RTC_Alarm >> 8)) == RESET)
+    {
+      status = ERROR;
+    } 
+    else
+    {
+      status = SUCCESS;
+    }        
+  } 
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+  
+  return status;
+}
+
+/**
+  * @brief  Configure the RTC AlarmA/B Sub seconds value and mask.*
+  * @note   This function is performed only when the Alarm is disabled. 
+  * @param  RTC_Alarm: specifies the alarm to be configured.
+  *   This parameter can be one of the following values:
+  *     @arg RTC_Alarm_A: to select Alarm A
+  *     @arg RTC_Alarm_B: to select Alarm B
+  * @param  RTC_AlarmSubSecondValue: specifies the Sub seconds value.
+  *   This parameter can be a value from 0 to 0x00007FFF.
+  * @param  RTC_AlarmSubSecondMask:  specifies the Sub seconds Mask.
+  *   This parameter can be any combination of the following values:
+  *     @arg RTC_AlarmSubSecondMask_All    : All Alarm SS fields are masked.
+  *                                          There is no comparison on sub seconds for Alarm.
+  *     @arg RTC_AlarmSubSecondMask_SS14_1 : SS[14:1] are don't care in Alarm comparison.
+  *                                          Only SS[0] is compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_2 : SS[14:2] are don't care in Alarm comparison.
+  *                                          Only SS[1:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_3 : SS[14:3] are don't care in Alarm comparison.
+  *                                          Only SS[2:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_4 : SS[14:4] are don't care in Alarm comparison.
+  *                                          Only SS[3:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_5 : SS[14:5] are don't care in Alarm comparison.
+  *                                          Only SS[4:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_6 : SS[14:6] are don't care in Alarm comparison.
+  *                                          Only SS[5:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_7 : SS[14:7] are don't care in Alarm comparison.
+  *                                          Only SS[6:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_8 : SS[14:8] are don't care in Alarm comparison.
+  *                                          Only SS[7:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_9 : SS[14:9] are don't care in Alarm comparison.
+  *                                          Only SS[8:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_10: SS[14:10] are don't care in Alarm comparison.
+  *                                          Only SS[9:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_11: SS[14:11] are don't care in Alarm comparison.
+  *                                          Only SS[10:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_12: SS[14:12] are don't care in Alarm comparison.
+  *                                          Only SS[11:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14_13: SS[14:13] are don't care in Alarm comparison.
+  *                                          Only SS[12:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_SS14   : SS[14] is don't care in Alarm comparison.
+  *                                          Only SS[13:0] are compared
+  *     @arg RTC_AlarmSubSecondMask_None   : SS[14:0] are compared and must match
+  *                                          to activate alarm
+  * @retval None
+  */
+void RTC_AlarmSubSecondConfig(uint32_t RTC_Alarm, uint32_t RTC_AlarmSubSecondValue, uint32_t RTC_AlarmSubSecondMask)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_ALARM(RTC_Alarm));
+  assert_param(IS_RTC_ALARM_SUB_SECOND_VALUE(RTC_AlarmSubSecondValue));
+  assert_param(IS_RTC_ALARM_SUB_SECOND_MASK(RTC_AlarmSubSecondMask));
+  
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  /* Configure the Alarm A or Alarm B Sub Second registers */
+  tmpreg = (uint32_t) (uint32_t)(RTC_AlarmSubSecondValue) | (uint32_t)(RTC_AlarmSubSecondMask);
+  
+  if (RTC_Alarm == RTC_Alarm_A)
+  {
+    /* Configure the Alarm A Sub Second register */
+    RTC->ALRMASSR = tmpreg;
+  }
+  else
+  {
+    /* Configure the Alarm B Sub Second register */
+    RTC->ALRMBSSR = tmpreg;
+  }
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;
+
+}
+
+/**
+  * @brief  Gets the RTC Alarm Sub seconds value.
+  * @param  RTC_Alarm: specifies the alarm to be read.
+  *   This parameter can be one of the following values:
+  *     @arg RTC_Alarm_A: to select Alarm A
+  *     @arg RTC_Alarm_B: to select Alarm B
+  * @param  None
+  * @retval RTC Alarm Sub seconds value.
+  */
+uint32_t RTC_GetAlarmSubSecond(uint32_t RTC_Alarm)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Get the RTC_ALRMxR register */
+  if (RTC_Alarm == RTC_Alarm_A)
+  {
+    tmpreg = (uint32_t)((RTC->ALRMASSR) & RTC_ALRMASSR_SS);
+  }
+  else
+  {
+    tmpreg = (uint32_t)((RTC->ALRMBSSR) & RTC_ALRMBSSR_SS);
+  } 
+  
+  return (tmpreg);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group4 WakeUp Timer configuration functions
+ *  @brief   WakeUp Timer configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+                 ##### WakeUp Timer configuration functions #####
+ ===============================================================================  
+
+ [..] This section provide functions allowing to program and read the RTC WakeUp.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the RTC Wakeup clock source.
+  * @note   The WakeUp Clock source can only be changed when the RTC WakeUp
+  *         is disabled (Use the RTC_WakeUpCmd(DISABLE)).      
+  * @param  RTC_WakeUpClock: Wakeup Clock source.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_WakeUpClock_RTCCLK_Div16: RTC Wakeup Counter Clock = RTCCLK/16
+  *            @arg RTC_WakeUpClock_RTCCLK_Div8: RTC Wakeup Counter Clock = RTCCLK/8
+  *            @arg RTC_WakeUpClock_RTCCLK_Div4: RTC Wakeup Counter Clock = RTCCLK/4
+  *            @arg RTC_WakeUpClock_RTCCLK_Div2: RTC Wakeup Counter Clock = RTCCLK/2
+  *            @arg RTC_WakeUpClock_CK_SPRE_16bits: RTC Wakeup Counter Clock = CK_SPRE
+  *            @arg RTC_WakeUpClock_CK_SPRE_17bits: RTC Wakeup Counter Clock = CK_SPRE
+  * @retval None
+  */
+void RTC_WakeUpClockConfig(uint32_t RTC_WakeUpClock)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_WAKEUP_CLOCK(RTC_WakeUpClock));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Clear the Wakeup Timer clock source bits in CR register */
+  RTC->CR &= (uint32_t)~RTC_CR_WUCKSEL;
+
+  /* Configure the clock source */
+  RTC->CR |= (uint32_t)RTC_WakeUpClock;
+  
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+}
+
+/**
+  * @brief  Configures the RTC Wakeup counter.
+  * @note   The RTC WakeUp counter can only be written when the RTC WakeUp
+  *         is disabled (Use the RTC_WakeUpCmd(DISABLE)).        
+  * @param  RTC_WakeUpCounter: specifies the WakeUp counter.
+  *          This parameter can be a value from 0x0000 to 0xFFFF. 
+  * @retval None
+  */
+void RTC_SetWakeUpCounter(uint32_t RTC_WakeUpCounter)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_WAKEUP_COUNTER(RTC_WakeUpCounter));
+  
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  /* Configure the Wakeup Timer counter */
+  RTC->WUTR = (uint32_t)RTC_WakeUpCounter;
+  
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+}
+
+/**
+  * @brief  Returns the RTC WakeUp timer counter value.
+  * @param  None
+  * @retval The RTC WakeUp Counter value.
+  */
+uint32_t RTC_GetWakeUpCounter(void)
+{
+  /* Get the counter value */
+  return ((uint32_t)(RTC->WUTR & RTC_WUTR_WUT));
+}
+
+/**
+  * @brief  Enables or Disables the RTC WakeUp timer.
+  * @param  NewState: new state of the WakeUp timer.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+ErrorStatus RTC_WakeUpCmd(FunctionalState NewState)
+{
+  __IO uint32_t wutcounter = 0x00;
+  uint32_t wutwfstatus = 0x00;
+  ErrorStatus status = ERROR;
+  
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the Wakeup Timer */
+    RTC->CR |= (uint32_t)RTC_CR_WUTE;
+    status = SUCCESS;    
+  }
+  else
+  {
+    /* Disable the Wakeup Timer */
+    RTC->CR &= (uint32_t)~RTC_CR_WUTE;
+    /* Wait till RTC WUTWF flag is set and if Time out is reached exit */
+    do
+    {
+      wutwfstatus = RTC->ISR & RTC_ISR_WUTWF;
+      wutcounter++;  
+    } while((wutcounter != INITMODE_TIMEOUT) && (wutwfstatus == 0x00));
+    
+    if ((RTC->ISR & RTC_ISR_WUTWF) == RESET)
+    {
+      status = ERROR;
+    }
+    else
+    {
+      status = SUCCESS;
+    }    
+  }
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+  
+  return status;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group5 Daylight Saving configuration functions
+ *  @brief   Daylight Saving configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Daylight Saving configuration functions #####
+ ===============================================================================  
+
+ [..] This section provide functions allowing to configure the RTC DayLight Saving.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Adds or substract one hour from the current time.
+  * @param  RTC_DayLightSaveOperation: the value of hour adjustment. 
+  *          This parameter can be one of the following values:
+  *            @arg RTC_DayLightSaving_SUB1H: Substract one hour (winter time)
+  *            @arg RTC_DayLightSaving_ADD1H: Add one hour (summer time)
+  * @param  RTC_StoreOperation: Specifies the value to be written in the BCK bit 
+  *                            in CR register to store the operation.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_StoreOperation_Reset: BCK Bit Reset
+  *            @arg RTC_StoreOperation_Set: BCK Bit Set
+  * @retval None
+  */
+void RTC_DayLightSavingConfig(uint32_t RTC_DayLightSaving, uint32_t RTC_StoreOperation)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_DAYLIGHT_SAVING(RTC_DayLightSaving));
+  assert_param(IS_RTC_STORE_OPERATION(RTC_StoreOperation));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Clear the bits to be configured */
+  RTC->CR &= (uint32_t)~(RTC_CR_BCK);
+
+  /* Configure the RTC_CR register */
+  RTC->CR |= (uint32_t)(RTC_DayLightSaving | RTC_StoreOperation);
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+}
+
+/**
+  * @brief  Returns the RTC Day Light Saving stored operation.
+  * @param  None
+  * @retval RTC Day Light Saving stored operation.
+  *          - RTC_StoreOperation_Reset
+  *          - RTC_StoreOperation_Set       
+  */
+uint32_t RTC_GetStoreOperation(void)
+{
+  return (RTC->CR & RTC_CR_BCK);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group6 Output pin Configuration function
+ *  @brief   Output pin Configuration function 
+ *
+@verbatim   
+ ===============================================================================
+                 ##### Output pin Configuration function #####
+ ===============================================================================  
+
+ [..] This section provide functions allowing to configure the RTC Output source.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the RTC output source (AFO_ALARM).
+  * @param  RTC_Output: Specifies which signal will be routed to the RTC output. 
+  *          This parameter can be one of the following values:
+  *            @arg RTC_Output_Disable: No output selected
+  *            @arg RTC_Output_AlarmA: signal of AlarmA mapped to output
+  *            @arg RTC_Output_AlarmB: signal of AlarmB mapped to output
+  *            @arg RTC_Output_WakeUp: signal of WakeUp mapped to output
+  * @param  RTC_OutputPolarity: Specifies the polarity of the output signal. 
+  *          This parameter can be one of the following:
+  *            @arg RTC_OutputPolarity_High: The output pin is high when the 
+  *                                 ALRAF/ALRBF/WUTF is high (depending on OSEL)
+  *            @arg RTC_OutputPolarity_Low: The output pin is low when the 
+  *                                 ALRAF/ALRBF/WUTF is high (depending on OSEL)
+  * @retval None
+  */
+void RTC_OutputConfig(uint32_t RTC_Output, uint32_t RTC_OutputPolarity)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_OUTPUT(RTC_Output));
+  assert_param(IS_RTC_OUTPUT_POL(RTC_OutputPolarity));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Clear the bits to be configured */
+  RTC->CR &= (uint32_t)~(RTC_CR_OSEL | RTC_CR_POL);
+
+  /* Configure the output selection and polarity */
+  RTC->CR |= (uint32_t)(RTC_Output | RTC_OutputPolarity);
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group7 Digital Calibration configuration functions
+ *  @brief   Coarse Calibration configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Digital Calibration configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the Coarse calibration parameters.
+  * @param  RTC_CalibSign: specifies the sign of the coarse calibration value.
+  *          This parameter can be  one of the following values:
+  *            @arg RTC_CalibSign_Positive: The value sign is positive 
+  *            @arg RTC_CalibSign_Negative: The value sign is negative
+  * @param  Value: value of coarse calibration expressed in ppm (coded on 5 bits).
+  *    
+  * @note   This Calibration value should be between 0 and 63 when using negative
+  *         sign with a 2-ppm step.
+  *           
+  * @note   This Calibration value should be between 0 and 126 when using positive
+  *         sign with a 4-ppm step.
+  *           
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC Coarse calibration are initialized
+  *          - ERROR: RTC Coarse calibration are not initialized     
+  */
+ErrorStatus RTC_CoarseCalibConfig(uint32_t RTC_CalibSign, uint32_t Value)
+{
+  ErrorStatus status = ERROR;
+   
+  /* Check the parameters */
+  assert_param(IS_RTC_CALIB_SIGN(RTC_CalibSign));
+  assert_param(IS_RTC_CALIB_VALUE(Value)); 
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Set Initialization mode */
+  if (RTC_EnterInitMode() == ERROR)
+  {
+    status = ERROR;
+  } 
+  else
+  {
+    /* Set the coarse calibration value */
+    RTC->CALIBR = (uint32_t)(RTC_CalibSign | Value);
+    /* Exit Initialization mode */
+    RTC_ExitInitMode();
+    
+    status = SUCCESS;
+  } 
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+  
+  return status;
+}
+
+/**
+  * @brief  Enables or disables the Coarse calibration process.
+  * @param  NewState: new state of the Coarse calibration.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC Coarse calibration are enabled/disabled
+  *          - ERROR: RTC Coarse calibration are not enabled/disabled    
+  */
+ErrorStatus RTC_CoarseCalibCmd(FunctionalState NewState)
+{
+  ErrorStatus status = ERROR;
+  
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  /* Set Initialization mode */
+  if (RTC_EnterInitMode() == ERROR)
+  {
+    status =  ERROR;
+  }
+  else
+  {
+    if (NewState != DISABLE)
+    {
+      /* Enable the Coarse Calibration */
+      RTC->CR |= (uint32_t)RTC_CR_DCE;
+    }
+    else
+    { 
+      /* Disable the Coarse Calibration */
+      RTC->CR &= (uint32_t)~RTC_CR_DCE;
+    }
+    /* Exit Initialization mode */
+    RTC_ExitInitMode();
+    
+    status = SUCCESS;
+  } 
+  
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+  
+  return status;
+}
+
+/**
+  * @brief  Enables or disables the RTC clock to be output through the relative pin.
+  * @param  NewState: new state of the digital calibration Output.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RTC_CalibOutputCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the RTC clock output */
+    RTC->CR |= (uint32_t)RTC_CR_COE;
+  }
+  else
+  { 
+    /* Disable the RTC clock output */
+    RTC->CR &= (uint32_t)~RTC_CR_COE;
+  }
+  
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+}
+
+/**
+  * @brief  Configure the Calibration Pinout (RTC_CALIB) Selection (1Hz or 512Hz).
+  * @param  RTC_CalibOutput : Select the Calibration output Selection .
+  *   This parameter can be one of the following values:
+  *     @arg RTC_CalibOutput_512Hz: A signal has a regular waveform at 512Hz. 
+  *     @arg RTC_CalibOutput_1Hz  : A signal has a regular waveform at 1Hz.
+  * @retval None
+*/
+void RTC_CalibOutputConfig(uint32_t RTC_CalibOutput)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_CALIB_OUTPUT(RTC_CalibOutput));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  /*clear flags before configuration */
+  RTC->CR &= (uint32_t)~(RTC_CR_COSEL);
+
+  /* Configure the RTC_CR register */
+  RTC->CR |= (uint32_t)RTC_CalibOutput;
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;
+}
+
+/**
+  * @brief  Configures the Smooth Calibration Settings.
+  * @param  RTC_SmoothCalibPeriod : Select the Smooth Calibration Period.
+  *   This parameter can be can be one of the following values:
+  *     @arg RTC_SmoothCalibPeriod_32sec : The smooth calibration period is 32s.
+  *     @arg RTC_SmoothCalibPeriod_16sec : The smooth calibration period is 16s.
+  *     @arg RTC_SmoothCalibPeriod_8sec  : The smooth calibartion period is 8s.
+  * @param  RTC_SmoothCalibPlusPulses : Select to Set or reset the CALP bit.
+  *   This parameter can be one of the following values:
+  *     @arg RTC_SmoothCalibPlusPulses_Set  : Add one RTCCLK puls every 2**11 pulses.
+  *     @arg RTC_SmoothCalibPlusPulses_Reset: No RTCCLK pulses are added.
+  * @param  RTC_SmouthCalibMinusPulsesValue: Select the value of CALM[8:0] bits.
+  *   This parameter can be one any value from 0 to 0x000001FF.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC Calib registers are configured
+  *          - ERROR: RTC Calib registers are not configured
+*/
+ErrorStatus RTC_SmoothCalibConfig(uint32_t RTC_SmoothCalibPeriod,
+                                  uint32_t RTC_SmoothCalibPlusPulses,
+                                  uint32_t RTC_SmouthCalibMinusPulsesValue)
+{
+  ErrorStatus status = ERROR;
+  uint32_t recalpfcount = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_SMOOTH_CALIB_PERIOD(RTC_SmoothCalibPeriod));
+  assert_param(IS_RTC_SMOOTH_CALIB_PLUS(RTC_SmoothCalibPlusPulses));
+  assert_param(IS_RTC_SMOOTH_CALIB_MINUS(RTC_SmouthCalibMinusPulsesValue));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  /* check if a calibration is pending*/
+  if ((RTC->ISR & RTC_ISR_RECALPF) != RESET)
+  {
+    /* wait until the Calibration is completed*/
+    while (((RTC->ISR & RTC_ISR_RECALPF) != RESET) && (recalpfcount != RECALPF_TIMEOUT))
+    {
+      recalpfcount++;
+    }
+  }
+
+  /* check if the calibration pending is completed or if there is no calibration operation at all*/
+  if ((RTC->ISR & RTC_ISR_RECALPF) == RESET)
+  {
+    /* Configure the Smooth calibration settings */
+    RTC->CALR = (uint32_t)((uint32_t)RTC_SmoothCalibPeriod | (uint32_t)RTC_SmoothCalibPlusPulses | (uint32_t)RTC_SmouthCalibMinusPulsesValue);
+
+    status = SUCCESS;
+  }
+  else
+  {
+    status = ERROR;
+  }
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;
+  
+  return (ErrorStatus)(status);
+}
+
+/**
+  * @}
+  */
+
+
+/** @defgroup RTC_Group8 TimeStamp configuration functions
+ *  @brief   TimeStamp configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+                 ##### TimeStamp configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or Disables the RTC TimeStamp functionality with the 
+  *         specified time stamp pin stimulating edge.
+  * @param  RTC_TimeStampEdge: Specifies the pin edge on which the TimeStamp is 
+  *         activated.
+  *          This parameter can be one of the following:
+  *            @arg RTC_TimeStampEdge_Rising: the Time stamp event occurs on the rising 
+  *                                    edge of the related pin.
+  *            @arg RTC_TimeStampEdge_Falling: the Time stamp event occurs on the 
+  *                                     falling edge of the related pin.
+  * @param  NewState: new state of the TimeStamp.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RTC_TimeStampCmd(uint32_t RTC_TimeStampEdge, FunctionalState NewState)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_TIMESTAMP_EDGE(RTC_TimeStampEdge));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Get the RTC_CR register and clear the bits to be configured */
+  tmpreg = (uint32_t)(RTC->CR & (uint32_t)~(RTC_CR_TSEDGE | RTC_CR_TSE));
+
+  /* Get the new configuration */
+  if (NewState != DISABLE)
+  {
+    tmpreg |= (uint32_t)(RTC_TimeStampEdge | RTC_CR_TSE);
+  }
+  else
+  {
+    tmpreg |= (uint32_t)(RTC_TimeStampEdge);
+  }
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  /* Configure the Time Stamp TSEDGE and Enable bits */
+  RTC->CR = (uint32_t)tmpreg;
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+}
+
+/**
+  * @brief  Get the RTC TimeStamp value and masks.
+  * @param  RTC_Format: specifies the format of the output parameters.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_Format_BIN: Binary data format 
+  *            @arg RTC_Format_BCD: BCD data format
+  * @param RTC_StampTimeStruct: pointer to a RTC_TimeTypeDef structure that will 
+  *                             contains the TimeStamp time values. 
+  * @param RTC_StampDateStruct: pointer to a RTC_DateTypeDef structure that will 
+  *                             contains the TimeStamp date values.     
+  * @retval None
+  */
+void RTC_GetTimeStamp(uint32_t RTC_Format, RTC_TimeTypeDef* RTC_StampTimeStruct, 
+                                      RTC_DateTypeDef* RTC_StampDateStruct)
+{
+  uint32_t tmptime = 0, tmpdate = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_FORMAT(RTC_Format));
+
+  /* Get the TimeStamp time and date registers values */
+  tmptime = (uint32_t)(RTC->TSTR & RTC_TR_RESERVED_MASK);
+  tmpdate = (uint32_t)(RTC->TSDR & RTC_DR_RESERVED_MASK);
+
+  /* Fill the Time structure fields with the read parameters */
+  RTC_StampTimeStruct->RTC_Hours = (uint8_t)((tmptime & (RTC_TR_HT | RTC_TR_HU)) >> 16);
+  RTC_StampTimeStruct->RTC_Minutes = (uint8_t)((tmptime & (RTC_TR_MNT | RTC_TR_MNU)) >> 8);
+  RTC_StampTimeStruct->RTC_Seconds = (uint8_t)(tmptime & (RTC_TR_ST | RTC_TR_SU));
+  RTC_StampTimeStruct->RTC_H12 = (uint8_t)((tmptime & (RTC_TR_PM)) >> 16);  
+
+  /* Fill the Date structure fields with the read parameters */
+  RTC_StampDateStruct->RTC_Year = 0;
+  RTC_StampDateStruct->RTC_Month = (uint8_t)((tmpdate & (RTC_DR_MT | RTC_DR_MU)) >> 8);
+  RTC_StampDateStruct->RTC_Date = (uint8_t)(tmpdate & (RTC_DR_DT | RTC_DR_DU));
+  RTC_StampDateStruct->RTC_WeekDay = (uint8_t)((tmpdate & (RTC_DR_WDU)) >> 13);
+
+  /* Check the input parameters format */
+  if (RTC_Format == RTC_Format_BIN)
+  {
+    /* Convert the Time structure parameters to Binary format */
+    RTC_StampTimeStruct->RTC_Hours = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Hours);
+    RTC_StampTimeStruct->RTC_Minutes = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Minutes);
+    RTC_StampTimeStruct->RTC_Seconds = (uint8_t)RTC_Bcd2ToByte(RTC_StampTimeStruct->RTC_Seconds);
+
+    /* Convert the Date structure parameters to Binary format */
+    RTC_StampDateStruct->RTC_Month = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_Month);
+    RTC_StampDateStruct->RTC_Date = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_Date);
+    RTC_StampDateStruct->RTC_WeekDay = (uint8_t)RTC_Bcd2ToByte(RTC_StampDateStruct->RTC_WeekDay);
+  }
+}
+
+/**
+  * @brief  Get the RTC timestamp Sub seconds value.
+  * @param  None
+  * @retval RTC current timestamp Sub seconds value.
+  */
+uint32_t RTC_GetTimeStampSubSecond(void)
+{
+  /* Get timestamp sub seconds values from the correspondent registers */
+  return (uint32_t)(RTC->TSSSR);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group9 Tampers configuration functions
+ *  @brief   Tampers configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+                 ##### Tampers configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the select Tamper pin edge.
+  * @param  RTC_Tamper: Selected tamper pin.
+  *          This parameter can be RTC_Tamper_1.
+  * @param  RTC_TamperTrigger: Specifies the trigger on the tamper pin that 
+  *         stimulates tamper event. 
+  *   This parameter can be one of the following values:
+  *     @arg RTC_TamperTrigger_RisingEdge: Rising Edge of the tamper pin causes tamper event.
+  *     @arg RTC_TamperTrigger_FallingEdge: Falling Edge of the tamper pin causes tamper event.
+  *     @arg RTC_TamperTrigger_LowLevel: Low Level of the tamper pin causes tamper event.
+  *     @arg RTC_TamperTrigger_HighLevel: High Level of the tamper pin causes tamper event.
+  * @retval None
+  */
+void RTC_TamperTriggerConfig(uint32_t RTC_Tamper, uint32_t RTC_TamperTrigger)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_TAMPER(RTC_Tamper)); 
+  assert_param(IS_RTC_TAMPER_TRIGGER(RTC_TamperTrigger));
+ 
+  if (RTC_TamperTrigger == RTC_TamperTrigger_RisingEdge)
+  {  
+    /* Configure the RTC_TAFCR register */
+    RTC->TAFCR &= (uint32_t)((uint32_t)~(RTC_Tamper << 1));	
+  }
+  else
+  { 
+    /* Configure the RTC_TAFCR register */
+    RTC->TAFCR |= (uint32_t)(RTC_Tamper << 1);  
+  }  
+}
+
+/**
+  * @brief  Enables or Disables the Tamper detection.
+  * @param  RTC_Tamper: Selected tamper pin.
+  *          This parameter can be RTC_Tamper_1.
+  * @param  NewState: new state of the tamper pin.
+  *          This parameter can be: ENABLE or DISABLE.                   
+  * @retval None
+  */
+void RTC_TamperCmd(uint32_t RTC_Tamper, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_TAMPER(RTC_Tamper));  
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected Tamper pin */
+    RTC->TAFCR |= (uint32_t)RTC_Tamper;
+  }
+  else
+  {
+    /* Disable the selected Tamper pin */
+    RTC->TAFCR &= (uint32_t)~RTC_Tamper;    
+  }  
+}
+
+/**
+  * @brief  Configures the Tampers Filter.
+  * @param  RTC_TamperFilter: Specifies the tampers filter.
+  *   This parameter can be one of the following values:
+  *     @arg RTC_TamperFilter_Disable: Tamper filter is disabled.
+  *     @arg RTC_TamperFilter_2Sample: Tamper is activated after 2 consecutive 
+  *                                    samples at the active level 
+  *     @arg RTC_TamperFilter_4Sample: Tamper is activated after 4 consecutive 
+  *                                    samples at the active level
+  *     @arg RTC_TamperFilter_8Sample: Tamper is activated after 8 consecutive 
+  *                                    samples at the active level 
+  * @retval None
+  */
+void RTC_TamperFilterConfig(uint32_t RTC_TamperFilter)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_TAMPER_FILTER(RTC_TamperFilter));
+   
+  /* Clear TAMPFLT[1:0] bits in the RTC_TAFCR register */
+  RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPFLT);
+
+  /* Configure the RTC_TAFCR register */
+  RTC->TAFCR |= (uint32_t)RTC_TamperFilter;
+}
+
+/**
+  * @brief  Configures the Tampers Sampling Frequency.
+  * @param  RTC_TamperSamplingFreq: Specifies the tampers Sampling Frequency.
+  *   This parameter can be one of the following values:
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div32768: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 32768
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div16384: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 16384
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div8192: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 8192
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div4096: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 4096
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div2048: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 2048
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div1024: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 1024
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div512: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 512  
+  *     @arg RTC_TamperSamplingFreq_RTCCLK_Div256: Each of the tamper inputs are sampled
+  *                                           with a frequency =  RTCCLK / 256  
+  * @retval None
+  */
+void RTC_TamperSamplingFreqConfig(uint32_t RTC_TamperSamplingFreq)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_TAMPER_SAMPLING_FREQ(RTC_TamperSamplingFreq));
+ 
+  /* Clear TAMPFREQ[2:0] bits in the RTC_TAFCR register */
+  RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPFREQ);
+
+  /* Configure the RTC_TAFCR register */
+  RTC->TAFCR |= (uint32_t)RTC_TamperSamplingFreq;
+}
+
+/**
+  * @brief  Configures the Tampers Pins input Precharge Duration.
+  * @param  RTC_TamperPrechargeDuration: Specifies the Tampers Pins input
+  *         Precharge Duration.
+  *   This parameter can be one of the following values:
+  *     @arg RTC_TamperPrechargeDuration_1RTCCLK: Tamper pins are precharged before sampling during 1 RTCCLK cycle
+  *     @arg RTC_TamperPrechargeDuration_2RTCCLK: Tamper pins are precharged before sampling during 2 RTCCLK cycle
+  *     @arg RTC_TamperPrechargeDuration_4RTCCLK: Tamper pins are precharged before sampling during 4 RTCCLK cycle    
+  *     @arg RTC_TamperPrechargeDuration_8RTCCLK: Tamper pins are precharged before sampling during 8 RTCCLK cycle
+  * @retval None
+  */
+void RTC_TamperPinsPrechargeDuration(uint32_t RTC_TamperPrechargeDuration)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_TAMPER_PRECHARGE_DURATION(RTC_TamperPrechargeDuration));
+   
+  /* Clear TAMPPRCH[1:0] bits in the RTC_TAFCR register */
+  RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPPRCH);
+
+  /* Configure the RTC_TAFCR register */
+  RTC->TAFCR |= (uint32_t)RTC_TamperPrechargeDuration;
+}
+
+/**
+  * @brief  Enables or Disables the TimeStamp on Tamper Detection Event.
+  * @note   The timestamp is valid even the TSE bit in tamper control register 
+  *         is reset.   
+  * @param  NewState: new state of the timestamp on tamper event.
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RTC_TimeStampOnTamperDetectionCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+   
+  if (NewState != DISABLE)
+  {
+    /* Save timestamp on tamper detection event */
+    RTC->TAFCR |= (uint32_t)RTC_TAFCR_TAMPTS;
+  }
+  else
+  {
+    /* Tamper detection does not cause a timestamp to be saved */
+    RTC->TAFCR &= (uint32_t)~RTC_TAFCR_TAMPTS;    
+  }
+}
+
+/**
+  * @brief  Enables or Disables the Precharge of Tamper pin.
+  * @param  NewState: new state of tamper pull up.
+  *   This parameter can be: ENABLE or DISABLE.                   
+  * @retval None
+  */
+void RTC_TamperPullUpCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+ if (NewState != DISABLE)
+  {
+    /* Enable precharge of the selected Tamper pin */
+    RTC->TAFCR &= (uint32_t)~RTC_TAFCR_TAMPPUDIS; 
+  }
+  else
+  {
+    /* Disable precharge of the selected Tamper pin */
+    RTC->TAFCR |= (uint32_t)RTC_TAFCR_TAMPPUDIS;    
+  } 
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group10 Backup Data Registers configuration functions
+ *  @brief   Backup Data Registers configuration functions  
+ *
+@verbatim   
+ ===============================================================================
+             ##### Backup Data Registers configuration functions ##### 
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Writes a data in a specified RTC Backup data register.
+  * @param  RTC_BKP_DR: RTC Backup data Register number.
+  *          This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to 
+  *                          specify the register.
+  * @param  Data: Data to be written in the specified RTC Backup data register.                     
+  * @retval None
+  */
+void RTC_WriteBackupRegister(uint32_t RTC_BKP_DR, uint32_t Data)
+{
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RTC_BKP(RTC_BKP_DR));
+
+  tmp = RTC_BASE + 0x50;
+  tmp += (RTC_BKP_DR * 4);
+
+  /* Write the specified register */
+  *(__IO uint32_t *)tmp = (uint32_t)Data;
+}
+
+/**
+  * @brief  Reads data from the specified RTC Backup data Register.
+  * @param  RTC_BKP_DR: RTC Backup data Register number.
+  *          This parameter can be: RTC_BKP_DRx where x can be from 0 to 19 to 
+  *                          specify the register.                   
+  * @retval None
+  */
+uint32_t RTC_ReadBackupRegister(uint32_t RTC_BKP_DR)
+{
+  __IO uint32_t tmp = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RTC_BKP(RTC_BKP_DR));
+
+  tmp = RTC_BASE + 0x50;
+  tmp += (RTC_BKP_DR * 4);
+  
+  /* Read the specified register */
+  return (*(__IO uint32_t *)tmp);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group11 RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration functions
+ *  @brief   RTC Tamper and TimeStamp Pins Selection and Output Type Config 
+ *           configuration functions  
+ *
+@verbatim   
+ ==================================================================================================
+ ##### RTC Tamper and TimeStamp Pins Selection and Output Type Config configuration functions ##### 
+ ==================================================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Selects the RTC Tamper Pin.
+  * @param  RTC_TamperPin: specifies the RTC Tamper Pin.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_TamperPin_PC13: PC13 is selected as RTC Tamper Pin.
+  *            @arg RTC_TamperPin_PI8: PI8 is selected as RTC Tamper Pin.    
+  * @retval None
+  */
+void RTC_TamperPinSelection(uint32_t RTC_TamperPin)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_TAMPER_PIN(RTC_TamperPin));
+  
+  RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TAMPINSEL);
+  RTC->TAFCR |= (uint32_t)(RTC_TamperPin);  
+}
+
+/**
+  * @brief  Selects the RTC TimeStamp Pin.
+  * @param  RTC_TimeStampPin: specifies the RTC TimeStamp Pin.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_TimeStampPin_PC13: PC13 is selected as RTC TimeStamp Pin.
+  *            @arg RTC_TimeStampPin_PI8: PI8 is selected as RTC TimeStamp Pin.    
+  * @retval None
+  */
+void RTC_TimeStampPinSelection(uint32_t RTC_TimeStampPin)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_TIMESTAMP_PIN(RTC_TimeStampPin));
+  
+  RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_TSINSEL);
+  RTC->TAFCR |= (uint32_t)(RTC_TimeStampPin);  
+}
+
+/**
+  * @brief  Configures the RTC Output Pin mode. 
+  * @param  RTC_OutputType: specifies the RTC Output (PC13) pin mode.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_OutputType_OpenDrain: RTC Output (PC13) is configured in 
+  *                                    Open Drain mode.
+  *            @arg RTC_OutputType_PushPull:  RTC Output (PC13) is configured in 
+  *                                    Push Pull mode.    
+  * @retval None
+  */
+void RTC_OutputTypeConfig(uint32_t RTC_OutputType)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_OUTPUT_TYPE(RTC_OutputType));
+  
+  RTC->TAFCR &= (uint32_t)~(RTC_TAFCR_ALARMOUTTYPE);
+  RTC->TAFCR |= (uint32_t)(RTC_OutputType);  
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group12 Shift control synchronisation functions
+ *  @brief   Shift control synchronisation functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Shift control synchronisation functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the Synchronization Shift Control Settings.
+  * @note   When REFCKON is set, firmware must not write to Shift control register 
+  * @param  RTC_ShiftAdd1S : Select to add or not 1 second to the time Calendar.
+  *   This parameter can be one of the following values :
+  *     @arg RTC_ShiftAdd1S_Set  : Add one second to the clock calendar. 
+  *     @arg RTC_ShiftAdd1S_Reset: No effect.
+  * @param  RTC_ShiftSubFS: Select the number of Second Fractions to Substitute.
+  *         This parameter can be one any value from 0 to 0x7FFF.
+  * @retval An ErrorStatus enumeration value:
+  *          - SUCCESS: RTC Shift registers are configured
+  *          - ERROR: RTC Shift registers are not configured
+*/
+ErrorStatus RTC_SynchroShiftConfig(uint32_t RTC_ShiftAdd1S, uint32_t RTC_ShiftSubFS)
+{
+  ErrorStatus status = ERROR;
+  uint32_t shpfcount = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_SHIFT_ADD1S(RTC_ShiftAdd1S));
+  assert_param(IS_RTC_SHIFT_SUBFS(RTC_ShiftSubFS));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+  
+  /* Check if a Shift is pending*/
+  if ((RTC->ISR & RTC_ISR_SHPF) != RESET)
+  {
+    /* Wait until the shift is completed*/
+    while (((RTC->ISR & RTC_ISR_SHPF) != RESET) && (shpfcount != SHPF_TIMEOUT))
+    {
+      shpfcount++;
+    }
+  }
+
+  /* Check if the Shift pending is completed or if there is no Shift operation at all*/
+  if ((RTC->ISR & RTC_ISR_SHPF) == RESET)
+  {
+    /* check if the reference clock detection is disabled */
+    if((RTC->CR & RTC_CR_REFCKON) == RESET)
+    {
+      /* Configure the Shift settings */
+      RTC->SHIFTR = (uint32_t)(uint32_t)(RTC_ShiftSubFS) | (uint32_t)(RTC_ShiftAdd1S);
+    
+      if(RTC_WaitForSynchro() == ERROR)
+      {
+        status = ERROR;
+      }
+      else
+      {
+        status = SUCCESS;
+      }
+    }
+    else
+    {
+      status = ERROR;
+    }
+  }
+  else
+  {
+    status = ERROR;
+  }
+
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF;
+  
+  return (ErrorStatus)(status);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup RTC_Group13 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions  
+ *
+@verbatim   
+ ===============================================================================
+              ##### Interrupts and flags management functions #####
+ ===============================================================================  
+ [..] All RTC interrupts are connected to the EXTI controller.
+ 
+   (+) To enable the RTC Alarm interrupt, the following sequence is required:
+       (++) Configure and enable the EXTI Line 17 in interrupt mode and select 
+            the rising edge sensitivity using the EXTI_Init() function.
+       (++) Configure and enable the RTC_Alarm IRQ channel in the NVIC using the 
+            NVIC_Init() function.
+       (++) Configure the RTC to generate RTC alarms (Alarm A and/or Alarm B) using
+            the RTC_SetAlarm() and RTC_AlarmCmd() functions.
+
+   (+) To enable the RTC Wakeup interrupt, the following sequence is required:
+       (++) Configure and enable the EXTI Line 22 in interrupt mode and select the
+            rising edge sensitivity using the EXTI_Init() function.
+       (++) Configure and enable the RTC_WKUP IRQ channel in the NVIC using the 
+            NVIC_Init() function.
+       (++) Configure the RTC to generate the RTC wakeup timer event using the 
+            RTC_WakeUpClockConfig(), RTC_SetWakeUpCounter() and RTC_WakeUpCmd() 
+            functions.
+
+   (+) To enable the RTC Tamper interrupt, the following sequence is required:
+       (++) Configure and enable the EXTI Line 21 in interrupt mode and select 
+            the rising edge sensitivity using the EXTI_Init() function.
+       (++) Configure and enable the TAMP_STAMP IRQ channel in the NVIC using the
+            NVIC_Init() function.
+       (++) Configure the RTC to detect the RTC tamper event using the 
+            RTC_TamperTriggerConfig() and RTC_TamperCmd() functions.
+
+   (+) To enable the RTC TimeStamp interrupt, the following sequence is required:
+       (++) Configure and enable the EXTI Line 21 in interrupt mode and select the
+            rising edge sensitivity using the EXTI_Init() function.
+       (++) Configure and enable the TAMP_STAMP IRQ channel in the NVIC using the 
+            NVIC_Init() function.
+       (++) Configure the RTC to detect the RTC time stamp event using the 
+            RTC_TimeStampCmd() functions.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified RTC interrupts.
+  * @param  RTC_IT: specifies the RTC interrupt sources to be enabled or disabled. 
+  *          This parameter can be any combination of the following values:
+  *            @arg RTC_IT_TS:  Time Stamp interrupt mask
+  *            @arg RTC_IT_WUT:  WakeUp Timer interrupt mask
+  *            @arg RTC_IT_ALRB:  Alarm B interrupt mask
+  *            @arg RTC_IT_ALRA:  Alarm A interrupt mask
+  *            @arg RTC_IT_TAMP: Tamper event interrupt mask
+  * @param  NewState: new state of the specified RTC interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void RTC_ITConfig(uint32_t RTC_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_CONFIG_IT(RTC_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* Disable the write protection for RTC registers */
+  RTC->WPR = 0xCA;
+  RTC->WPR = 0x53;
+
+  if (NewState != DISABLE)
+  {
+    /* Configure the Interrupts in the RTC_CR register */
+    RTC->CR |= (uint32_t)(RTC_IT & ~RTC_TAFCR_TAMPIE);
+    /* Configure the Tamper Interrupt in the RTC_TAFCR */
+    RTC->TAFCR |= (uint32_t)(RTC_IT & RTC_TAFCR_TAMPIE);
+  }
+  else
+  {
+    /* Configure the Interrupts in the RTC_CR register */
+    RTC->CR &= (uint32_t)~(RTC_IT & (uint32_t)~RTC_TAFCR_TAMPIE);
+    /* Configure the Tamper Interrupt in the RTC_TAFCR */
+    RTC->TAFCR &= (uint32_t)~(RTC_IT & RTC_TAFCR_TAMPIE);
+  }
+  /* Enable the write protection for RTC registers */
+  RTC->WPR = 0xFF; 
+}
+
+/**
+  * @brief  Checks whether the specified RTC flag is set or not.
+  * @param  RTC_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_FLAG_RECALPF: RECALPF event flag.
+  *            @arg RTC_FLAG_TAMP1F: Tamper 1 event flag
+  *            @arg RTC_FLAG_TSOVF: Time Stamp OverFlow flag
+  *            @arg RTC_FLAG_TSF: Time Stamp event flag
+  *            @arg RTC_FLAG_WUTF: WakeUp Timer flag
+  *            @arg RTC_FLAG_ALRBF: Alarm B flag
+  *            @arg RTC_FLAG_ALRAF: Alarm A flag
+  *            @arg RTC_FLAG_INITF: Initialization mode flag
+  *            @arg RTC_FLAG_RSF: Registers Synchronized flag
+  *            @arg RTC_FLAG_INITS: Registers Configured flag
+  *            @arg RTC_FLAG_SHPF: Shift operation pending flag.
+  *            @arg RTC_FLAG_WUTWF: WakeUp Timer Write flag
+  *            @arg RTC_FLAG_ALRBWF: Alarm B Write flag
+  *            @arg RTC_FLAG_ALRAWF: Alarm A write flag
+  * @retval The new state of RTC_FLAG (SET or RESET).
+  */
+FlagStatus RTC_GetFlagStatus(uint32_t RTC_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_RTC_GET_FLAG(RTC_FLAG));
+  
+  /* Get all the flags */
+  tmpreg = (uint32_t)(RTC->ISR & RTC_FLAGS_MASK);
+  
+  /* Return the status of the flag */
+  if ((tmpreg & RTC_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the RTC's pending flags.
+  * @param  RTC_FLAG: specifies the RTC flag to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg RTC_FLAG_TAMP1F: Tamper 1 event flag
+  *            @arg RTC_FLAG_TSOVF: Time Stamp Overflow flag 
+  *            @arg RTC_FLAG_TSF: Time Stamp event flag
+  *            @arg RTC_FLAG_WUTF: WakeUp Timer flag
+  *            @arg RTC_FLAG_ALRBF: Alarm B flag
+  *            @arg RTC_FLAG_ALRAF: Alarm A flag
+  *            @arg RTC_FLAG_RSF: Registers Synchronized flag
+  * @retval None
+  */
+void RTC_ClearFlag(uint32_t RTC_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG));
+
+  /* Clear the Flags in the RTC_ISR register */
+  RTC->ISR = (uint32_t)((uint32_t)(~((RTC_FLAG | RTC_ISR_INIT)& 0x0000FFFF) | (uint32_t)(RTC->ISR & RTC_ISR_INIT)));  
+}
+
+/**
+  * @brief  Checks whether the specified RTC interrupt has occurred or not.
+  * @param  RTC_IT: specifies the RTC interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg RTC_IT_TS: Time Stamp interrupt 
+  *            @arg RTC_IT_WUT: WakeUp Timer interrupt 
+  *            @arg RTC_IT_ALRB: Alarm B interrupt 
+  *            @arg RTC_IT_ALRA: Alarm A interrupt 
+  *            @arg RTC_IT_TAMP1: Tamper 1 event interrupt 
+  * @retval The new state of RTC_IT (SET or RESET).
+  */
+ITStatus RTC_GetITStatus(uint32_t RTC_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t tmpreg = 0, enablestatus = 0;
+ 
+  /* Check the parameters */
+  assert_param(IS_RTC_GET_IT(RTC_IT));
+  
+  /* Get the TAMPER Interrupt enable bit and pending bit */
+  tmpreg = (uint32_t)(RTC->TAFCR & (RTC_TAFCR_TAMPIE));
+ 
+  /* Get the Interrupt enable Status */
+  enablestatus = (uint32_t)((RTC->CR & RTC_IT) | (tmpreg & (RTC_IT >> 15)));
+  
+  /* Get the Interrupt pending bit */
+  tmpreg = (uint32_t)((RTC->ISR & (uint32_t)(RTC_IT >> 4)));
+  
+  /* Get the status of the Interrupt */
+  if ((enablestatus != (uint32_t)RESET) && ((tmpreg & 0x0000FFFF) != (uint32_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the RTC's interrupt pending bits.
+  * @param  RTC_IT: specifies the RTC interrupt pending bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg RTC_IT_TS: Time Stamp interrupt 
+  *            @arg RTC_IT_WUT: WakeUp Timer interrupt 
+  *            @arg RTC_IT_ALRB: Alarm B interrupt 
+  *            @arg RTC_IT_ALRA: Alarm A interrupt 
+  *            @arg RTC_IT_TAMP1: Tamper 1 event interrupt 
+  * @retval None
+  */
+void RTC_ClearITPendingBit(uint32_t RTC_IT)
+{
+  uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_RTC_CLEAR_IT(RTC_IT));
+
+  /* Get the RTC_ISR Interrupt pending bits mask */
+  tmpreg = (uint32_t)(RTC_IT >> 4);
+
+  /* Clear the interrupt pending bits in the RTC_ISR register */
+  RTC->ISR = (uint32_t)((uint32_t)(~((tmpreg | RTC_ISR_INIT)& 0x0000FFFF) | (uint32_t)(RTC->ISR & RTC_ISR_INIT))); 
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @brief  Converts a 2 digit decimal to BCD format.
+  * @param  Value: Byte to be converted.
+  * @retval Converted byte
+  */
+static uint8_t RTC_ByteToBcd2(uint8_t Value)
+{
+  uint8_t bcdhigh = 0;
+  
+  while (Value >= 10)
+  {
+    bcdhigh++;
+    Value -= 10;
+  }
+  
+  return  ((uint8_t)(bcdhigh << 4) | Value);
+}
+
+/**
+  * @brief  Convert from 2 digit BCD to Binary.
+  * @param  Value: BCD value to be converted.
+  * @retval Converted word
+  */
+static uint8_t RTC_Bcd2ToByte(uint8_t Value)
+{
+  uint8_t tmp = 0;
+  tmp = ((uint8_t)(Value & (uint8_t)0xF0) >> (uint8_t)0x4) * 10;
+  return (tmp + (Value & (uint8_t)0x0F));
+}
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sai.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sai.c
new file mode 100644
index 0000000000000000000000000000000000000000..8a5eaeae329f31b0d3887717b6691074b6524fce
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sai.c
@@ -0,0 +1,1079 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_sai.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013  
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Serial Audio Interface (SAI):
+  *           + Initialization and Configuration
+  *           + Data transfers functions
+  *           + DMA transfers management
+  *           + Interrupts and flags management 
+  *           
+  @verbatim
+ ===============================================================================
+                     ##### How to use this driver #####
+ ===============================================================================
+    [..] 
+    
+       (#) Enable peripheral clock using the following functions 
+           RCC_APB2PeriphClockCmd(RCC_APB2Periph_SAI1, ENABLE) for SAI1
+  
+       (#) For each SAI Block A/B enable SCK, SD, FS and MCLK GPIO clocks 
+           using RCC_AHB1PeriphClockCmd() function.
+  
+       (#) Peripherals alternate function: 
+           (++) Connect the pin to the desired peripherals' Alternate 
+                Function (AF) using GPIO_PinAFConfig() function.
+           (++) Configure the desired pin in alternate function by:
+                GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
+           (++) Select the type, pull-up/pull-down and output speed via 
+                GPIO_PuPd, GPIO_OType and GPIO_Speed members
+           (++) Call GPIO_Init() function
+           -@@- If an external clock source is used then the I2S CKIN pin should be 
+               also configured in Alternate function Push-pull pull-up mode.
+                
+      (#) The SAI clock can be generated from different clock source :
+          PLL I2S, PLL SAI or external clock source.
+          (++) The PLL I2S is configured using the following functions RCC_PLLI2SConfig(), 
+               RCC_PLLI2SCmd(ENABLE), RCC_GetFlagStatus(RCC_FLAG_PLLI2SRDY) and 
+               RCC_SAIPLLI2SClkDivConfig() or;
+              
+          (++) The PLL SAI is configured using the following functions RCC_PLLSAIConfig(), 
+               RCC_PLLSAICmd(ENABLE), RCC_GetFlagStatus(RCC_FLAG_PLLSAIRDY) and 
+               RCC_SAIPLLSAIClkDivConfig()or;          
+              
+          (++) External clock source is configured using the function 
+               RCC_I2SCLKConfig(RCC_I2S2CLKSource_Ext) and after setting correctly the 
+               define constant I2S_EXTERNAL_CLOCK_VAL in the stm32f4xx_conf.h file.      
+                
+      (#) Each SAI Block A or B has its own clock generator to make these two blocks 
+          completely independent. The Clock generator is configured using RCC_SAIBlockACLKConfig() and 
+          RCC_SAIBlockBCLKConfig() functions.
+                  
+      (#) Each SAI Block A or B can be configured separetely : 
+          (++) Program the Master clock divider, Audio mode, Protocol, Data Length, Clock Strobing Edge, 
+               Synchronous mode, Output drive and FIFO Thresold using SAI_Init() function.   
+               In case of master mode, program the Master clock divider (MCKDIV) using 
+               the following formula :  
+               (+++) MCLK_x = SAI_CK_x / (MCKDIV * 2) with MCLK_x = 256 * FS
+               (+++) FS = SAI_CK_x / (MCKDIV * 2) * 256
+               (+++) MCKDIV = SAI_CK_x / FS * 512
+         (++) Program the Frame Length, Frame active Length, FS Definition, FS Polarity, 
+              FS Offset using SAI_FrameInit() function.    
+         (++) Program the Slot First Bit Offset, Slot Size, Slot Number, Slot Active 
+              using SAI_SlotInit() function. 
+                   
+      (#) Enable the NVIC and the corresponding interrupt using the function 
+          SAI_ITConfig() if you need to use interrupt mode. 
+  
+      (#) When using the DMA mode 
+          (++) Configure the DMA using DMA_Init() function
+          (++) Active the needed channel Request using SAI_DMACmd() function
+   
+      (#) Enable the SAI using the SAI_Cmd() function.
+   
+      (#) Enable the DMA using the DMA_Cmd() function when using DMA mode. 
+  
+      (#) The SAI has some specific functions which can be useful depending 
+          on the audio protocol selected.  
+          (++) Enable Mute mode when the audio block is a transmitter using SAI_MuteModeCmd()
+               function and configure the value transmitted during mute using SAI_MuteValueConfig().  
+          (++) Detect the Mute mode when audio block is a receiver using SAI_MuteFrameCounterConfig().             
+          (++) Enable the MONO mode without any data preprocessing in memory when the number
+               of slot is equal to 2 using SAI_MonoModeConfig() function.
+          (++) Enable data companding algorithm (U law and A law) using SAI_CompandingModeConfig().
+          (++) Choose the behavior of the SD line in output when an inactive slot is sent 
+               on the data line using SAI_TRIStateConfig() function.   
+  [..]               
+   (@)    In master TX mode: enabling the audio block immediately generates the bit clock 
+          for the external slaves even if there is no data in the FIFO, However FS signal 
+          generation is conditioned by the presence of data in the FIFO.
+                 
+   (@)    In master RX mode: enabling the audio block immediately generates the bit clock 
+          and FS signal for the external slaves. 
+                
+   (@)    It is mandatory to respect the following conditions in order to avoid bad SAI behavior: 
+            (+@)  First bit Offset <= (SLOT size - Data size)
+            (+@)  Data size <= SLOT size
+            (+@)  Number of SLOT x SLOT size = Frame length
+            (+@)  The number of slots should be even when bit FSDEF in the SAI_xFRCR is set.    
+  
+    @endverbatim  
+                                    
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_sai.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup SAI 
+  * @brief SAI driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* *SAI registers Masks */
+#define CR1_CLEAR_MASK            ((uint32_t)0xFF07C010)
+#define FRCR_CLEAR_MASK           ((uint32_t)0xFFF88000)
+#define SLOTR_CLEAR_MASK          ((uint32_t)0x0000F020)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup SAI_Private_Functions
+  * @{
+  */
+
+/** @defgroup SAI_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+            ##### Initialization and Configuration functions #####
+ ===============================================================================  
+  [..]
+  This section provides a set of functions allowing to initialize the SAI Audio 
+  Block Mode, Audio Protocol, Data size, Synchronization between audio block, 
+  Master clock Divider, Fifo threshold, Frame configuration, slot configuration,
+  Tristate mode, Companding mode and Mute mode.  
+  [..] 
+  The SAI_Init(), SAI_FrameInit() and SAI_SlotInit() functions follows the SAI Block
+  configuration procedures for Master mode and Slave mode (details for these procedures 
+  are available in reference manual(RM0090).
+  
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitialize the SAIx peripheral registers to their default reset values.
+  * @param  SAIx: To select the SAIx peripheral, where x can be the different instances 
+  *                     
+  * @retval None
+  */
+void SAI_DeInit(SAI_TypeDef* SAIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_PERIPH(SAIx));
+
+  /* Enable SAI1 reset state */
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_SAI1, ENABLE);
+  /* Release SAI1 from reset state */
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_SAI1, DISABLE);  
+}
+
+/**
+  * @brief  Initializes the SAI Block x peripheral according to the specified 
+  *         parameters in the SAI_InitStruct.
+  *         
+  * @note   SAI clock is generated from a specific output of the PLLSAI or a specific  
+  *         output of the PLLI2S or from an alternate function bypassing the PLL I2S.
+  *        
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  SAI_InitStruct: pointer to a SAI_InitTypeDef structure that
+  *         contains the configuration information for the specified SAI Block peripheral.             
+  * @retval None
+  */
+void SAI_Init(SAI_Block_TypeDef* SAI_Block_x, SAI_InitTypeDef* SAI_InitStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  
+  /* Check the SAI Block parameters */
+  assert_param(IS_SAI_BLOCK_MODE(SAI_InitStruct->SAI_AudioMode));
+  assert_param(IS_SAI_BLOCK_PROTOCOL(SAI_InitStruct->SAI_Protocol));
+  assert_param(IS_SAI_BLOCK_DATASIZE(SAI_InitStruct->SAI_DataSize));
+  assert_param(IS_SAI_BLOCK_FIRST_BIT(SAI_InitStruct->SAI_FirstBit));
+  assert_param(IS_SAI_BLOCK_CLOCK_STROBING(SAI_InitStruct->SAI_ClockStrobing));
+  assert_param(IS_SAI_BLOCK_SYNCHRO(SAI_InitStruct->SAI_Synchro));
+  assert_param(IS_SAI_BLOCK_OUTPUT_DRIVE(SAI_InitStruct->SAI_OUTDRIV));
+  assert_param(IS_SAI_BLOCK_NODIVIDER(SAI_InitStruct->SAI_NoDivider));
+  assert_param(IS_SAI_BLOCK_MASTER_DIVIDER(SAI_InitStruct->SAI_MasterDivider));
+  assert_param(IS_SAI_BLOCK_FIFO_THRESHOLD(SAI_InitStruct->SAI_FIFOThreshold));
+
+  /* SAI Block_x CR1 Configuration */
+  /* Get the SAI Block_x CR1 value */
+  tmpreg = SAI_Block_x->CR1;
+  /* Clear MODE, PRTCFG, DS, LSBFIRST, CKSTR, SYNCEN, OUTDRIV, NODIV, and MCKDIV bits */
+  tmpreg &= CR1_CLEAR_MASK;
+  /* Configure SAI_Block_x: Audio mode, Protocol, Data Size, first transmitted bit, Clock strobing 
+     edge, Synchronization mode, Output drive, Master Divider and FIFO level */  
+  /* Set MODE bits according to SAI_AudioMode value       */
+  /* Set PRTCFG bits according to SAI_Protocol value      */
+  /* Set DS bits according to SAI_DataSize value          */
+  /* Set LSBFIRST bit according to SAI_FirstBit value     */
+  /* Set CKSTR bit according to SAI_ClockStrobing value   */
+  /* Set SYNCEN bit according to SAI_Synchro value        */
+  /* Set OUTDRIV bit according to SAI_OUTDRIV value       */
+  /* Set NODIV bit according to SAI_NoDivider value       */
+  /* Set MCKDIV bits according to SAI_MasterDivider value */
+  tmpreg |= (uint32_t)(SAI_InitStruct->SAI_AudioMode     | SAI_InitStruct->SAI_Protocol  |
+                       SAI_InitStruct->SAI_DataSize      | SAI_InitStruct->SAI_FirstBit  |  
+                       SAI_InitStruct->SAI_ClockStrobing | SAI_InitStruct->SAI_Synchro   |  
+                       SAI_InitStruct->SAI_OUTDRIV       | SAI_InitStruct->SAI_NoDivider | 
+                       (uint32_t)((SAI_InitStruct->SAI_MasterDivider) << 20));
+  /* Write to SAI_Block_x CR1 */
+  SAI_Block_x->CR1 = tmpreg;
+  
+  /* SAI Block_x CR2 Configuration */
+  /* Get the SAIBlock_x CR2 value */
+  tmpreg = SAI_Block_x->CR2;
+  /* Clear FTH bits */
+  tmpreg &= ~(SAI_xCR2_FTH);
+  /* Configure the FIFO Level */
+  /* Set FTH bits according to SAI_FIFOThreshold value */ 
+  tmpreg |= (uint32_t)(SAI_InitStruct->SAI_FIFOThreshold);
+  /* Write to SAI_Block_x CR2 */
+  SAI_Block_x->CR2 = tmpreg;
+}
+
+/**
+  * @brief  Initializes the SAI Block Audio frame according to the specified 
+  *         parameters in the SAI_FrameInitStruct.
+  *         
+  * @note   this function has no meaning if the AC'97 or SPDIF audio protocol 
+  *         are selected. 
+  *               
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  SAI_FrameInitStruct: pointer to an SAI_FrameInitTypeDef structure that
+  *         contains the configuration of audio frame for a specified SAI Block                       
+  * @retval None
+  */
+void SAI_FrameInit(SAI_Block_TypeDef* SAI_Block_x, SAI_FrameInitTypeDef* SAI_FrameInitStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  
+  /* Check the SAI Block frame parameters */
+  assert_param(IS_SAI_BLOCK_FRAME_LENGTH(SAI_FrameInitStruct->SAI_FrameLength));
+  assert_param(IS_SAI_BLOCK_ACTIVE_FRAME(SAI_FrameInitStruct->SAI_ActiveFrameLength));
+  assert_param(IS_SAI_BLOCK_FS_DEFINITION(SAI_FrameInitStruct->SAI_FSDefinition));
+  assert_param(IS_SAI_BLOCK_FS_POLARITY(SAI_FrameInitStruct->SAI_FSPolarity));
+  assert_param(IS_SAI_BLOCK_FS_OFFSET(SAI_FrameInitStruct->SAI_FSOffset));
+
+  /* SAI Block_x FRCR Configuration */
+  /* Get the SAI Block_x FRCR value */
+  tmpreg = SAI_Block_x->FRCR;
+  /* Clear FRL, FSALL, FSDEF, FSPOL, FSOFF bits */
+  tmpreg &= FRCR_CLEAR_MASK;
+  /* Configure SAI_Block_x Frame: Frame Length, Active Frame Length, Frame Synchronization
+     Definition, Frame Synchronization Polarity and Frame Synchronization Polarity */
+  /* Set FRL bits according to SAI_FrameLength value         */
+  /* Set FSALL bits according to SAI_ActiveFrameLength value */
+  /* Set FSDEF bit according to SAI_FSDefinition value       */
+  /* Set FSPOL bit according to SAI_FSPolarity value         */
+  /* Set FSOFF bit according to SAI_FSOffset value           */
+  tmpreg |= (uint32_t)((uint32_t)(SAI_FrameInitStruct->SAI_FrameLength - 1)  | 
+                       SAI_FrameInitStruct->SAI_FSOffset     | 
+                       SAI_FrameInitStruct->SAI_FSDefinition |    
+                       SAI_FrameInitStruct->SAI_FSPolarity   |                        
+                       (uint32_t)((SAI_FrameInitStruct->SAI_ActiveFrameLength - 1) << 8));
+                       
+  /* Write to SAI_Block_x FRCR */
+  SAI_Block_x->FRCR = tmpreg;
+}
+
+/**
+  * @brief  Initializes the SAI Block audio Slot according to the specified 
+  *         parameters in the SAI_SlotInitStruct.
+  *         
+  * @note   this function has no meaning if the AC'97 or SPDIF audio protocol 
+  *         are selected.
+  *               
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  SAI_SlotInitStruct: pointer to an SAI_SlotInitTypeDef structure that
+  *         contains the configuration of audio slot for a specified SAI Block                      
+  * @retval None
+  */
+void SAI_SlotInit(SAI_Block_TypeDef* SAI_Block_x, SAI_SlotInitTypeDef* SAI_SlotInitStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  
+  /* Check the SAI Block Slot parameters */
+  assert_param(IS_SAI_BLOCK_FIRSTBIT_OFFSET(SAI_SlotInitStruct->SAI_FirstBitOffset));
+  assert_param(IS_SAI_BLOCK_SLOT_SIZE(SAI_SlotInitStruct->SAI_SlotSize));
+  assert_param(IS_SAI_BLOCK_SLOT_NUMBER(SAI_SlotInitStruct->SAI_SlotNumber));
+  assert_param(IS_SAI_SLOT_ACTIVE(SAI_SlotInitStruct->SAI_SlotActive));
+
+  /* SAI Block_x SLOTR Configuration */
+  /* Get the SAI Block_x SLOTR value */
+  tmpreg = SAI_Block_x->SLOTR;
+  /* Clear FBOFF, SLOTSZ, NBSLOT, SLOTEN bits */
+  tmpreg &= SLOTR_CLEAR_MASK;
+  /* Configure SAI_Block_x Slot: First bit offset, Slot size, Number of Slot in  
+     audio frame and slots activated in audio frame */
+  /* Set FBOFF bits according to SAI_FirstBitOffset value  */
+  /* Set SLOTSZ bits according to SAI_SlotSize value       */
+  /* Set NBSLOT bits according to SAI_SlotNumber value     */
+  /* Set SLOTEN bits according to SAI_SlotActive value     */
+  tmpreg |= (uint32_t)(SAI_SlotInitStruct->SAI_FirstBitOffset | 
+                       SAI_SlotInitStruct->SAI_SlotSize       | 
+                       SAI_SlotInitStruct->SAI_SlotActive     |    
+                       (uint32_t)((SAI_SlotInitStruct->SAI_SlotNumber - 1) <<  8));
+                       
+  /* Write to SAI_Block_x SLOTR */
+  SAI_Block_x->SLOTR = tmpreg;
+}
+
+/**
+  * @brief  Fills each SAI_InitStruct member with its default value.
+  * @param  SAI_InitStruct: pointer to a SAI_InitTypeDef structure which will 
+  *         be initialized.  
+  * @retval None
+  */
+void SAI_StructInit(SAI_InitTypeDef* SAI_InitStruct)
+{
+  /* Reset SAI init structure parameters values */
+  /* Initialize the SAI_AudioMode member */
+  SAI_InitStruct->SAI_AudioMode = SAI_Mode_MasterTx;
+  /* Initialize the SAI_Protocol member */
+  SAI_InitStruct->SAI_Protocol = SAI_Free_Protocol;
+  /* Initialize the SAI_DataSize member */
+  SAI_InitStruct->SAI_DataSize = SAI_DataSize_8b;
+  /* Initialize the SAI_FirstBit member */
+  SAI_InitStruct->SAI_FirstBit = SAI_FirstBit_MSB;
+  /* Initialize the SAI_ClockStrobing member */
+  SAI_InitStruct->SAI_ClockStrobing = SAI_ClockStrobing_FallingEdge;
+  /* Initialize the SAI_Synchro member */
+  SAI_InitStruct->SAI_Synchro = SAI_Asynchronous;
+  /* Initialize the SAI_OUTDRIV member */
+  SAI_InitStruct->SAI_OUTDRIV = SAI_OutputDrive_Disabled;
+  /* Initialize the SAI_NoDivider member */
+  SAI_InitStruct->SAI_NoDivider = SAI_MasterDivider_Enabled;
+  /* Initialize the SAI_MasterDivider member */
+  SAI_InitStruct->SAI_MasterDivider = 0;
+  /* Initialize the SAI_FIFOThreshold member */
+  SAI_InitStruct->SAI_FIFOThreshold = SAI_Threshold_FIFOEmpty;
+}
+
+/**
+  * @brief  Fills each SAI_FrameInitStruct member with its default value.
+  * @param  SAI_FrameInitStruct: pointer to a SAI_FrameInitTypeDef structure 
+  *         which will be initialized.                     
+  * @retval None
+  */
+void SAI_FrameStructInit(SAI_FrameInitTypeDef* SAI_FrameInitStruct)
+{
+  /* Reset SAI Frame init structure parameters values */
+  /* Initialize the SAI_FrameLength member */
+  SAI_FrameInitStruct->SAI_FrameLength = 8;
+  /* Initialize the SAI_ActiveFrameLength member */
+  SAI_FrameInitStruct->SAI_ActiveFrameLength = 1;
+  /* Initialize the SAI_FSDefinition member */
+  SAI_FrameInitStruct->SAI_FSDefinition = SAI_FS_StartFrame;
+  /* Initialize the SAI_FSPolarity member */
+  SAI_FrameInitStruct->SAI_FSPolarity = SAI_FS_ActiveLow;
+  /* Initialize the SAI_FSOffset member */
+  SAI_FrameInitStruct->SAI_FSOffset = SAI_FS_FirstBit;
+}
+
+/**
+  * @brief  Fills each SAI_SlotInitStruct member with its default value.
+  * @param  SAI_SlotInitStruct: pointer to a SAI_SlotInitTypeDef structure 
+  *         which will be initialized.                     
+  * @retval None
+  */
+void SAI_SlotStructInit(SAI_SlotInitTypeDef* SAI_SlotInitStruct)
+{
+  /* Reset SAI Slot init structure parameters values */
+  /* Initialize the SAI_FirstBitOffset member */
+  SAI_SlotInitStruct->SAI_FirstBitOffset = 0;
+  /* Initialize the SAI_SlotSize member */
+  SAI_SlotInitStruct->SAI_SlotSize = SAI_SlotSize_DataSize;
+  /* Initialize the SAI_SlotNumber member */
+  SAI_SlotInitStruct->SAI_SlotNumber = 1;
+  /* Initialize the SAI_SlotActive member */
+  SAI_SlotInitStruct->SAI_SlotActive = SAI_Slot_NotActive;
+
+}
+
+/**
+  * @brief  Enables or disables the specified SAI Block peripheral.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  NewState: new state of the SAI_Block_x peripheral. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SAI_Cmd(SAI_Block_TypeDef* SAI_Block_x, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SAI peripheral */
+    SAI_Block_x->CR1 |= SAI_xCR1_SAIEN;
+  }
+  else
+  {
+    /* Disable the selected SAI peripheral */
+    SAI_Block_x->CR1 &= ~(SAI_xCR1_SAIEN);
+  }
+}
+
+/**
+  * @brief  Configures the mono mode for the selected SAI block.
+  * 
+  * @note  This function has a meaning only when the number of slot is equal to 2. 
+  *      
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  SAI_MonoMode: specifies the SAI block mono mode.
+  *          This parameter can be one of the following values:
+  *            @arg SAI_MonoMode : Set mono audio mode
+  *            @arg SAI_StreoMode : Set streo audio mode                       
+  * @retval None
+  */
+void SAI_MonoModeConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_Mono_StreoMode)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_MONO_STREO_MODE(SAI_MonoMode));
+  /* Clear MONO bit */
+  SAI_Block_x->CR1 &= ~(SAI_xCR1_MONO);
+  /* Set new Mono Mode value */
+  SAI_Block_x->CR1 |= SAI_MonoMode;
+}
+
+/**
+  * @brief  Configures the TRIState managment on data line for the selected SAI block.
+  * 
+  * @note  This function has a meaning only when the SAI block is configured in transmitter 
+  *      
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  SAI_TRIState: specifies the SAI block TRIState management.
+  *          This parameter can be one of the following values:
+  *            @arg SAI_Output_NotReleased : SD output line is still drived by the SAI.
+  *            @arg SAI_Output_Released : SD output line is released (HI-Z)                       
+  * @retval None
+  */
+void SAI_TRIStateConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_TRIState)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_TRISTATE_MANAGEMENT(SAI_TRIState));
+  /* Clear MONO bit */
+  SAI_Block_x->CR1 &= ~(SAI_xCR1_MONO);
+  /* Set new Mono Mode value */
+  SAI_Block_x->CR1 |= SAI_MonoMode;  
+  
+}
+
+/**
+  * @brief  Configures the companding mode for the selected SAI block.
+  * 
+  * @note  The data expansion or data compression are determined by the state of
+  *        SAI block selected (transmitter or receiver). 
+
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.              
+  * @param  SAI_CompandingMode: specifies the SAI block companding mode.
+  *          This parameter can be one of the following values:
+  *            @arg SAI_NoCompanding : no companding algorithm set
+  *            @arg SAI_ULaw_1CPL_Companding : Set U law (algorithm 1's complement representation)
+  *            @arg SAI_ALaw_1CPL_Companding : Set A law (algorithm 1's complement repesentation)  
+  *            @arg SAI_ULaw_2CPL_Companding : Set U law (algorithm 2's complement representation)
+  *            @arg SAI_ALaw_2CPL_Companding : Set A law (algorithm 2's complement repesentation)  
+  * @retval None
+  */
+void SAI_CompandingModeConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_CompandingMode)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_COMPANDING_MODE(SAI_CompandingMode));
+  /* Clear Companding Mode bits */
+  SAI_Block_x->CR2 &= ~(SAI_xCR2_COMP);
+  /* Set new Companding Mode value */
+  SAI_Block_x->CR2 |= SAI_CompandingMode;
+}
+
+/**
+  * @brief  Enables or disables the Mute mode for the selected SAI block.
+  *    
+  * @note   This function has a meaning only when the audio block is transmitter
+  * @note   Mute mode is applied for an entire frame for all the valid slot
+  *         It becomes active at the end of an audio frame when set somewhere in a frame. 
+  *         Mute mode exit occurs at the end of the frame in which the bit MUTE has been set.
+  *
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  NewState: new state of the SAIx block. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SAI_MuteModeCmd(SAI_Block_TypeDef* SAI_Block_x, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SAI block mute mode */
+    SAI_Block_x->CR2 |= SAI_xCR2_MUTE;
+  }
+  else
+  {
+    /* Disable the selected SAI SS output */
+    SAI_Block_x->CR2 &= ~(SAI_xCR2_MUTE);
+  }
+}
+
+/**
+  * @brief  Configure the mute value for the selected SAI block.
+  *    
+  * @note   This function has a meaning only when the audio block is transmitter
+  * @note   the configuration last value sent during mute mode has only a meaning 
+  *          when the number of slot is lower or equal to 2 and if the MUTE bit is set.
+  *           
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  SAI_MuteValue: specifies the SAI block mute value.
+  *          This parameter can be one of the following values:
+  *            @arg SAI_ZeroValue : bit value 0 is sent during Mute Mode
+  *            @arg SAI_LastSentValue : Last value is sent during Mute Mode  
+  * @retval None
+  */
+void SAI_MuteValueConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_MuteValue)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_MUTE_VALUE(SAI_MuteValue));
+  
+  /* Clear Mute value bits */
+  SAI_Block_x->CR2 &= ~(SAI_xCR2_MUTEVAL);
+  /* Set new Mute value */
+  SAI_Block_x->CR2 |= SAI_MuteValue;
+}
+
+/**
+  * @brief  Enables or disables the Mute mode for the selected SAI block. 
+  *
+  * @note   This function has a meaning only when the audio block is Receiver
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  SAI_MuteCounter: specifies the SAI block mute value.
+  *         This parameter can be a number between 0 and 63.  
+ 
+  * @retval None
+  */
+void SAI_MuteFrameCounterConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_MuteCounter)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_MUTE_COUNTER(SAI_MuteCounter));
+  
+  /* Clear Mute value bits */
+  SAI_Block_x->CR2 &= ~(SAI_xCR2_MUTECNT);
+  /* Set new Mute value */
+  SAI_Block_x->CR2 |= (SAI_MuteCounter << 7);
+}
+
+/**
+  * @brief  Reinitialize the FIFO pointer
+  *   
+  * @note   The FIFO pointers can be reinitialized at anytime The data present 
+  *         into the FIFO, if it is not empty, will be lost. 
+  * 
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  * @param  NewState: new state of the selected SAI TI communication mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SAI_FlushFIFO(SAI_Block_TypeDef* SAI_Block_x)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+
+  /* FIFO flush */
+  SAI_Block_x->CR2 |= SAI_xCR2_FFLUSH;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Group2 Data transfers functions
+ *  @brief   Data transfers functions
+ *
+@verbatim   
+ ===============================================================================
+                       ##### Data transfers functions #####
+ ===============================================================================  
+  [..]
+  This section provides a set of functions allowing to manage the SAI data transfers.
+  [..]
+  In reception, data are received and then stored into an internal FIFO while 
+  In transmission, data are first stored into an internal FIFO before being 
+  transmitted.
+  [..]
+  The read access of the SAI_xDR register can be done using the SAI_ReceiveData()
+  function and returns the Rx buffered value. Whereas a write access to the SAI_DR 
+  can be done using SAI_SendData() function and stores the written data into 
+  Tx buffer.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Returns the most recent received data by the SAI block x peripheral. 
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral. 
+  *         
+  * @retval The value of the received data.
+  */
+uint32_t SAI_ReceiveData(SAI_Block_TypeDef* SAI_Block_x)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  
+  /* Return the data in the DR register */
+  return SAI_Block_x->DR;
+}
+
+/**
+  * @brief  Transmits a Data through the SAI block x peripheral.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  *        
+  * @param  Data: Data to be transmitted.
+  * @retval None
+  */
+void SAI_SendData(SAI_Block_TypeDef* SAI_Block_x, uint32_t Data)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  
+  /* Write in the DR register the data to be sent */
+  SAI_Block_x->DR = Data;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Group3 DMA transfers management functions
+ *  @brief   DMA transfers management functions
+  *
+@verbatim   
+ ===============================================================================
+                  ##### DMA transfers management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the SAI Block x DMA interface.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral. 
+  * @param  NewState: new state of the selected SAI block DMA transfer request.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SAI_DMACmd(SAI_Block_TypeDef* SAI_Block_x, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SAI block mute mode */
+    SAI_Block_x->CR1 |= SAI_xCR1_DMAEN;
+  }
+  else
+  {
+    /* Disable the selected SAI SS output */
+    SAI_Block_x->CR1 &= ~(SAI_xCR1_DMAEN);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SAI_Group4 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+  *
+@verbatim   
+ ===============================================================================
+            ##### Interrupts and flags management functions #####
+ ===============================================================================  
+  [..]
+  This section provides a set of functions allowing to configure the SAI Interrupts 
+  sources and check or clear the flags or pending bits status.
+  The user should identify which mode will be used in his application to manage 
+  the communication: Polling mode, Interrupt mode or DMA mode. 
+    
+  *** Polling Mode ***
+  ====================
+  [..]
+  In Polling Mode, the SAI communication can be managed by 7 flags:
+     (#) SAI_FLAG_FREQ : to indicate if there is a FIFO Request to write or to read.
+     (#) SAI_FLAG_MUTEDET : to indicate if a MUTE frame detected
+     (#) SAI_FLAG_OVRUDR : to indicate if an Overrun or Underrun error occur
+     (#) SAI_FLAG_AFSDET : to indicate if there is the detection of a audio frame 
+                          synchronisation (FS) earlier than expected
+     (#) SAI_FLAG_LFSDET : to indicate if there is the detection of a audio frame 
+                          synchronisation (FS) later than expected              
+     (#) SAI_FLAG_CNRDY : to indicate if  the codec is not ready to communicate during 
+                         the reception of the TAG 0 (slot0) of the AC97 audio frame 
+     (#) SAI_FLAG_WCKCFG: to indicate if wrong clock configuration in master mode 
+                         error occurs.
+  [..]
+  In this Mode it is advised to use the following functions:
+     (+) FlagStatus SAI_GetFlagStatus(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_FLAG);
+     (+) void SAI_ClearFlag(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_FLAG);
+
+  *** Interrupt Mode ***
+  ======================
+  [..]
+  In Interrupt Mode, the SAI communication can be managed by 7 interrupt sources
+  and 7 pending bits: 
+  (+) Pending Bits:
+     (##) SAI_IT_FREQ : to indicate if there is a FIFO Request to write or to read.
+     (##) SAI_IT_MUTEDET : to indicate if a MUTE frame detected.
+     (##) SAI_IT_OVRUDR : to indicate if an Overrun or Underrun error occur.
+     (##) SAI_IT_AFSDET : to indicate if there is the detection of a audio frame 
+                          synchronisation (FS) earlier than expected.
+     (##) SAI_IT_LFSDET : to indicate if there is the detection of a audio frame 
+                          synchronisation (FS) later than expected.              
+     (##) SAI_IT_CNRDY : to indicate if  the codec is not ready to communicate during 
+                         the reception of the TAG 0 (slot0) of the AC97 audio frame. 
+     (##) SAI_IT_WCKCFG: to indicate if wrong clock configuration in master mode 
+                         error occurs.
+
+  (+) Interrupt Source:
+     (##) SAI_IT_FREQ : specifies the interrupt source for FIFO Request.
+     (##) SAI_IT_MUTEDET : specifies the interrupt source for MUTE frame detected.
+     (##) SAI_IT_OVRUDR : specifies the interrupt source for overrun or underrun error.
+     (##) SAI_IT_AFSDET : specifies the interrupt source for anticipated frame synchronization
+                          detection interrupt.
+     (##) SAI_IT_LFSDET : specifies the interrupt source for late frame synchronization
+                          detection interrupt.             
+     (##) SAI_IT_CNRDY : specifies the interrupt source for codec not ready interrupt
+     (##) SAI_IT_WCKCFG: specifies the interrupt source for wrong clock configuration
+                         interrupt.
+  [..]                     
+  In this Mode it is advised to use the following functions:
+     (+) void SAI_ITConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT, FunctionalState NewState);
+     (+) ITStatus SAI_GetITStatus(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT);
+     (+) void SAI_ClearITPendingBit(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT);
+
+  *** DMA Mode ***
+  ================
+  [..]
+  In DMA Mode, each SAI audio block has an independent DMA interface in order to 
+  read or to write into the SAI_xDR register (to hit the internal FIFO). 
+  There is one DMA channel by audio block following basic DMA request/acknowledge 
+  protocol.
+  [..]
+  In this Mode it is advised to use the following function:
+    (+) void SAI_DMACmd(SAI_Block_TypeDef* SAI_Block_x, FunctionalState NewState);
+  [..]
+  This section provides also functions allowing to
+   (+) Check the SAI Block enable status
+   (+)Check the FIFO status 
+   
+  *** SAI Block Enable status ***
+  ===============================
+  [..]
+  After disabling a SAI Block, it is recommended to check (or wait until) the SAI Block 
+  is effectively disabled. If a Block is disabled while an audio frame transfer is ongoing
+  the current frame will be transferred and the block will be effectively disabled only at 
+  the end of audio frame. 
+  To monitor this state it is possible to use the following function:
+    (+) FunctionalState SAI_GetCmdStatus(SAI_Block_TypeDef* SAI_Block_x); 
+ 
+  *** SAI Block FIFO status ***
+  =============================
+  [..]
+  It is possible to monitor the FIFO status when a transfer is ongoing using the following 
+  function:
+    (+) uint32_t SAI_GetFIFOStatus(SAI_Block_TypeDef* SAI_Block_x);
+    
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified SAI Block interrupts.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral. 
+  * @param  SAI_IT: specifies the SAI interrupt source to be enabled or disabled. 
+  *          This parameter can be one of the following values:
+  *            @arg SAI_IT_FREQ: FIFO Request interrupt mask
+  *            @arg SAI_IT_MUTEDET: MUTE detection interrupt mask
+  *            @arg SAI_IT_OVRUDR: overrun/underrun interrupt mask
+  *            @arg SAI_IT_AFSDET: anticipated frame synchronization detection 
+  *                                interrupt mask  
+  *            @arg SAI_IT_LFSDET: late frame synchronization detection interrupt 
+  *                                mask
+  *            @arg SAI_IT_CNRDY: codec not ready interrupt mask
+  *            @arg SAI_IT_WCKCFG: wrong clock configuration interrupt mask      
+  * @param  NewState: new state of the specified SAI interrupt.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SAI_ITConfig(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT, FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_SAI_BLOCK_CONFIG_IT(SAI_IT));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SAI Block interrupt */
+    SAI_Block_x->IMR |= SAI_IT;
+  }
+  else
+  {
+    /* Disable the selected SAI Block interrupt */
+    SAI_Block_x->IMR &= ~(SAI_IT);
+  }
+}
+
+/**
+  * @brief  Checks whether the specified SAI block x flag is set or not.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral. 
+  * @param  SAI_FLAG: specifies the SAI block flag to check. 
+  *          This parameter can be one of the following values:
+  *            @arg SAI_FLAG_FREQ: FIFO Request flag.  
+  *            @arg SAI_FLAG_MUTEDET: MUTE detection flag.  
+  *            @arg SAI_FLAG_OVRUDR: overrun/underrun flag.
+  *            @arg SAI_FLAG_WCKCFG: wrong clock configuration flag.            
+  *            @arg SAI_FLAG_CNRDY: codec not ready flag. 
+  *            @arg SAI_FLAG_AFSDET: anticipated frame synchronization detection flag.
+  *            @arg SAI_FLAG_LFSDET: late frame synchronization detection flag.
+  * @retval The new state of SAI_FLAG (SET or RESET).
+  */
+FlagStatus SAI_GetFlagStatus(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_GET_FLAG(SAI_FLAG));
+  
+  /* Check the status of the specified SAI flag */
+  if ((SAI_Block_x->SR & SAI_FLAG) != (uint32_t)RESET)
+  {
+    /* SAI_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SAI_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the SAI_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the specified SAI Block x flag.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral. 
+  * @param  SAI_FLAG: specifies the SAI block flag to check. 
+  *          This parameter can be one of the following values: 
+  *            @arg SAI_FLAG_MUTEDET: MUTE detection flag.  
+  *            @arg SAI_FLAG_OVRUDR: overrun/underrun flag.
+  *            @arg SAI_FLAG_WCKCFG: wrong clock configuration flag.            
+  *            @arg SAI_FLAG_CNRDY: codec not ready flag. 
+  *            @arg SAI_FLAG_AFSDET: anticipated frame synchronization detection flag.
+  *            @arg SAI_FLAG_LFSDET: late frame synchronization detection flag. 
+  *  
+  * @note    FREQ (FIFO Request) flag is cleared : 
+  *          - When the audio block is transmitter and the FIFO is full or the FIFO   
+  *            has one data (one buffer mode) depending the bit FTH in the
+  *            SAI_xCR2 register.
+  *          - When the audio block is receiver and the FIFO is not empty           
+  *  
+  * @retval None
+  */
+void SAI_ClearFlag(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_CLEAR_FLAG(SAI_FLAG));
+    
+  /* Clear the selected SAI Block flag */
+  SAI_Block_x->CLRFR |= SAI_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified SAI Block x interrupt has occurred or not.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral. 
+  * @param  SAI_IT: specifies the SAI interrupt source to be enabled or disabled. 
+  *          This parameter can be one of the following values:
+  *            @arg SAI_IT_FREQ: FIFO Request interrupt 
+  *            @arg SAI_IT_MUTEDET: MUTE detection interrupt 
+  *            @arg SAI_IT_OVRUDR: overrun/underrun interrupt 
+  *            @arg SAI_IT_AFSDET: anticipated frame synchronization detection interrupt                                    
+  *            @arg SAI_IT_LFSDET: late frame synchronization detection interrupt                                
+  *            @arg SAI_IT_CNRDY: codec not ready interrupt 
+  *            @arg SAI_IT_WCKCFG: wrong clock configuration interrupt 
+  *                
+  * @retval The new state of SAI_IT (SET or RESET).
+  */
+ITStatus SAI_GetITStatus(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint32_t  enablestatus = 0;
+
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_CONFIG_IT(SAI_IT));
+  
+  /* Get the SAI_IT enable bit status */
+  enablestatus = (SAI_Block_x->IMR & SAI_IT) ;
+
+  /* Check the status of the specified SAI interrupt */
+  if (((SAI_Block_x->SR & SAI_IT) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET))
+  {
+    /* SAI_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SAI_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the SAI_IT status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the SAI Block x interrupt pending bit.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral. 
+  * @param  SAI_IT: specifies the SAI Block interrupt pending bit to clear. 
+  *          This parameter can be one of the following values:  
+  *            @arg SAI_IT_MUTEDET: MUTE detection interrupt.  
+  *            @arg SAI_IT_OVRUDR: overrun/underrun interrupt.
+  *            @arg SAI_IT_WCKCFG: wrong clock configuration interrupt.            
+  *            @arg SAI_IT_CNRDY: codec not ready interrupt. 
+  *            @arg SAI_IT_AFSDET: anticipated frame synchronization detection interrupt.
+  *            @arg SAI_IT_LFSDET: late frame synchronization detection interrupt. 
+  *  
+  * @note    FREQ (FIFO Request) flag is cleared : 
+  *          - When the audio block is transmitter and the FIFO is full or the FIFO   
+  *            has one data (one buffer mode) depending the bit FTH in the
+  *            SAI_xCR2 register.
+  *          - When the audio block is receiver and the FIFO is not empty  
+  *            
+  * @retval None
+  */
+void SAI_ClearITPendingBit(SAI_Block_TypeDef* SAI_Block_x, uint32_t SAI_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  assert_param(IS_SAI_BLOCK_CONFIG_IT(SAI_IT));
+
+  /* Clear the selected SAI Block x interrupt pending bit */
+  SAI_Block_x->CLRFR |= SAI_IT; 
+}
+
+/**
+  * @brief  Returns the status of EN bit for the specified SAI Block x.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  *   
+  * @note    After disabling a SAI Block, it is recommended to check (or wait until) 
+  *          the SAI Block is effectively disabled. If a Block is disabled while
+  *          an audio frame transfer is ongoing, the current frame will be 
+  *          transferred and the block will be effectively disabled only at 
+  *          the end of audio frame.  
+  *      
+  * @retval Current state of the DMAy Streamx (ENABLE or DISABLE).
+  */
+FunctionalState SAI_GetCmdStatus(SAI_Block_TypeDef* SAI_Block_x)
+{
+  FunctionalState state = DISABLE;
+
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  if ((SAI_Block_x->CR1 & (uint32_t)SAI_xCR1_SAIEN) != 0)
+  {
+    /* The selected SAI Block x EN bit is set (audio frame transfer is ongoing) */
+    state = ENABLE;
+  }
+  else
+  {
+    /* The selected SAI Block x EN bit is cleared (SAI Block is disabled and 
+        all transfers are complete) */
+    state = DISABLE;
+  }
+  return state;
+}
+
+/**
+  * @brief  Returns the current SAI Block x FIFO filled level.
+  * @param  SAI_Block_x: where x can be A or B to select the SAI Block peripheral.
+  *   
+  * @retval The FIFO filling state.
+  *           - SAI_FIFOStatus_Empty: when FIFO is empty  
+  *           - SAI_FIFOStatus_Less1QuarterFull: when FIFO is less than 1 quarter-full 
+  *                                               and not empty.
+  *           - SAI_FIFOStatus_1QuarterFull: if more than 1 quarter-full.
+  *           - SAI_FIFOStatus_HalfFull: if more than 1 half-full.
+  *           - SAI_FIFOStatus_3QuartersFull: if more than 3 quarters-full.
+  *           - SAI_FIFOStatus_Full: when FIFO is full
+  */
+uint32_t SAI_GetFIFOStatus(SAI_Block_TypeDef* SAI_Block_x)
+{
+  uint32_t tmpreg = 0;
+ 
+  /* Check the parameters */
+  assert_param(IS_SAI_BLOCK_PERIPH(SAI_Block_x));
+  
+  /* Get the FIFO level bits */
+  tmpreg = (uint32_t)((SAI_Block_x->SR & SAI_xSR_FLVL));
+  
+  return tmpreg;
+}
+
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c
new file mode 100644
index 0000000000000000000000000000000000000000..aead846a1d2b8a92132b131f343ef3c2b19f6af7
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_sdio.c
@@ -0,0 +1,1011 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_sdio.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Secure digital input/output interface (SDIO) 
+  *          peripheral:
+  *           + Initialization and Configuration
+  *           + Command path state machine (CPSM) management
+  *           + Data path state machine (DPSM) management
+  *           + SDIO IO Cards mode management
+  *           + CE-ATA mode management
+  *           + DMA transfers management
+  *           + Interrupts and flags management
+  *
+@verbatim
+
+ ===================================================================
+                 ##### How to use this driver #####
+ ===================================================================
+ [..]
+   (#) The SDIO clock (SDIOCLK = 48 MHz) is coming from a specific output of PLL 
+       (PLL48CLK). Before to start working with SDIO peripheral make sure that the
+       PLL is well configured.
+       The SDIO peripheral uses two clock signals:
+       (++) SDIO adapter clock (SDIOCLK = 48 MHz)
+       (++) APB2 bus clock (PCLK2)
+       
+       -@@- PCLK2 and SDIO_CK clock frequencies must respect the following condition:
+           Frequency(PCLK2) >= (3 / 8 x Frequency(SDIO_CK))
+  
+   (#) Enable peripheral clock using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SDIO, ENABLE).
+  
+   (#) According to the SDIO mode, enable the GPIO clocks using 
+       RCC_AHB1PeriphClockCmd() function. 
+       The I/O can be one of the following configurations:
+       (++) 1-bit data length: SDIO_CMD, SDIO_CK and D0.
+       (++) 4-bit data length: SDIO_CMD, SDIO_CK and D[3:0].
+       (++) 8-bit data length: SDIO_CMD, SDIO_CK and D[7:0].      
+  
+   (#) Peripheral alternate function: 
+       (++) Connect the pin to the desired peripherals' Alternate Function (AF) 
+           using GPIO_PinAFConfig() function
+       (++) Configure the desired pin in alternate function by: 
+           GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
+       (++) Select the type, pull-up/pull-down and output speed via GPIO_PuPd, 
+           GPIO_OType and GPIO_Speed members
+       (++) Call GPIO_Init() function
+  
+   (#) Program the Clock Edge, Clock Bypass, Clock Power Save, Bus Wide, 
+       hardware, flow control and the Clock Divider using the SDIO_Init()
+       function.
+  
+   (#) Enable the Power ON State using the SDIO_SetPowerState(SDIO_PowerState_ON) 
+       function.
+                
+   (#) Enable the clock using the SDIO_ClockCmd() function.
+  
+   (#) Enable the NVIC and the corresponding interrupt using the function 
+       SDIO_ITConfig() if you need to use interrupt mode. 
+  
+   (#) When using the DMA mode 
+       (++) Configure the DMA using DMA_Init() function
+       (++) Active the needed channel Request using SDIO_DMACmd() function
+  
+   (#) Enable the DMA using the DMA_Cmd() function, when using DMA mode. 
+  
+   (#) To control the CPSM (Command Path State Machine) and send 
+       commands to the card use the SDIO_SendCommand(), 
+       SDIO_GetCommandResponse() and SDIO_GetResponse() functions. First, user has
+       to fill the command structure (pointer to SDIO_CmdInitTypeDef) according 
+       to the selected command to be sent.
+       The parameters that should be filled are:
+       (++) Command Argument
+       (++) Command Index
+       (++) Command Response type
+       (++) Command Wait
+       (++) CPSM Status (Enable or Disable).
+  
+       -@@- To check if the command is well received, read the SDIO_CMDRESP
+           register using the SDIO_GetCommandResponse().
+           The SDIO responses registers (SDIO_RESP1 to SDIO_RESP2), use the
+           SDIO_GetResponse() function.
+  
+   (#) To control the DPSM (Data Path State Machine) and send/receive 
+       data to/from the card use the SDIO_DataConfig(), SDIO_GetDataCounter(), 
+       SDIO_ReadData(), SDIO_WriteData() and SDIO_GetFIFOCount() functions.
+  
+ *** Read Operations ***
+ =======================
+ [..]
+   (#) First, user has to fill the data structure (pointer to
+       SDIO_DataInitTypeDef) according to the selected data type to be received.
+       The parameters that should be filled are:
+       (++) Data TimeOut
+       (++) Data Length
+       (++) Data Block size
+       (++) Data Transfer direction: should be from card (To SDIO)
+       (++) Data Transfer mode
+       (++) DPSM Status (Enable or Disable)
+                                     
+   (#) Configure the SDIO resources to receive the data from the card
+       according to selected transfer mode (Refer to Step 8, 9 and 10).
+  
+   (#)  Send the selected Read command (refer to step 11).
+                    
+   (#) Use the SDIO flags/interrupts to check the transfer status.
+  
+ *** Write Operations ***
+ ========================
+ [..]
+   (#) First, user has to fill the data structure (pointer to
+       SDIO_DataInitTypeDef) according to the selected data type to be received.
+       The parameters that should be filled are:
+       (++) Data TimeOut
+       (++) Data Length
+       (++) Data Block size
+       (++) Data Transfer direction:  should be to card (To CARD)
+       (++) Data Transfer mode
+       (++) DPSM Status (Enable or Disable)
+  
+   (#) Configure the SDIO resources to send the data to the card according to 
+       selected transfer mode (Refer to Step 8, 9 and 10).
+                     
+   (#) Send the selected Write command (refer to step 11).
+                    
+   (#) Use the SDIO flags/interrupts to check the transfer status.
+  
+  
+@endverbatim
+  *
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_sdio.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup SDIO 
+  * @brief SDIO driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* ------------ SDIO registers bit address in the alias region ----------- */
+#define SDIO_OFFSET                (SDIO_BASE - PERIPH_BASE)
+
+/* --- CLKCR Register ---*/
+/* Alias word address of CLKEN bit */
+#define CLKCR_OFFSET              (SDIO_OFFSET + 0x04)
+#define CLKEN_BitNumber           0x08
+#define CLKCR_CLKEN_BB            (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4))
+
+/* --- CMD Register ---*/
+/* Alias word address of SDIOSUSPEND bit */
+#define CMD_OFFSET                (SDIO_OFFSET + 0x0C)
+#define SDIOSUSPEND_BitNumber     0x0B
+#define CMD_SDIOSUSPEND_BB        (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4))
+
+/* Alias word address of ENCMDCOMPL bit */
+#define ENCMDCOMPL_BitNumber      0x0C
+#define CMD_ENCMDCOMPL_BB         (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4))
+
+/* Alias word address of NIEN bit */
+#define NIEN_BitNumber            0x0D
+#define CMD_NIEN_BB               (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4))
+
+/* Alias word address of ATACMD bit */
+#define ATACMD_BitNumber          0x0E
+#define CMD_ATACMD_BB             (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4))
+
+/* --- DCTRL Register ---*/
+/* Alias word address of DMAEN bit */
+#define DCTRL_OFFSET              (SDIO_OFFSET + 0x2C)
+#define DMAEN_BitNumber           0x03
+#define DCTRL_DMAEN_BB            (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4))
+
+/* Alias word address of RWSTART bit */
+#define RWSTART_BitNumber         0x08
+#define DCTRL_RWSTART_BB          (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4))
+
+/* Alias word address of RWSTOP bit */
+#define RWSTOP_BitNumber          0x09
+#define DCTRL_RWSTOP_BB           (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4))
+
+/* Alias word address of RWMOD bit */
+#define RWMOD_BitNumber           0x0A
+#define DCTRL_RWMOD_BB            (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4))
+
+/* Alias word address of SDIOEN bit */
+#define SDIOEN_BitNumber          0x0B
+#define DCTRL_SDIOEN_BB           (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4))
+
+/* ---------------------- SDIO registers bit mask ------------------------ */
+/* --- CLKCR Register ---*/
+/* CLKCR register clear mask */
+#define CLKCR_CLEAR_MASK         ((uint32_t)0xFFFF8100) 
+
+/* --- PWRCTRL Register ---*/
+/* SDIO PWRCTRL Mask */
+#define PWR_PWRCTRL_MASK         ((uint32_t)0xFFFFFFFC)
+
+/* --- DCTRL Register ---*/
+/* SDIO DCTRL Clear Mask */
+#define DCTRL_CLEAR_MASK         ((uint32_t)0xFFFFFF08)
+
+/* --- CMD Register ---*/
+/* CMD Register clear mask */
+#define CMD_CLEAR_MASK           ((uint32_t)0xFFFFF800)
+
+/* SDIO RESP Registers Address */
+#define SDIO_RESP_ADDR           ((uint32_t)(SDIO_BASE + 0x14))
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup SDIO_Private_Functions
+  * @{
+  */
+
+/** @defgroup SDIO_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Initialization and Configuration functions #####
+ ===============================================================================
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the SDIO peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void SDIO_DeInit(void)
+{
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_SDIO, ENABLE);
+  RCC_APB2PeriphResetCmd(RCC_APB2Periph_SDIO, DISABLE);
+}
+
+/**
+  * @brief  Initializes the SDIO peripheral according to the specified 
+  *         parameters in the SDIO_InitStruct.
+  * @param  SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure 
+  *         that contains the configuration information for the SDIO peripheral.
+  * @retval None
+  */
+void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+  uint32_t tmpreg = 0;
+    
+  /* Check the parameters */
+  assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge));
+  assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass));
+  assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave));
+  assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide));
+  assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl)); 
+   
+/*---------------------------- SDIO CLKCR Configuration ------------------------*/  
+  /* Get the SDIO CLKCR value */
+  tmpreg = SDIO->CLKCR;
+  
+  /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */
+  tmpreg &= CLKCR_CLEAR_MASK;
+  
+  /* Set CLKDIV bits according to SDIO_ClockDiv value */
+  /* Set PWRSAV bit according to SDIO_ClockPowerSave value */
+  /* Set BYPASS bit according to SDIO_ClockBypass value */
+  /* Set WIDBUS bits according to SDIO_BusWide value */
+  /* Set NEGEDGE bits according to SDIO_ClockEdge value */
+  /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */
+  tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv  | SDIO_InitStruct->SDIO_ClockPowerSave |
+             SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide |
+             SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl); 
+  
+  /* Write to SDIO CLKCR */
+  SDIO->CLKCR = tmpreg;
+}
+
+/**
+  * @brief  Fills each SDIO_InitStruct member with its default value.
+  * @param  SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which 
+  *         will be initialized.
+  * @retval None
+  */
+void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct)
+{
+  /* SDIO_InitStruct members default value */
+  SDIO_InitStruct->SDIO_ClockDiv = 0x00;
+  SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising;
+  SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable;
+  SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable;
+  SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b;
+  SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable;
+}
+
+/**
+  * @brief  Enables or disables the SDIO Clock.
+  * @param  NewState: new state of the SDIO Clock. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_ClockCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CLKCR_CLKEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Sets the power status of the controller.
+  * @param  SDIO_PowerState: new state of the Power state. 
+  *          This parameter can be one of the following values:
+  *            @arg SDIO_PowerState_OFF: SDIO Power OFF
+  *            @arg SDIO_PowerState_ON: SDIO Power ON
+  * @retval None
+  */
+void SDIO_SetPowerState(uint32_t SDIO_PowerState)
+{
+  /* Check the parameters */
+  assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState));
+  
+  SDIO->POWER = SDIO_PowerState;
+}
+
+/**
+  * @brief  Gets the power status of the controller.
+  * @param  None
+  * @retval Power status of the controller. The returned value can be one of the 
+  *         following values:
+  *            - 0x00: Power OFF
+  *            - 0x02: Power UP
+  *            - 0x03: Power ON 
+  */
+uint32_t SDIO_GetPowerState(void)
+{
+  return (SDIO->POWER & (~PWR_PWRCTRL_MASK));
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Group2 Command path state machine (CPSM) management functions
+ *  @brief   Command path state machine (CPSM) management functions 
+ *
+@verbatim   
+ ===============================================================================
+        ##### Command path state machine (CPSM) management functions #####
+ ===============================================================================  
+
+  This section provide functions allowing to program and read the Command path 
+  state machine (CPSM).
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Initializes the SDIO Command according to the specified 
+  *         parameters in the SDIO_CmdInitStruct and send the command.
+  * @param  SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef 
+  *         structure that contains the configuration information for the SDIO 
+  *         command.
+  * @retval None
+  */
+void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex));
+  assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response));
+  assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait));
+  assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM));
+  
+/*---------------------------- SDIO ARG Configuration ------------------------*/
+  /* Set the SDIO Argument value */
+  SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument;
+  
+/*---------------------------- SDIO CMD Configuration ------------------------*/  
+  /* Get the SDIO CMD value */
+  tmpreg = SDIO->CMD;
+  /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */
+  tmpreg &= CMD_CLEAR_MASK;
+  /* Set CMDINDEX bits according to SDIO_CmdIndex value */
+  /* Set WAITRESP bits according to SDIO_Response value */
+  /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */
+  /* Set CPSMEN bits according to SDIO_CPSM value */
+  tmpreg |= (uint32_t)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response
+           | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM;
+  
+  /* Write to SDIO CMD */
+  SDIO->CMD = tmpreg;
+}
+
+/**
+  * @brief  Fills each SDIO_CmdInitStruct member with its default value.
+  * @param  SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef 
+  *         structure which will be initialized.
+  * @retval None
+  */
+void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct)
+{
+  /* SDIO_CmdInitStruct members default value */
+  SDIO_CmdInitStruct->SDIO_Argument = 0x00;
+  SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00;
+  SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No;
+  SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No;
+  SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable;
+}
+
+/**
+  * @brief  Returns command index of last command for which response received.
+  * @param  None
+  * @retval Returns the command index of the last command response received.
+  */
+uint8_t SDIO_GetCommandResponse(void)
+{
+  return (uint8_t)(SDIO->RESPCMD);
+}
+
+/**
+  * @brief  Returns response received from the card for the last command.
+  * @param  SDIO_RESP: Specifies the SDIO response register. 
+  *          This parameter can be one of the following values:
+  *            @arg SDIO_RESP1: Response Register 1
+  *            @arg SDIO_RESP2: Response Register 2
+  *            @arg SDIO_RESP3: Response Register 3
+  *            @arg SDIO_RESP4: Response Register 4
+  * @retval The Corresponding response register value.
+  */
+uint32_t SDIO_GetResponse(uint32_t SDIO_RESP)
+{
+  __IO uint32_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_SDIO_RESP(SDIO_RESP));
+
+  tmp = SDIO_RESP_ADDR + SDIO_RESP;
+  
+  return (*(__IO uint32_t *) tmp); 
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Group3 Data path state machine (DPSM) management functions
+ *  @brief   Data path state machine (DPSM) management functions
+ *
+@verbatim   
+ ===============================================================================
+         ##### Data path state machine (DPSM) management functions #####
+ ===============================================================================  
+
+  This section provide functions allowing to program and read the Data path 
+  state machine (DPSM).
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Initializes the SDIO data path according to the specified 
+  *         parameters in the SDIO_DataInitStruct.
+  * @param  SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef structure 
+  *         that contains the configuration information for the SDIO command.
+  * @retval None
+  */
+void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+  uint32_t tmpreg = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength));
+  assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize));
+  assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir));
+  assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode));
+  assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM));
+
+/*---------------------------- SDIO DTIMER Configuration ---------------------*/
+  /* Set the SDIO Data TimeOut value */
+  SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut;
+
+/*---------------------------- SDIO DLEN Configuration -----------------------*/
+  /* Set the SDIO DataLength value */
+  SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength;
+
+/*---------------------------- SDIO DCTRL Configuration ----------------------*/  
+  /* Get the SDIO DCTRL value */
+  tmpreg = SDIO->DCTRL;
+  /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */
+  tmpreg &= DCTRL_CLEAR_MASK;
+  /* Set DEN bit according to SDIO_DPSM value */
+  /* Set DTMODE bit according to SDIO_TransferMode value */
+  /* Set DTDIR bit according to SDIO_TransferDir value */
+  /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */
+  tmpreg |= (uint32_t)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir
+           | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM;
+
+  /* Write to SDIO DCTRL */
+  SDIO->DCTRL = tmpreg;
+}
+
+/**
+  * @brief  Fills each SDIO_DataInitStruct member with its default value.
+  * @param  SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef structure 
+  *         which will be initialized.
+  * @retval None
+  */
+void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct)
+{
+  /* SDIO_DataInitStruct members default value */
+  SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF;
+  SDIO_DataInitStruct->SDIO_DataLength = 0x00;
+  SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b;
+  SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard;
+  SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block;  
+  SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable;
+}
+
+/**
+  * @brief  Returns number of remaining data bytes to be transferred.
+  * @param  None
+  * @retval Number of remaining data bytes to be transferred
+  */
+uint32_t SDIO_GetDataCounter(void)
+{ 
+  return SDIO->DCOUNT;
+}
+
+/**
+  * @brief  Read one data word from Rx FIFO.
+  * @param  None
+  * @retval Data received
+  */
+uint32_t SDIO_ReadData(void)
+{ 
+  return SDIO->FIFO;
+}
+
+/**
+  * @brief  Write one data word to Tx FIFO.
+  * @param  Data: 32-bit data word to write.
+  * @retval None
+  */
+void SDIO_WriteData(uint32_t Data)
+{ 
+  SDIO->FIFO = Data;
+}
+
+/**
+  * @brief  Returns the number of words left to be written to or read from FIFO.	
+  * @param  None
+  * @retval Remaining number of words.
+  */
+uint32_t SDIO_GetFIFOCount(void)
+{ 
+  return SDIO->FIFOCNT;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Group4 SDIO IO Cards mode management functions
+ *  @brief   SDIO IO Cards mode management functions
+ *
+@verbatim   
+ ===============================================================================
+               ##### SDIO IO Cards mode management functions #####
+ ===============================================================================  
+
+  This section provide functions allowing to program and read the SDIO IO Cards.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Starts the SD I/O Read Wait operation.	
+  * @param  NewState: new state of the Start SDIO Read Wait operation. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_StartSDIOReadWait(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_RWSTART_BB = (uint32_t) NewState;
+}
+
+/**
+  * @brief  Stops the SD I/O Read Wait operation.	
+  * @param  NewState: new state of the Stop SDIO Read Wait operation. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_StopSDIOReadWait(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_RWSTOP_BB = (uint32_t) NewState;
+}
+
+/**
+  * @brief  Sets one of the two options of inserting read wait interval.
+  * @param  SDIO_ReadWaitMode: SD I/O Read Wait operation mode.
+  *          This parameter can be:
+  *            @arg SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK
+  *            @arg SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2
+  * @retval None
+  */
+void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode)
+{
+  /* Check the parameters */
+  assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode));
+  
+  *(__IO uint32_t *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode;
+}
+
+/**
+  * @brief  Enables or disables the SD I/O Mode Operation.
+  * @param  NewState: new state of SDIO specific operation. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_SetSDIOOperation(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_SDIOEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the SD I/O Mode suspend command sending.
+  * @param  NewState: new state of the SD I/O Mode suspend command.
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_SendSDIOSuspendCmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_SDIOSUSPEND_BB = (uint32_t)NewState;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Group5 CE-ATA mode management functions
+ *  @brief   CE-ATA mode management functions
+ *
+@verbatim   
+ ===============================================================================
+                  ##### CE-ATA mode management functions #####
+ ===============================================================================  
+
+  This section provide functions allowing to program and read the CE-ATA card.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the command completion signal.
+  * @param  NewState: new state of command completion signal. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_CommandCompletionCmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_ENCMDCOMPL_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Enables or disables the CE-ATA interrupt.
+  * @param  NewState: new state of CE-ATA interrupt. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_CEATAITCmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)((~((uint32_t)NewState)) & ((uint32_t)0x1));
+}
+
+/**
+  * @brief  Sends CE-ATA command (CMD61).
+  * @param  NewState: new state of CE-ATA command. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_SendCEATACmd(FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) CMD_ATACMD_BB = (uint32_t)NewState;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Group6 DMA transfers management functions
+ *  @brief   DMA transfers management functions
+ *
+@verbatim   
+ ===============================================================================
+                  ##### DMA transfers management functions #####
+ ===============================================================================  
+
+  This section provide functions allowing to program SDIO DMA transfer.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the SDIO DMA request.
+  * @param  NewState: new state of the selected SDIO DMA request.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SDIO_DMACmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  *(__IO uint32_t *) DCTRL_DMAEN_BB = (uint32_t)NewState;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SDIO_Group7 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions  
+ *
+@verbatim   
+ ===============================================================================
+              ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the SDIO interrupts.
+  * @param  SDIO_IT: specifies the SDIO interrupt sources to be enabled or disabled.
+  *          This parameter can be one or a combination of the following values:
+  *            @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt
+  *            @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt
+  *            @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt
+  *            @arg SDIO_IT_DTIMEOUT: Data timeout interrupt
+  *            @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+  *            @arg SDIO_IT_RXOVERR:  Received FIFO overrun error interrupt
+  *            @arg SDIO_IT_CMDREND:  Command response received (CRC check passed) interrupt
+  *            @arg SDIO_IT_CMDSENT:  Command sent (no response required) interrupt
+  *            @arg SDIO_IT_DATAEND:  Data end (data counter, SDIDCOUNT, is zero) interrupt
+  *            @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide 
+  *                                   bus mode interrupt
+  *            @arg SDIO_IT_DBCKEND:  Data block sent/received (CRC check passed) interrupt
+  *            @arg SDIO_IT_CMDACT:   Command transfer in progress interrupt
+  *            @arg SDIO_IT_TXACT:    Data transmit in progress interrupt
+  *            @arg SDIO_IT_RXACT:    Data receive in progress interrupt
+  *            @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+  *            @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+  *            @arg SDIO_IT_TXFIFOF:  Transmit FIFO full interrupt
+  *            @arg SDIO_IT_RXFIFOF:  Receive FIFO full interrupt
+  *            @arg SDIO_IT_TXFIFOE:  Transmit FIFO empty interrupt
+  *            @arg SDIO_IT_RXFIFOE:  Receive FIFO empty interrupt
+  *            @arg SDIO_IT_TXDAVL:   Data available in transmit FIFO interrupt
+  *            @arg SDIO_IT_RXDAVL:   Data available in receive FIFO interrupt
+  *            @arg SDIO_IT_SDIOIT:   SD I/O interrupt received interrupt
+  *            @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt
+  * @param  NewState: new state of the specified SDIO interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None 
+  */
+void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SDIO_IT(SDIO_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the SDIO interrupts */
+    SDIO->MASK |= SDIO_IT;
+  }
+  else
+  {
+    /* Disable the SDIO interrupts */
+    SDIO->MASK &= ~SDIO_IT;
+  } 
+}
+
+/**
+  * @brief  Checks whether the specified SDIO flag is set or not.
+  * @param  SDIO_FLAG: specifies the flag to check. 
+  *          This parameter can be one of the following values:
+  *            @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed)
+  *            @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed)
+  *            @arg SDIO_FLAG_CTIMEOUT: Command response timeout
+  *            @arg SDIO_FLAG_DTIMEOUT: Data timeout
+  *            @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+  *            @arg SDIO_FLAG_RXOVERR:  Received FIFO overrun error
+  *            @arg SDIO_FLAG_CMDREND:  Command response received (CRC check passed)
+  *            @arg SDIO_FLAG_CMDSENT:  Command sent (no response required)
+  *            @arg SDIO_FLAG_DATAEND:  Data end (data counter, SDIDCOUNT, is zero)
+  *            @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide bus mode.
+  *            @arg SDIO_FLAG_DBCKEND:  Data block sent/received (CRC check passed)
+  *            @arg SDIO_FLAG_CMDACT:   Command transfer in progress
+  *            @arg SDIO_FLAG_TXACT:    Data transmit in progress
+  *            @arg SDIO_FLAG_RXACT:    Data receive in progress
+  *            @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty
+  *            @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full
+  *            @arg SDIO_FLAG_TXFIFOF:  Transmit FIFO full
+  *            @arg SDIO_FLAG_RXFIFOF:  Receive FIFO full
+  *            @arg SDIO_FLAG_TXFIFOE:  Transmit FIFO empty
+  *            @arg SDIO_FLAG_RXFIFOE:  Receive FIFO empty
+  *            @arg SDIO_FLAG_TXDAVL:   Data available in transmit FIFO
+  *            @arg SDIO_FLAG_RXDAVL:   Data available in receive FIFO
+  *            @arg SDIO_FLAG_SDIOIT:   SD I/O interrupt received
+  *            @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61
+  * @retval The new state of SDIO_FLAG (SET or RESET).
+  */
+FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG)
+{ 
+  FlagStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_FLAG(SDIO_FLAG));
+  
+  if ((SDIO->STA & SDIO_FLAG) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the SDIO's pending flags.
+  * @param  SDIO_FLAG: specifies the flag to clear.  
+  *          This parameter can be one or a combination of the following values:
+  *            @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed)
+  *            @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed)
+  *            @arg SDIO_FLAG_CTIMEOUT: Command response timeout
+  *            @arg SDIO_FLAG_DTIMEOUT: Data timeout
+  *            @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error
+  *            @arg SDIO_FLAG_RXOVERR:  Received FIFO overrun error
+  *            @arg SDIO_FLAG_CMDREND:  Command response received (CRC check passed)
+  *            @arg SDIO_FLAG_CMDSENT:  Command sent (no response required)
+  *            @arg SDIO_FLAG_DATAEND:  Data end (data counter, SDIDCOUNT, is zero)
+  *            @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide bus mode
+  *            @arg SDIO_FLAG_DBCKEND:  Data block sent/received (CRC check passed)
+  *            @arg SDIO_FLAG_SDIOIT:   SD I/O interrupt received
+  *            @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61
+  * @retval None
+  */
+void SDIO_ClearFlag(uint32_t SDIO_FLAG)
+{ 
+  /* Check the parameters */
+  assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG));
+   
+  SDIO->ICR = SDIO_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified SDIO interrupt has occurred or not.
+  * @param  SDIO_IT: specifies the SDIO interrupt source to check. 
+  *          This parameter can be one of the following values:
+  *            @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt
+  *            @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt
+  *            @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt
+  *            @arg SDIO_IT_DTIMEOUT: Data timeout interrupt
+  *            @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+  *            @arg SDIO_IT_RXOVERR:  Received FIFO overrun error interrupt
+  *            @arg SDIO_IT_CMDREND:  Command response received (CRC check passed) interrupt
+  *            @arg SDIO_IT_CMDSENT:  Command sent (no response required) interrupt
+  *            @arg SDIO_IT_DATAEND:  Data end (data counter, SDIDCOUNT, is zero) interrupt
+  *            @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide 
+  *                                   bus mode interrupt
+  *            @arg SDIO_IT_DBCKEND:  Data block sent/received (CRC check passed) interrupt
+  *            @arg SDIO_IT_CMDACT:   Command transfer in progress interrupt
+  *            @arg SDIO_IT_TXACT:    Data transmit in progress interrupt
+  *            @arg SDIO_IT_RXACT:    Data receive in progress interrupt
+  *            @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt
+  *            @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt
+  *            @arg SDIO_IT_TXFIFOF:  Transmit FIFO full interrupt
+  *            @arg SDIO_IT_RXFIFOF:  Receive FIFO full interrupt
+  *            @arg SDIO_IT_TXFIFOE:  Transmit FIFO empty interrupt
+  *            @arg SDIO_IT_RXFIFOE:  Receive FIFO empty interrupt
+  *            @arg SDIO_IT_TXDAVL:   Data available in transmit FIFO interrupt
+  *            @arg SDIO_IT_RXDAVL:   Data available in receive FIFO interrupt
+  *            @arg SDIO_IT_SDIOIT:   SD I/O interrupt received interrupt
+  *            @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt
+  * @retval The new state of SDIO_IT (SET or RESET).
+  */
+ITStatus SDIO_GetITStatus(uint32_t SDIO_IT)
+{ 
+  ITStatus bitstatus = RESET;
+  
+  /* Check the parameters */
+  assert_param(IS_SDIO_GET_IT(SDIO_IT));
+  if ((SDIO->STA & SDIO_IT) != (uint32_t)RESET)  
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the SDIO's interrupt pending bits.
+  * @param  SDIO_IT: specifies the interrupt pending bit to clear. 
+  *          This parameter can be one or a combination of the following values:
+  *            @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt
+  *            @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt
+  *            @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt
+  *            @arg SDIO_IT_DTIMEOUT: Data timeout interrupt
+  *            @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt
+  *            @arg SDIO_IT_RXOVERR:  Received FIFO overrun error interrupt
+  *            @arg SDIO_IT_CMDREND:  Command response received (CRC check passed) interrupt
+  *            @arg SDIO_IT_CMDSENT:  Command sent (no response required) interrupt
+  *            @arg SDIO_IT_DATAEND:  Data end (data counter, SDIO_DCOUNT, is zero) interrupt
+  *            @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide 
+  *                                   bus mode interrupt
+  *            @arg SDIO_IT_SDIOIT:   SD I/O interrupt received interrupt
+  *            @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61
+  * @retval None
+  */
+void SDIO_ClearITPendingBit(uint32_t SDIO_IT)
+{ 
+  /* Check the parameters */
+  assert_param(IS_SDIO_CLEAR_IT(SDIO_IT));
+   
+  SDIO->ICR = SDIO_IT;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c
new file mode 100644
index 0000000000000000000000000000000000000000..eb725f46ee3ca5acbc44cdfea6749bdb7873e833
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c
@@ -0,0 +1,1312 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_spi.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Serial peripheral interface (SPI):
+  *           + Initialization and Configuration
+  *           + Data transfers functions
+  *           + Hardware CRC Calculation
+  *           + DMA transfers management
+  *           + Interrupts and flags management 
+  *           
+@verbatim
+
+ ===================================================================
+                  ##### How to use this driver #####
+ ===================================================================
+ [..]
+   (#) Enable peripheral clock using the following functions 
+       RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE) for SPI1
+       RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE) for SPI2
+       RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE) for SPI3
+       RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE) for SPI4
+       RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE) for SPI5
+       RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE) for SPI6.
+  
+   (#) Enable SCK, MOSI, MISO and NSS GPIO clocks using RCC_AHB1PeriphClockCmd()
+       function. In I2S mode, if an external clock source is used then the I2S 
+       CKIN pin GPIO clock should also be enabled.
+  
+   (#) Peripherals alternate function: 
+       (++) Connect the pin to the desired peripherals' Alternate Function (AF) 
+            using GPIO_PinAFConfig() function
+       (++) Configure the desired pin in alternate function by: 
+            GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
+       (++) Select the type, pull-up/pull-down and output speed via GPIO_PuPd, 
+            GPIO_OType and GPIO_Speed members
+       (++) Call GPIO_Init() function In I2S mode, if an external clock source is 
+            used then the I2S CKIN pin should be also configured in Alternate 
+            function Push-pull pull-up mode. 
+          
+   (#) Program the Polarity, Phase, First Data, Baud Rate Prescaler, Slave 
+       Management, Peripheral Mode and CRC Polynomial values using the SPI_Init()
+       function.
+       In I2S mode, program the Mode, Standard, Data Format, MCLK Output, Audio 
+       frequency and Polarity using I2S_Init() function. For I2S mode, make sure 
+       that either:
+       (++) I2S PLL is configured using the functions 
+            RCC_I2SCLKConfig(RCC_I2S2CLKSource_PLLI2S), RCC_PLLI2SCmd(ENABLE) and 
+            RCC_GetFlagStatus(RCC_FLAG_PLLI2SRDY); or 
+       (++) External clock source is configured using the function 
+            RCC_I2SCLKConfig(RCC_I2S2CLKSource_Ext) and after setting correctly 
+            the define constant I2S_EXTERNAL_CLOCK_VAL in the stm32f4xx_conf.h file. 
+  
+   (#) Enable the NVIC and the corresponding interrupt using the function 
+       SPI_ITConfig() if you need to use interrupt mode. 
+  
+   (#) When using the DMA mode 
+       (++) Configure the DMA using DMA_Init() function
+       (++) Active the needed channel Request using SPI_I2S_DMACmd() function
+   
+   (#) Enable the SPI using the SPI_Cmd() function or enable the I2S using
+       I2S_Cmd().
+   
+   (#) Enable the DMA using the DMA_Cmd() function when using DMA mode. 
+  
+   (#) Optionally, you can enable/configure the following parameters without
+       re-initialization (i.e there is no need to call again SPI_Init() function):
+       (++) When bidirectional mode (SPI_Direction_1Line_Rx or SPI_Direction_1Line_Tx)
+            is programmed as Data direction parameter using the SPI_Init() function
+            it can be possible to switch between SPI_Direction_Tx or SPI_Direction_Rx
+            using the SPI_BiDirectionalLineConfig() function.
+       (++) When SPI_NSS_Soft is selected as Slave Select Management parameter 
+            using the SPI_Init() function it can be possible to manage the 
+            NSS internal signal using the SPI_NSSInternalSoftwareConfig() function.
+       (++) Reconfigure the data size using the SPI_DataSizeConfig() function  
+       (++) Enable or disable the SS output using the SPI_SSOutputCmd() function  
+            
+    (#) To use the CRC Hardware calculation feature refer to the Peripheral 
+        CRC hardware Calculation subsection.
+     
+  
+ [..] It is possible to use SPI in I2S full duplex mode, in this case, each SPI 
+      peripheral is able to manage sending and receiving data simultaneously
+      using two data lines. Each SPI peripheral has an extended block called I2Sxext
+      (ie. I2S2ext for SPI2 and I2S3ext for SPI3).
+      The extension block is not a full SPI IP, it is used only as I2S slave to
+      implement full duplex mode. The extension block uses the same clock sources
+      as its master.          
+      To configure I2S full duplex you have to:
+              
+      (#) Configure SPIx in I2S mode (I2S_Init() function) as described above. 
+             
+      (#) Call the I2S_FullDuplexConfig() function using the same strucutre passed to  
+          I2S_Init() function.
+              
+      (#) Call I2S_Cmd() for SPIx then for its extended block.
+            
+      (#) To configure interrupts or DMA requests and to get/clear flag status, 
+          use I2Sxext instance for the extension block.
+               
+ [..] Functions that can be called with I2Sxext instances are: I2S_Cmd(), 
+      I2S_FullDuplexConfig(), SPI_I2S_ReceiveData(), SPI_I2S_SendData(), 
+      SPI_I2S_DMACmd(), SPI_I2S_ITConfig(), SPI_I2S_GetFlagStatus(), 
+      SPI_I2S_ClearFlag(), SPI_I2S_GetITStatus() and SPI_I2S_ClearITPendingBit().
+                   
+      Example: To use SPI3 in Full duplex mode (SPI3 is Master Tx, I2S3ext is Slave Rx):
+              
+      RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE);   
+      I2S_StructInit(&I2SInitStruct);
+      I2SInitStruct.Mode = I2S_Mode_MasterTx;     
+      I2S_Init(SPI3, &I2SInitStruct);
+      I2S_FullDuplexConfig(SPI3ext, &I2SInitStruct)
+      I2S_Cmd(SPI3, ENABLE);
+      I2S_Cmd(SPI3ext, ENABLE);
+      ...
+      while (SPI_I2S_GetFlagStatus(SPI2, SPI_FLAG_TXE) == RESET)
+      {}
+      SPI_I2S_SendData(SPI3, txdata[i]);
+      ...  
+      while (SPI_I2S_GetFlagStatus(I2S3ext, SPI_FLAG_RXNE) == RESET)
+      {}
+      rxdata[i] = SPI_I2S_ReceiveData(I2S3ext);
+      ...          
+                
+ [..]       
+   (@) In I2S mode: if an external clock is used as source clock for the I2S,  
+       then the define I2S_EXTERNAL_CLOCK_VAL in file stm32f4xx_conf.h should 
+       be enabled and set to the value of the source clock frequency (in Hz).
+   
+   (@) In SPI mode: To use the SPI TI mode, call the function SPI_TIModeCmd() 
+       just after calling the function SPI_Init().
+  
+@endverbatim  
+  *                                  
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_spi.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup SPI 
+  * @brief SPI driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* SPI registers Masks */
+#define CR1_CLEAR_MASK            ((uint16_t)0x3040)
+#define I2SCFGR_CLEAR_MASK        ((uint16_t)0xF040)
+
+/* RCC PLLs masks */
+#define PLLCFGR_PPLR_MASK         ((uint32_t)0x70000000)
+#define PLLCFGR_PPLN_MASK         ((uint32_t)0x00007FC0)
+
+#define SPI_CR2_FRF               ((uint16_t)0x0010)
+#define SPI_SR_TIFRFE             ((uint16_t)0x0100)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup SPI_Private_Functions
+  * @{
+  */
+
+/** @defgroup SPI_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+             ##### Initialization and Configuration functions ##### 
+ ===============================================================================  
+ [..] This section provides a set of functions allowing to initialize the SPI 
+      Direction, SPI Mode, SPI Data Size, SPI Polarity, SPI Phase, SPI NSS 
+      Management, SPI Baud Rate Prescaler, SPI First Bit and SPI CRC Polynomial.
+  
+ [..] The SPI_Init() function follows the SPI configuration procedures for Master 
+      mode and Slave mode (details for these procedures are available in reference 
+      manual (RM0090)).
+  
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  De-initialize the SPIx peripheral registers to their default reset values.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode.   
+  *         
+  * @note   The extended I2S blocks (ie. I2S2ext and I2S3ext blocks) are de-initialized
+  *         when the relative I2S peripheral is de-initialized (the extended block's clock
+  *         is managed by the I2S peripheral clock).
+  *             
+  * @retval None
+  */
+void SPI_I2S_DeInit(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+
+  if (SPIx == SPI1)
+  {
+    /* Enable SPI1 reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
+    /* Release SPI1 from reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE);
+  }
+  else if (SPIx == SPI2)
+  {
+    /* Enable SPI2 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
+    /* Release SPI2 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE);
+  }
+  else if (SPIx == SPI3)
+  {
+    /* Enable SPI3 reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
+    /* Release SPI3 from reset state */
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE);
+  }
+  else if (SPIx == SPI4)
+  {
+    /* Enable SPI4 reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI4, ENABLE);
+    /* Release SPI4 from reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI4, DISABLE);
+  }
+  else if (SPIx == SPI5)
+  {
+    /* Enable SPI5 reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI5, ENABLE);
+    /* Release SPI5 from reset state */
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI5, DISABLE);
+  }
+  else 
+  {
+    if (SPIx == SPI6)
+    {
+      /* Enable SPI6 reset state */
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI6, ENABLE);
+      /* Release SPI6 from reset state */
+      RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI6, DISABLE);
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the SPIx peripheral according to the specified 
+  *         parameters in the SPI_InitStruct.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  SPI_InitStruct: pointer to a SPI_InitTypeDef structure that
+  *         contains the configuration information for the specified SPI peripheral.
+  * @retval None
+  */
+void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct)
+{
+  uint16_t tmpreg = 0;
+  
+  /* check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  
+  /* Check the SPI parameters */
+  assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction));
+  assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode));
+  assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize));
+  assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL));
+  assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA));
+  assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS));
+  assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler));
+  assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit));
+  assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial));
+
+/*---------------------------- SPIx CR1 Configuration ------------------------*/
+  /* Get the SPIx CR1 value */
+  tmpreg = SPIx->CR1;
+  /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */
+  tmpreg &= CR1_CLEAR_MASK;
+  /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler
+     master/salve mode, CPOL and CPHA */
+  /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */
+  /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */
+  /* Set LSBFirst bit according to SPI_FirstBit value */
+  /* Set BR bits according to SPI_BaudRatePrescaler value */
+  /* Set CPOL bit according to SPI_CPOL value */
+  /* Set CPHA bit according to SPI_CPHA value */
+  tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode |
+                  SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL |  
+                  SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS |  
+                  SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit);
+  /* Write to SPIx CR1 */
+  SPIx->CR1 = tmpreg;
+
+  /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */
+  SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SMOD);
+/*---------------------------- SPIx CRCPOLY Configuration --------------------*/
+  /* Write to SPIx CRCPOLY */
+  SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial;
+}
+
+/**
+  * @brief  Initializes the SPIx peripheral according to the specified 
+  *         parameters in the I2S_InitStruct.
+  * @param  SPIx: where x can be  2 or 3 to select the SPI peripheral (configured in I2S mode).
+  * @param  I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
+  *         contains the configuration information for the specified SPI peripheral
+  *         configured in I2S mode.
+  *           
+  * @note   The function calculates the optimal prescaler needed to obtain the most 
+  *         accurate audio frequency (depending on the I2S clock source, the PLL values 
+  *         and the product configuration). But in case the prescaler value is greater 
+  *         than 511, the default value (0x02) will be configured instead.    
+  * 
+  * @note   if an external clock is used as source clock for the I2S, then the define
+  *         I2S_EXTERNAL_CLOCK_VAL in file stm32f4xx_conf.h should be enabled and set
+  *         to the value of the the source clock frequency (in Hz).
+  *  
+  * @retval None
+  */
+void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
+{
+  uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1;
+  uint32_t tmp = 0, i2sclk = 0;
+#ifndef I2S_EXTERNAL_CLOCK_VAL
+  uint32_t pllm = 0, plln = 0, pllr = 0;
+#endif /* I2S_EXTERNAL_CLOCK_VAL */
+  
+  /* Check the I2S parameters */
+  assert_param(IS_SPI_23_PERIPH(SPIx));
+  assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
+  assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
+  assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
+  assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput));
+  assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq));
+  assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));  
+
+/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
+  /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
+  SPIx->I2SCFGR &= I2SCFGR_CLEAR_MASK; 
+  SPIx->I2SPR = 0x0002;
+  
+  /* Get the I2SCFGR register value */
+  tmpreg = SPIx->I2SCFGR;
+  
+  /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/
+  if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default)
+  {
+    i2sodd = (uint16_t)0;
+    i2sdiv = (uint16_t)2;   
+  }
+  /* If the requested audio frequency is not the default, compute the prescaler */
+  else
+  {
+    /* Check the frame length (For the Prescaler computing) *******************/
+    if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b)
+    {
+      /* Packet length is 16 bits */
+      packetlength = 1;
+    }
+    else
+    {
+      /* Packet length is 32 bits */
+      packetlength = 2;
+    }
+
+    /* Get I2S source Clock frequency  ****************************************/
+      
+    /* If an external I2S clock has to be used, this define should be set  
+       in the project configuration or in the stm32f4xx_conf.h file */
+  #ifdef I2S_EXTERNAL_CLOCK_VAL     
+    /* Set external clock as I2S clock source */
+    if ((RCC->CFGR & RCC_CFGR_I2SSRC) == 0)
+    {
+      RCC->CFGR |= (uint32_t)RCC_CFGR_I2SSRC;
+    }
+    
+    /* Set the I2S clock to the external clock  value */
+    i2sclk = I2S_EXTERNAL_CLOCK_VAL;
+
+  #else /* There is no define for External I2S clock source */
+    /* Set PLLI2S as I2S clock source */
+    if ((RCC->CFGR & RCC_CFGR_I2SSRC) != 0)
+    {
+      RCC->CFGR &= ~(uint32_t)RCC_CFGR_I2SSRC;
+    }    
+    
+    /* Get the PLLI2SN value */
+    plln = (uint32_t)(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SN) >> 6) & \
+                      (RCC_PLLI2SCFGR_PLLI2SN >> 6));
+    
+    /* Get the PLLI2SR value */
+    pllr = (uint32_t)(((RCC->PLLI2SCFGR & RCC_PLLI2SCFGR_PLLI2SR) >> 28) & \
+                      (RCC_PLLI2SCFGR_PLLI2SR >> 28));
+    
+    /* Get the PLLM value */
+    pllm = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM);      
+
+    /* Get the I2S source clock value */
+    i2sclk = (uint32_t)(((HSE_VALUE / pllm) * plln) / pllr);
+  #endif /* I2S_EXTERNAL_CLOCK_VAL */
+    
+    /* Compute the Real divider depending on the MCLK output state, with a floating point */
+    if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
+    {
+      /* MCLK output is enabled */
+      tmp = (uint16_t)(((((i2sclk / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5);
+    }
+    else
+    {
+      /* MCLK output is disabled */
+      tmp = (uint16_t)(((((i2sclk / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5);
+    }
+    
+    /* Remove the flatting point */
+    tmp = tmp / 10;  
+      
+    /* Check the parity of the divider */
+    i2sodd = (uint16_t)(tmp & (uint16_t)0x0001);
+   
+    /* Compute the i2sdiv prescaler */
+    i2sdiv = (uint16_t)((tmp - i2sodd) / 2);
+   
+    /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */
+    i2sodd = (uint16_t) (i2sodd << 8);
+  }
+
+  /* Test if the divider is 1 or 0 or greater than 0xFF */
+  if ((i2sdiv < 2) || (i2sdiv > 0xFF))
+  {
+    /* Set the default values */
+    i2sdiv = 2;
+    i2sodd = 0;
+  }
+
+  /* Write to SPIx I2SPR register the computed value */
+  SPIx->I2SPR = (uint16_t)((uint16_t)i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput));
+ 
+  /* Configure the I2S with the SPI_InitStruct values */
+  tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | (uint16_t)(I2S_InitStruct->I2S_Mode | \
+                  (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \
+                  (uint16_t)I2S_InitStruct->I2S_CPOL))));
+ 
+  /* Write to SPIx I2SCFGR */  
+  SPIx->I2SCFGR = tmpreg;
+}
+
+/**
+  * @brief  Fills each SPI_InitStruct member with its default value.
+  * @param  SPI_InitStruct: pointer to a SPI_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct)
+{
+/*--------------- Reset SPI init structure parameters values -----------------*/
+  /* Initialize the SPI_Direction member */
+  SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex;
+  /* initialize the SPI_Mode member */
+  SPI_InitStruct->SPI_Mode = SPI_Mode_Slave;
+  /* initialize the SPI_DataSize member */
+  SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b;
+  /* Initialize the SPI_CPOL member */
+  SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low;
+  /* Initialize the SPI_CPHA member */
+  SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge;
+  /* Initialize the SPI_NSS member */
+  SPI_InitStruct->SPI_NSS = SPI_NSS_Hard;
+  /* Initialize the SPI_BaudRatePrescaler member */
+  SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2;
+  /* Initialize the SPI_FirstBit member */
+  SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB;
+  /* Initialize the SPI_CRCPolynomial member */
+  SPI_InitStruct->SPI_CRCPolynomial = 7;
+}
+
+/**
+  * @brief  Fills each I2S_InitStruct member with its default value.
+  * @param  I2S_InitStruct: pointer to a I2S_InitTypeDef structure which will be initialized.
+  * @retval None
+  */
+void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct)
+{
+/*--------------- Reset I2S init structure parameters values -----------------*/
+  /* Initialize the I2S_Mode member */
+  I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx;
+  
+  /* Initialize the I2S_Standard member */
+  I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips;
+  
+  /* Initialize the I2S_DataFormat member */
+  I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b;
+  
+  /* Initialize the I2S_MCLKOutput member */
+  I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable;
+  
+  /* Initialize the I2S_AudioFreq member */
+  I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default;
+  
+  /* Initialize the I2S_CPOL member */
+  I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low;
+}
+
+/**
+  * @brief  Enables or disables the specified SPI peripheral.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  NewState: new state of the SPIx peripheral. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI peripheral */
+    SPIx->CR1 |= SPI_CR1_SPE;
+  }
+  else
+  {
+    /* Disable the selected SPI peripheral */
+    SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_SPE);
+  }
+}
+
+/**
+  * @brief  Enables or disables the specified SPI peripheral (in I2S mode).
+  * @param  SPIx: where x can be 2 or 3 to select the SPI peripheral (or I2Sxext 
+  *         for full duplex mode).
+  * @param  NewState: new state of the SPIx peripheral. 
+  *         This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_23_PERIPH_EXT(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI peripheral (in I2S mode) */
+    SPIx->I2SCFGR |= SPI_I2SCFGR_I2SE;
+  }
+  else
+  {
+    /* Disable the selected SPI peripheral in I2S mode */
+    SPIx->I2SCFGR &= (uint16_t)~((uint16_t)SPI_I2SCFGR_I2SE);
+  }
+}
+
+/**
+  * @brief  Configures the data size for the selected SPI.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  SPI_DataSize: specifies the SPI data size.
+  *          This parameter can be one of the following values:
+  *            @arg SPI_DataSize_16b: Set data frame format to 16bit
+  *            @arg SPI_DataSize_8b: Set data frame format to 8bit
+  * @retval None
+  */
+void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_DATASIZE(SPI_DataSize));
+  /* Clear DFF bit */
+  SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b;
+  /* Set new DFF bit value */
+  SPIx->CR1 |= SPI_DataSize;
+}
+
+/**
+  * @brief  Selects the data transfer direction in bidirectional mode for the specified SPI.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  SPI_Direction: specifies the data transfer direction in bidirectional mode. 
+  *          This parameter can be one of the following values:
+  *            @arg SPI_Direction_Tx: Selects Tx transmission direction
+  *            @arg SPI_Direction_Rx: Selects Rx receive direction
+  * @retval None
+  */
+void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_DIRECTION(SPI_Direction));
+  if (SPI_Direction == SPI_Direction_Tx)
+  {
+    /* Set the Tx only mode */
+    SPIx->CR1 |= SPI_Direction_Tx;
+  }
+  else
+  {
+    /* Set the Rx only mode */
+    SPIx->CR1 &= SPI_Direction_Rx;
+  }
+}
+
+/**
+  * @brief  Configures internally by software the NSS pin for the selected SPI.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  SPI_NSSInternalSoft: specifies the SPI NSS internal state.
+  *          This parameter can be one of the following values:
+  *            @arg SPI_NSSInternalSoft_Set: Set NSS pin internally
+  *            @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally
+  * @retval None
+  */
+void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft));
+  if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset)
+  {
+    /* Set NSS pin internally by software */
+    SPIx->CR1 |= SPI_NSSInternalSoft_Set;
+  }
+  else
+  {
+    /* Reset NSS pin internally by software */
+    SPIx->CR1 &= SPI_NSSInternalSoft_Reset;
+  }
+}
+
+/**
+  * @brief  Enables or disables the SS output for the selected SPI.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  NewState: new state of the SPIx SS output. 
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI SS output */
+    SPIx->CR2 |= (uint16_t)SPI_CR2_SSOE;
+  }
+  else
+  {
+    /* Disable the selected SPI SS output */
+    SPIx->CR2 &= (uint16_t)~((uint16_t)SPI_CR2_SSOE);
+  }
+}
+
+/**
+  * @brief  Enables or disables the SPIx/I2Sx DMA interface.
+  *   
+  * @note   This function can be called only after the SPI_Init() function has 
+  *         been called. 
+  * @note   When TI mode is selected, the control bits SSM, SSI, CPOL and CPHA 
+  *         are not taken into consideration and are configured by hardware
+  *         respectively to the TI mode requirements.  
+  * 
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 
+  * @param  NewState: new state of the selected SPI TI communication mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_TIModeCmd(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the TI mode for the selected SPI peripheral */
+    SPIx->CR2 |= SPI_CR2_FRF;
+  }
+  else
+  {
+    /* Disable the TI mode for the selected SPI peripheral */
+    SPIx->CR2 &= (uint16_t)~SPI_CR2_FRF;
+  }
+}
+
+/**
+  * @brief  Configures the full duplex mode for the I2Sx peripheral using its
+  *         extension I2Sxext according to the specified parameters in the 
+  *         I2S_InitStruct.
+  * @param  I2Sxext: where x can be  2 or 3 to select the I2S peripheral extension block.
+  * @param  I2S_InitStruct: pointer to an I2S_InitTypeDef structure that
+  *         contains the configuration information for the specified I2S peripheral
+  *         extension.
+  * 
+  * @note   The structure pointed by I2S_InitStruct parameter should be the same
+  *         used for the master I2S peripheral. In this case, if the master is 
+  *         configured as transmitter, the slave will be receiver and vice versa.
+  *         Or you can force a different mode by modifying the field I2S_Mode to the
+  *         value I2S_SlaveRx or I2S_SlaveTx indepedently of the master configuration.    
+  *         
+  * @note   The I2S full duplex extension can be configured in slave mode only.    
+  *  
+  * @retval None
+  */
+void I2S_FullDuplexConfig(SPI_TypeDef* I2Sxext, I2S_InitTypeDef* I2S_InitStruct)
+{
+  uint16_t tmpreg = 0, tmp = 0;
+  
+  /* Check the I2S parameters */
+  assert_param(IS_I2S_EXT_PERIPH(I2Sxext));
+  assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode));
+  assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard));
+  assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat));
+  assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL));  
+
+/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/
+  /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */
+  I2Sxext->I2SCFGR &= I2SCFGR_CLEAR_MASK; 
+  I2Sxext->I2SPR = 0x0002;
+  
+  /* Get the I2SCFGR register value */
+  tmpreg = I2Sxext->I2SCFGR;
+  
+  /* Get the mode to be configured for the extended I2S */
+  if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterTx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveTx))
+  {
+    tmp = I2S_Mode_SlaveRx;
+  }
+  else
+  {
+    if ((I2S_InitStruct->I2S_Mode == I2S_Mode_MasterRx) || (I2S_InitStruct->I2S_Mode == I2S_Mode_SlaveRx))
+    {
+      tmp = I2S_Mode_SlaveTx;
+    }
+  }
+
+ 
+  /* Configure the I2S with the SPI_InitStruct values */
+  tmpreg |= (uint16_t)((uint16_t)SPI_I2SCFGR_I2SMOD | (uint16_t)(tmp | \
+                  (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \
+                  (uint16_t)I2S_InitStruct->I2S_CPOL))));
+ 
+  /* Write to SPIx I2SCFGR */  
+  I2Sxext->I2SCFGR = tmpreg;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Group2 Data transfers functions
+ *  @brief   Data transfers functions
+ *
+@verbatim   
+ ===============================================================================
+                      ##### Data transfers functions #####
+ ===============================================================================  
+
+ [..] This section provides a set of functions allowing to manage the SPI data 
+      transfers. In reception, data are received and then stored into an internal 
+      Rx buffer while. In transmission, data are first stored into an internal Tx 
+      buffer before being transmitted.
+
+ [..] The read access of the SPI_DR register can be done using the SPI_I2S_ReceiveData()
+      function and returns the Rx buffered value. Whereas a write access to the SPI_DR 
+      can be done using SPI_I2S_SendData() function and stores the written data into 
+      Tx buffer.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Returns the most recent received data by the SPIx/I2Sx peripheral. 
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. 
+  * @retval The value of the received data.
+  */
+uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  
+  /* Return the data in the DR register */
+  return SPIx->DR;
+}
+
+/**
+  * @brief  Transmits a Data through the SPIx/I2Sx peripheral.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.     
+  * @param  Data: Data to be transmitted.
+  * @retval None
+  */
+void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  
+  /* Write in the DR register the data to be sent */
+  SPIx->DR = Data;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Group3 Hardware CRC Calculation functions
+ *  @brief   Hardware CRC Calculation functions
+ *
+@verbatim   
+ ===============================================================================
+                 ##### Hardware CRC Calculation functions #####
+ ===============================================================================  
+
+ [..] This section provides a set of functions allowing to manage the SPI CRC hardware 
+      calculation
+
+ [..] SPI communication using CRC is possible through the following procedure:
+   (#) Program the Data direction, Polarity, Phase, First Data, Baud Rate Prescaler, 
+       Slave Management, Peripheral Mode and CRC Polynomial values using the SPI_Init()
+       function.
+   (#) Enable the CRC calculation using the SPI_CalculateCRC() function.
+   (#) Enable the SPI using the SPI_Cmd() function
+   (#) Before writing the last data to the TX buffer, set the CRCNext bit using the 
+       SPI_TransmitCRC() function to indicate that after transmission of the last 
+       data, the CRC should be transmitted.
+   (#) After transmitting the last data, the SPI transmits the CRC. The SPI_CR1_CRCNEXT
+        bit is reset. The CRC is also received and compared against the SPI_RXCRCR 
+        value. 
+        If the value does not match, the SPI_FLAG_CRCERR flag is set and an interrupt
+        can be generated when the SPI_I2S_IT_ERR interrupt is enabled.
+
+ [..]
+   (@) It is advised not to read the calculated CRC values during the communication.
+
+   (@) When the SPI is in slave mode, be careful to enable CRC calculation only 
+       when the clock is stable, that is, when the clock is in the steady state. 
+       If not, a wrong CRC calculation may be done. In fact, the CRC is sensitive 
+       to the SCK slave input clock as soon as CRCEN is set, and this, whatever 
+       the value of the SPE bit.
+
+   (@) With high bitrate frequencies, be careful when transmitting the CRC.
+       As the number of used CPU cycles has to be as low as possible in the CRC 
+       transfer phase, it is forbidden to call software functions in the CRC 
+       transmission sequence to avoid errors in the last data and CRC reception. 
+       In fact, CRCNEXT bit has to be written before the end of the transmission/reception 
+       of the last data.
+
+   (@) For high bit rate frequencies, it is advised to use the DMA mode to avoid the
+       degradation of the SPI speed performance due to CPU accesses impacting the 
+       SPI bandwidth.
+
+   (@) When the STM32F4xx is configured as slave and the NSS hardware mode is 
+       used, the NSS pin needs to be kept low between the data phase and the CRC 
+       phase.
+
+   (@) When the SPI is configured in slave mode with the CRC feature enabled, CRC
+       calculation takes place even if a high level is applied on the NSS pin. 
+       This may happen for example in case of a multi-slave environment where the 
+       communication master addresses slaves alternately.
+
+   (@) Between a slave de-selection (high level on NSS) and a new slave selection 
+       (low level on NSS), the CRC value should be cleared on both master and slave
+       sides in order to resynchronize the master and slave for their respective 
+       CRC calculation.
+
+   (@) To clear the CRC, follow the procedure below:
+       (#@) Disable SPI using the SPI_Cmd() function
+       (#@) Disable the CRC calculation using the SPI_CalculateCRC() function.
+       (#@) Enable the CRC calculation using the SPI_CalculateCRC() function.
+       (#@) Enable SPI using the SPI_Cmd() function.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the CRC value calculation of the transferred bytes.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  NewState: new state of the SPIx CRC value calculation.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI CRC calculation */
+    SPIx->CR1 |= SPI_CR1_CRCEN;
+  }
+  else
+  {
+    /* Disable the selected SPI CRC calculation */
+    SPIx->CR1 &= (uint16_t)~((uint16_t)SPI_CR1_CRCEN);
+  }
+}
+
+/**
+  * @brief  Transmit the SPIx CRC value.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @retval None
+  */
+void SPI_TransmitCRC(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  
+  /* Enable the selected SPI CRC transmission */
+  SPIx->CR1 |= SPI_CR1_CRCNEXT;
+}
+
+/**
+  * @brief  Returns the transmit or the receive CRC register value for the specified SPI.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @param  SPI_CRC: specifies the CRC register to be read.
+  *          This parameter can be one of the following values:
+  *            @arg SPI_CRC_Tx: Selects Tx CRC register
+  *            @arg SPI_CRC_Rx: Selects Rx CRC register
+  * @retval The selected CRC register value..
+  */
+uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC)
+{
+  uint16_t crcreg = 0;
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  assert_param(IS_SPI_CRC(SPI_CRC));
+  if (SPI_CRC != SPI_CRC_Rx)
+  {
+    /* Get the Tx CRC register */
+    crcreg = SPIx->TXCRCR;
+  }
+  else
+  {
+    /* Get the Rx CRC register */
+    crcreg = SPIx->RXCRCR;
+  }
+  /* Return the selected CRC register */
+  return crcreg;
+}
+
+/**
+  * @brief  Returns the CRC Polynomial register value for the specified SPI.
+  * @param  SPIx: where x can be 1, 2, 3, 4, 5 or 6 to select the SPI peripheral.
+  * @retval The CRC Polynomial register value.
+  */
+uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH(SPIx));
+  
+  /* Return the CRC polynomial register */
+  return SPIx->CRCPR;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Group4 DMA transfers management functions
+ *  @brief   DMA transfers management functions
+  *
+@verbatim   
+ ===============================================================================
+                   ##### DMA transfers management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the SPIx/I2Sx DMA interface.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. 
+  * @param  SPI_I2S_DMAReq: specifies the SPI DMA transfer request to be enabled or disabled. 
+  *          This parameter can be any combination of the following values:
+  *            @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request
+  *            @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request
+  * @param  NewState: new state of the selected SPI DMA transfer request.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI DMA requests */
+    SPIx->CR2 |= SPI_I2S_DMAReq;
+  }
+  else
+  {
+    /* Disable the selected SPI DMA requests */
+    SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq;
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup SPI_Group5 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions
+  *
+@verbatim   
+ ===============================================================================
+            ##### Interrupts and flags management functions #####
+ ===============================================================================  
+ 
+ [..] This section provides a set of functions allowing to configure the SPI Interrupts 
+      sources and check or clear the flags or pending bits status.
+      The user should identify which mode will be used in his application to manage 
+      the communication: Polling mode, Interrupt mode or DMA mode. 
+    
+ *** Polling Mode ***
+ ====================
+[..] In Polling Mode, the SPI/I2S communication can be managed by 9 flags:
+  (#) SPI_I2S_FLAG_TXE : to indicate the status of the transmit buffer register
+  (#) SPI_I2S_FLAG_RXNE : to indicate the status of the receive buffer register
+  (#) SPI_I2S_FLAG_BSY : to indicate the state of the communication layer of the SPI.
+  (#) SPI_FLAG_CRCERR : to indicate if a CRC Calculation error occur              
+  (#) SPI_FLAG_MODF : to indicate if a Mode Fault error occur
+  (#) SPI_I2S_FLAG_OVR : to indicate if an Overrun error occur
+  (#) I2S_FLAG_TIFRFE: to indicate a Frame Format error occurs.
+  (#) I2S_FLAG_UDR: to indicate an Underrun error occurs.
+  (#) I2S_FLAG_CHSIDE: to indicate Channel Side.
+
+  (@) Do not use the BSY flag to handle each data transmission or reception. It is
+      better to use the TXE and RXNE flags instead.
+
+ [..] In this Mode it is advised to use the following functions:
+   (+) FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
+   (+) void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG);
+
+ *** Interrupt Mode ***
+ ======================
+ [..] In Interrupt Mode, the SPI communication can be managed by 3 interrupt sources
+      and 7 pending bits: 
+   (+) Pending Bits:
+       (##) SPI_I2S_IT_TXE : to indicate the status of the transmit buffer register
+       (##) SPI_I2S_IT_RXNE : to indicate the status of the receive buffer register
+       (##) SPI_IT_CRCERR : to indicate if a CRC Calculation error occur (available in SPI mode only)            
+       (##) SPI_IT_MODF : to indicate if a Mode Fault error occur (available in SPI mode only)
+       (##) SPI_I2S_IT_OVR : to indicate if an Overrun error occur
+       (##) I2S_IT_UDR : to indicate an Underrun Error occurs (available in I2S mode only).
+       (##) I2S_FLAG_TIFRFE : to indicate a Frame Format error occurs (available in TI mode only).
+
+   (+) Interrupt Source:
+       (##) SPI_I2S_IT_TXE: specifies the interrupt source for the Tx buffer empty 
+            interrupt.  
+       (##) SPI_I2S_IT_RXNE : specifies the interrupt source for the Rx buffer not 
+            empty interrupt.
+       (##) SPI_I2S_IT_ERR : specifies the interrupt source for the errors interrupt.
+
+ [..] In this Mode it is advised to use the following functions:
+   (+) void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState);
+   (+) ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
+   (+) void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT);
+
+ *** DMA Mode ***
+ ================
+ [..] In DMA Mode, the SPI communication can be managed by 2 DMA Channel requests:
+   (#) SPI_I2S_DMAReq_Tx: specifies the Tx buffer DMA transfer request
+   (#) SPI_I2S_DMAReq_Rx: specifies the Rx buffer DMA transfer request
+
+ [..] In this Mode it is advised to use the following function:
+   (+) void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState 
+       NewState);
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified SPI/I2S interrupts.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. 
+  * @param  SPI_I2S_IT: specifies the SPI interrupt source to be enabled or disabled. 
+  *          This parameter can be one of the following values:
+  *            @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask
+  *            @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask
+  *            @arg SPI_I2S_IT_ERR: Error interrupt mask
+  * @param  NewState: new state of the specified SPI interrupt.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState)
+{
+  uint16_t itpos = 0, itmask = 0 ;
+  
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT));
+
+  /* Get the SPI IT index */
+  itpos = SPI_I2S_IT >> 4;
+
+  /* Set the IT mask */
+  itmask = (uint16_t)1 << (uint16_t)itpos;
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected SPI interrupt */
+    SPIx->CR2 |= itmask;
+  }
+  else
+  {
+    /* Disable the selected SPI interrupt */
+    SPIx->CR2 &= (uint16_t)~itmask;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified SPIx/I2Sx flag is set or not.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. 
+  * @param  SPI_I2S_FLAG: specifies the SPI flag to check. 
+  *          This parameter can be one of the following values:
+  *            @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag.
+  *            @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag.
+  *            @arg SPI_I2S_FLAG_BSY: Busy flag.
+  *            @arg SPI_I2S_FLAG_OVR: Overrun flag.
+  *            @arg SPI_FLAG_MODF: Mode Fault flag.
+  *            @arg SPI_FLAG_CRCERR: CRC Error flag.
+  *            @arg SPI_I2S_FLAG_TIFRFE: Format Error.
+  *            @arg I2S_FLAG_UDR: Underrun Error flag.
+  *            @arg I2S_FLAG_CHSIDE: Channel Side flag.  
+  * @retval The new state of SPI_I2S_FLAG (SET or RESET).
+  */
+FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG));
+  
+  /* Check the status of the specified SPI flag */
+  if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET)
+  {
+    /* SPI_I2S_FLAG is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SPI_I2S_FLAG is reset */
+    bitstatus = RESET;
+  }
+  /* Return the SPI_I2S_FLAG status */
+  return  bitstatus;
+}
+
+/**
+  * @brief  Clears the SPIx CRC Error (CRCERR) flag.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode. 
+  * @param  SPI_I2S_FLAG: specifies the SPI flag to clear. 
+  *          This function clears only CRCERR flag.
+  *            @arg SPI_FLAG_CRCERR: CRC Error flag.  
+  *  
+  * @note   OVR (OverRun error) flag is cleared by software sequence: a read 
+  *          operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read 
+  *          operation to SPI_SR register (SPI_I2S_GetFlagStatus()).
+  * @note   UDR (UnderRun error) flag is cleared by a read operation to 
+  *          SPI_SR register (SPI_I2S_GetFlagStatus()).   
+  * @note   MODF (Mode Fault) flag is cleared by software sequence: a read/write 
+  *          operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a 
+  *          write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI).
+  *  
+  * @retval None
+  */
+void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG));
+    
+  /* Clear the selected SPI CRC Error (CRCERR) flag */
+  SPIx->SR = (uint16_t)~SPI_I2S_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified SPIx/I2Sx interrupt has occurred or not.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.  
+  * @param  SPI_I2S_IT: specifies the SPI interrupt source to check. 
+  *          This parameter can be one of the following values:
+  *            @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt.
+  *            @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt.
+  *            @arg SPI_I2S_IT_OVR: Overrun interrupt.
+  *            @arg SPI_IT_MODF: Mode Fault interrupt.
+  *            @arg SPI_IT_CRCERR: CRC Error interrupt.
+  *            @arg I2S_IT_UDR: Underrun interrupt.  
+  *            @arg SPI_I2S_IT_TIFRFE: Format Error interrupt.  
+  * @retval The new state of SPI_I2S_IT (SET or RESET).
+  */
+ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
+{
+  ITStatus bitstatus = RESET;
+  uint16_t itpos = 0, itmask = 0, enablestatus = 0;
+
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT));
+
+  /* Get the SPI_I2S_IT index */
+  itpos = 0x01 << (SPI_I2S_IT & 0x0F);
+
+  /* Get the SPI_I2S_IT IT mask */
+  itmask = SPI_I2S_IT >> 4;
+
+  /* Set the IT mask */
+  itmask = 0x01 << itmask;
+
+  /* Get the SPI_I2S_IT enable bit status */
+  enablestatus = (SPIx->CR2 & itmask) ;
+
+  /* Check the status of the specified SPI interrupt */
+  if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus)
+  {
+    /* SPI_I2S_IT is set */
+    bitstatus = SET;
+  }
+  else
+  {
+    /* SPI_I2S_IT is reset */
+    bitstatus = RESET;
+  }
+  /* Return the SPI_I2S_IT status */
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the SPIx CRC Error (CRCERR) interrupt pending bit.
+  * @param  SPIx: To select the SPIx/I2Sx peripheral, where x can be: 1, 2, 3, 4, 5 or 6 
+  *         in SPI mode or 2 or 3 in I2S mode or I2Sxext for I2S full duplex mode.  
+  * @param  SPI_I2S_IT: specifies the SPI interrupt pending bit to clear.
+  *         This function clears only CRCERR interrupt pending bit.   
+  *            @arg SPI_IT_CRCERR: CRC Error interrupt.
+  *   
+  * @note   OVR (OverRun Error) interrupt pending bit is cleared by software 
+  *          sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData()) 
+  *          followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()).
+  * @note   UDR (UnderRun Error) interrupt pending bit is cleared by a read 
+  *          operation to SPI_SR register (SPI_I2S_GetITStatus()).   
+  * @note   MODF (Mode Fault) interrupt pending bit is cleared by software sequence:
+  *          a read/write operation to SPI_SR register (SPI_I2S_GetITStatus()) 
+  *          followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable 
+  *          the SPI).
+  * @retval None
+  */
+void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT)
+{
+  uint16_t itpos = 0;
+  /* Check the parameters */
+  assert_param(IS_SPI_ALL_PERIPH_EXT(SPIx));
+  assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT));
+
+  /* Get the SPI_I2S IT index */
+  itpos = 0x01 << (SPI_I2S_IT & 0x0F);
+
+  /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */
+  SPIx->SR = (uint16_t)~itpos;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c
new file mode 100644
index 0000000000000000000000000000000000000000..638f76115a1bffcb7fd109c96f640c0387505f5e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_syscfg.c
@@ -0,0 +1,240 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_syscfg.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the SYSCFG peripheral.
+  *
+ @verbatim
+    
+ ===============================================================================
+                     ##### How to use this driver #####
+ ===============================================================================
+    [..] This driver provides functions for:
+            
+       (#) Remapping the memory accessible in the code area using SYSCFG_MemoryRemapConfig()
+            
+       (#) Swapping the internal flash Bank1 and Bank2 this features is only visible for 
+           STM32F42xxx/43xxx devices Devices. 
+                
+       (#) Manage the EXTI lines connection to the GPIOs using SYSCFG_EXTILineConfig()
+              
+       (#) Select the ETHERNET media interface (RMII/RII) using SYSCFG_ETH_MediaInterfaceConfig()
+  
+       -@- SYSCFG APB clock must be enabled to get write access to SYSCFG registers,
+           using RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
+                   
+ @endverbatim      
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_syscfg.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup SYSCFG 
+  * @brief SYSCFG driver modules
+  * @{
+  */ 
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* ------------ RCC registers bit address in the alias region ----------- */
+#define SYSCFG_OFFSET             (SYSCFG_BASE - PERIPH_BASE)
+/* ---  MEMRMP Register ---*/ 
+/* Alias word address of UFB_MODE bit */ 
+#define MEMRMP_OFFSET             SYSCFG_OFFSET 
+#define UFB_MODE_BitNumber        ((uint8_t)0x8) 
+#define UFB_MODE_BB               (PERIPH_BB_BASE + (MEMRMP_OFFSET * 32) + (UFB_MODE_BitNumber * 4)) 
+
+
+/* ---  PMC Register ---*/ 
+/* Alias word address of MII_RMII_SEL bit */ 
+#define PMC_OFFSET                (SYSCFG_OFFSET + 0x04) 
+#define MII_RMII_SEL_BitNumber    ((uint8_t)0x17) 
+#define PMC_MII_RMII_SEL_BB       (PERIPH_BB_BASE + (PMC_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) 
+
+/* ---  CMPCR Register ---*/ 
+/* Alias word address of CMP_PD bit */ 
+#define CMPCR_OFFSET              (SYSCFG_OFFSET + 0x20) 
+#define CMP_PD_BitNumber          ((uint8_t)0x00) 
+#define CMPCR_CMP_PD_BB           (PERIPH_BB_BASE + (CMPCR_OFFSET * 32) + (CMP_PD_BitNumber * 4)) 
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup SYSCFG_Private_Functions
+  * @{
+  */ 
+
+/**
+  * @brief  Deinitializes the Alternate Functions (remap and EXTI configuration)
+  *   registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void SYSCFG_DeInit(void)
+{
+   RCC_APB2PeriphResetCmd(RCC_APB2Periph_SYSCFG, ENABLE);
+   RCC_APB2PeriphResetCmd(RCC_APB2Periph_SYSCFG, DISABLE);
+}
+
+/**
+  * @brief  Changes the mapping of the specified pin.
+  * @param  SYSCFG_Memory: selects the memory remapping.
+  *         This parameter can be one of the following values:
+  *            @arg SYSCFG_MemoryRemap_Flash:       Main Flash memory mapped at 0x00000000  
+  *            @arg SYSCFG_MemoryRemap_SystemFlash: System Flash memory mapped at 0x00000000
+  *            @arg SYSCFG_MemoryRemap_FSMC:        FSMC (Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 for STM32F405xx/407xx and STM32F415xx/417xx devices. 
+  *            @arg SYSCFG_MemoryRemap_FMC:         FMC (Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 for STM32F42xxx/43xxx devices.  
+  *            @arg SYSCFG_MemoryRemap_SRAM:        Embedded SRAM (112kB) mapped at 0x00000000
+  *            @arg SYSCFG_MemoryRemap_SDRAM:       FMC (External SDRAM)  mapped at 0x00000000 for STM32F42xxx/43xxx devices.            
+  * @retval None
+  */
+void SYSCFG_MemoryRemapConfig(uint8_t SYSCFG_MemoryRemap)
+{
+  /* Check the parameters */
+  assert_param(IS_SYSCFG_MEMORY_REMAP_CONFING(SYSCFG_MemoryRemap));
+
+  SYSCFG->MEMRMP = SYSCFG_MemoryRemap;
+}
+
+/**
+  * @brief  Enables or disables the Interal FLASH Bank Swapping.
+  *   
+  * @note   This function can be used only for STM32F42xxx/43xxx devices. 
+  *
+  * @param  NewState: new state of Interal FLASH Bank swapping.
+  *          This parameter can be one of the following values:
+  *            @arg ENABLE: Flash Bank2 mapped at 0x08000000 (and aliased @0x00000000) 
+  *                         and Flash Bank1 mapped at 0x08100000 (and aliased at 0x00100000)   
+  *            @arg DISABLE:(the default state) Flash Bank1 mapped at 0x08000000 (and aliased @0x0000 0000) 
+                            and Flash Bank2 mapped at 0x08100000 (and aliased at 0x00100000)  
+  * @retval None
+  */
+void SYSCFG_MemorySwappingBank(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) UFB_MODE_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Selects the GPIO pin used as EXTI Line.
+  * @param  EXTI_PortSourceGPIOx : selects the GPIO port to be used as source for
+  *          EXTI lines where x can be (A..K) for STM32F42xxx/43xxx devices, (A..I) 
+  *          for STM32F405xx/407xx and STM32F415xx/417xx devices or (A, B, C, D and H)
+  *          for STM32401xx devices.  
+  *            
+  * @param  EXTI_PinSourcex: specifies the EXTI line to be configured.
+  *           This parameter can be EXTI_PinSourcex where x can be (0..15, except
+  *           for EXTI_PortSourceGPIOI x can be (0..11) for STM32F405xx/407xx
+  *           and STM32F405xx/407xx devices and for EXTI_PortSourceGPIOK x can   
+  *           be (0..7) for STM32F42xxx/43xxx devices. 
+  *             
+  * @retval None
+  */
+void SYSCFG_EXTILineConfig(uint8_t EXTI_PortSourceGPIOx, uint8_t EXTI_PinSourcex)
+{
+  uint32_t tmp = 0x00;
+
+  /* Check the parameters */
+  assert_param(IS_EXTI_PORT_SOURCE(EXTI_PortSourceGPIOx));
+  assert_param(IS_EXTI_PIN_SOURCE(EXTI_PinSourcex));
+
+  tmp = ((uint32_t)0x0F) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03));
+  SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] &= ~tmp;
+  SYSCFG->EXTICR[EXTI_PinSourcex >> 0x02] |= (((uint32_t)EXTI_PortSourceGPIOx) << (0x04 * (EXTI_PinSourcex & (uint8_t)0x03)));
+}
+
+/**
+  * @brief  Selects the ETHERNET media interface 
+  * @param  SYSCFG_ETH_MediaInterface: specifies the Media Interface mode. 
+  *          This parameter can be one of the following values: 
+  *            @arg SYSCFG_ETH_MediaInterface_MII: MII mode selected
+  *            @arg SYSCFG_ETH_MediaInterface_RMII: RMII mode selected 
+  * @retval None 
+  */
+void SYSCFG_ETH_MediaInterfaceConfig(uint32_t SYSCFG_ETH_MediaInterface) 
+{ 
+  assert_param(IS_SYSCFG_ETH_MEDIA_INTERFACE(SYSCFG_ETH_MediaInterface)); 
+  /* Configure MII_RMII selection bit */ 
+  *(__IO uint32_t *) PMC_MII_RMII_SEL_BB = SYSCFG_ETH_MediaInterface; 
+}
+
+/**
+  * @brief  Enables or disables the I/O Compensation Cell.
+  * @note   The I/O compensation cell can be used only when the device supply
+  *         voltage ranges from 2.4 to 3.6 V.  
+  * @param  NewState: new state of the I/O Compensation Cell.
+  *          This parameter can be one of the following values:
+  *            @arg ENABLE: I/O compensation cell enabled  
+  *            @arg DISABLE: I/O compensation cell power-down mode  
+  * @retval None
+  */
+void SYSCFG_CompensationCellCmd(FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  *(__IO uint32_t *) CMPCR_CMP_PD_BB = (uint32_t)NewState;
+}
+
+/**
+  * @brief  Checks whether the I/O Compensation Cell ready flag is set or not.
+  * @param  None
+  * @retval The new state of the I/O Compensation Cell ready flag (SET or RESET)
+  */
+FlagStatus SYSCFG_GetCompensationCellStatus(void)
+{
+  FlagStatus bitstatus = RESET;
+    
+  if ((SYSCFG->CMPCR & SYSCFG_CMPCR_READY ) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/   
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c
new file mode 100644
index 0000000000000000000000000000000000000000..9a17ac316cd17a523f962261b21ffb2b0ee2109a
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c
@@ -0,0 +1,3365 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_tim.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the TIM peripheral:
+  *            + TimeBase management
+  *            + Output Compare management
+  *            + Input Capture management
+  *            + Advanced-control timers (TIM1 and TIM8) specific features  
+  *            + Interrupts, DMA and flags management
+  *            + Clocks management
+  *            + Synchronization management
+  *            + Specific interface management
+  *            + Specific remapping management      
+  *              
+  @verbatim   
+ ===============================================================================
+                   #####  How to use this driver #####
+ ===============================================================================
+    [..]
+    This driver provides functions to configure and program the TIM 
+    of all STM32F4xx devices.
+    These functions are split in 9 groups: 
+     
+      (#) TIM TimeBase management: this group includes all needed functions 
+          to configure the TM Timebase unit:
+        (++) Set/Get Prescaler
+        (++) Set/Get Autoreload  
+        (++) Counter modes configuration
+        (++) Set Clock division  
+        (++) Select the One Pulse mode
+        (++) Update Request Configuration
+        (++) Update Disable Configuration
+        (++) Auto-Preload Configuration 
+        (++) Enable/Disable the counter     
+                   
+      (#) TIM Output Compare management: this group includes all needed 
+          functions to configure the Capture/Compare unit used in Output 
+          compare mode: 
+        (++) Configure each channel, independently, in Output Compare mode
+        (++) Select the output compare modes
+        (++) Select the Polarities of each channel
+        (++) Set/Get the Capture/Compare register values
+        (++) Select the Output Compare Fast mode 
+        (++) Select the Output Compare Forced mode  
+        (++) Output Compare-Preload Configuration 
+        (++) Clear Output Compare Reference
+        (++) Select the OCREF Clear signal
+        (++) Enable/Disable the Capture/Compare Channels    
+                     
+      (#) TIM Input Capture management: this group includes all needed 
+          functions to configure the Capture/Compare unit used in 
+          Input Capture mode:
+        (++) Configure each channel in input capture mode
+        (++) Configure Channel1/2 in PWM Input mode
+        (++) Set the Input Capture Prescaler
+        (++) Get the Capture/Compare values      
+                     
+      (#) Advanced-control timers (TIM1 and TIM8) specific features
+        (++) Configures the Break input, dead time, Lock level, the OSSI,
+             the OSSR State and the AOE(automatic output enable)
+        (++) Enable/Disable the TIM peripheral Main Outputs
+        (++) Select the Commutation event
+        (++) Set/Reset the Capture Compare Preload Control bit
+                                
+      (#) TIM interrupts, DMA and flags management
+        (++) Enable/Disable interrupt sources
+        (++) Get flags status
+        (++) Clear flags/ Pending bits
+        (++) Enable/Disable DMA requests 
+        (++) Configure DMA burst mode
+        (++) Select CaptureCompare DMA request  
+                
+      (#) TIM clocks management: this group includes all needed functions 
+          to configure the clock controller unit:
+        (++) Select internal/External clock
+        (++) Select the external clock mode: ETR(Mode1/Mode2), TIx or ITRx
+           
+      (#) TIM synchronization management: this group includes all needed 
+          functions to configure the Synchronization unit:
+        (++) Select Input Trigger  
+        (++) Select Output Trigger  
+        (++) Select Master Slave Mode 
+        (++) ETR Configuration when used as external trigger   
+       
+      (#) TIM specific interface management, this group includes all 
+          needed functions to use the specific TIM interface:
+        (++) Encoder Interface Configuration
+        (++) Select Hall Sensor   
+           
+      (#) TIM specific remapping management includes the Remapping 
+          configuration of specific timers               
+     
+  @endverbatim    
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_tim.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup TIM 
+  * @brief TIM driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* ---------------------- TIM registers bit mask ------------------------ */
+#define SMCR_ETR_MASK      ((uint16_t)0x00FF) 
+#define CCMR_OFFSET        ((uint16_t)0x0018)
+#define CCER_CCE_SET       ((uint16_t)0x0001)  
+#define	CCER_CCNE_SET      ((uint16_t)0x0004) 
+#define CCMR_OC13M_MASK    ((uint16_t)0xFF8F)
+#define CCMR_OC24M_MASK    ((uint16_t)0x8FFF) 
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter);
+
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup TIM_Private_Functions
+  * @{
+  */
+
+/** @defgroup TIM_Group1 TimeBase management functions
+ *  @brief   TimeBase management functions 
+ *
+@verbatim   
+ ===============================================================================
+                     ##### TimeBase management functions #####
+ ===============================================================================  
+  
+     
+            ##### TIM Driver: how to use it in Timing(Time base) Mode #####
+ ===============================================================================
+    [..] 
+    To use the Timer in Timing(Time base) mode, the following steps are mandatory:
+       
+      (#) Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) function
+                    
+      (#) Fill the TIM_TimeBaseInitStruct with the desired parameters.
+       
+      (#) Call TIM_TimeBaseInit(TIMx, &TIM_TimeBaseInitStruct) to configure the Time Base unit
+          with the corresponding configuration
+          
+      (#) Enable the NVIC if you need to generate the update interrupt. 
+          
+      (#) Enable the corresponding interrupt using the function TIM_ITConfig(TIMx, TIM_IT_Update) 
+       
+      (#) Call the TIM_Cmd(ENABLE) function to enable the TIM counter.
+             
+       -@- All other functions can be used separately to modify, if needed,
+           a specific feature of the Timer. 
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Deinitializes the TIMx peripheral registers to their default reset values.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @retval None
+
+  */
+void TIM_DeInit(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx)); 
+ 
+  if (TIMx == TIM1)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE);  
+  } 
+  else if (TIMx == TIM2) 
+  {     
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE);
+  }  
+  else if (TIMx == TIM3)
+  { 
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE);
+  }  
+  else if (TIMx == TIM4)
+  { 
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE);
+  }  
+  else if (TIMx == TIM5)
+  {      
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE);
+  }  
+  else if (TIMx == TIM6)  
+  {    
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE);
+  }  
+  else if (TIMx == TIM7)
+  {      
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE);
+  }  
+  else if (TIMx == TIM8)
+  {      
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE);  
+  }  
+  else if (TIMx == TIM9)
+  {      
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, DISABLE);  
+   }  
+  else if (TIMx == TIM10)
+  {      
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, DISABLE);  
+  }  
+  else if (TIMx == TIM11) 
+  {     
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, DISABLE);  
+  }  
+  else if (TIMx == TIM12)
+  {      
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, DISABLE);  
+  }  
+  else if (TIMx == TIM13) 
+  {       
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, DISABLE);  
+  }  
+  else
+  { 
+    if (TIMx == TIM14) 
+    {     
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, ENABLE);
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, DISABLE); 
+    }   
+  }
+}
+
+/**
+  * @brief  Initializes the TIMx Time Base Unit peripheral according to 
+  *         the specified parameters in the TIM_TimeBaseInitStruct.
+  * @param  TIMx: where x can be  1 to 14 to select the TIM peripheral.
+  * @param  TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef structure
+  *         that contains the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+  uint16_t tmpcr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx)); 
+  assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode));
+  assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision));
+
+  tmpcr1 = TIMx->CR1;  
+
+  if((TIMx == TIM1) || (TIMx == TIM8)||
+     (TIMx == TIM2) || (TIMx == TIM3)||
+     (TIMx == TIM4) || (TIMx == TIM5)) 
+  {
+    /* Select the Counter Mode */
+    tmpcr1 &= (uint16_t)(~(TIM_CR1_DIR | TIM_CR1_CMS));
+    tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode;
+  }
+ 
+  if((TIMx != TIM6) && (TIMx != TIM7))
+  {
+    /* Set the clock division */
+    tmpcr1 &=  (uint16_t)(~TIM_CR1_CKD);
+    tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision;
+  }
+
+  TIMx->CR1 = tmpcr1;
+
+  /* Set the Autoreload value */
+  TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ;
+ 
+  /* Set the Prescaler value */
+  TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler;
+    
+  if ((TIMx == TIM1) || (TIMx == TIM8))  
+  {
+    /* Set the Repetition Counter value */
+    TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter;
+  }
+
+  /* Generate an update event to reload the Prescaler 
+     and the repetition counter(only for TIM1 and TIM8) value immediatly */
+  TIMx->EGR = TIM_PSCReloadMode_Immediate;          
+}
+
+/**
+  * @brief  Fills each TIM_TimeBaseInitStruct member with its default value.
+  * @param  TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef
+  *         structure which will be initialized.
+  * @retval None
+  */
+void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct)
+{
+  /* Set the default configuration */
+  TIM_TimeBaseInitStruct->TIM_Period = 0xFFFFFFFF;
+  TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000;
+  TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1;
+  TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up;
+  TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000;
+}
+
+/**
+  * @brief  Configures the TIMx Prescaler.
+  * @param  TIMx: where x can be  1 to 14 to select the TIM peripheral.
+  * @param  Prescaler: specifies the Prescaler Register value
+  * @param  TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode
+  *          This parameter can be one of the following values:
+  *            @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event.
+  *            @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediatly.
+  * @retval None
+  */
+void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode));
+  /* Set the Prescaler value */
+  TIMx->PSC = Prescaler;
+  /* Set or reset the UG Bit */
+  TIMx->EGR = TIM_PSCReloadMode;
+}
+
+/**
+  * @brief  Specifies the TIMx Counter Mode to be used.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_CounterMode: specifies the Counter Mode to be used
+  *          This parameter can be one of the following values:
+  *            @arg TIM_CounterMode_Up: TIM Up Counting Mode
+  *            @arg TIM_CounterMode_Down: TIM Down Counting Mode
+  *            @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1
+  *            @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2
+  *            @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3
+  * @retval None
+  */
+void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode)
+{
+  uint16_t tmpcr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode));
+
+  tmpcr1 = TIMx->CR1;
+
+  /* Reset the CMS and DIR Bits */
+  tmpcr1 &= (uint16_t)~(TIM_CR1_DIR | TIM_CR1_CMS);
+
+  /* Set the Counter Mode */
+  tmpcr1 |= TIM_CounterMode;
+
+  /* Write to TIMx CR1 register */
+  TIMx->CR1 = tmpcr1;
+}
+
+/**
+  * @brief  Sets the TIMx Counter Register value
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  Counter: specifies the Counter register new value.
+  * @retval None
+  */
+void TIM_SetCounter(TIM_TypeDef* TIMx, uint32_t Counter)
+{
+  /* Check the parameters */
+   assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+  /* Set the Counter Register value */
+  TIMx->CNT = Counter;
+}
+
+/**
+  * @brief  Sets the TIMx Autoreload Register value
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  Autoreload: specifies the Autoreload register new value.
+  * @retval None
+  */
+void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint32_t Autoreload)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  
+  /* Set the Autoreload Register value */
+  TIMx->ARR = Autoreload;
+}
+
+/**
+  * @brief  Gets the TIMx Counter value.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @retval Counter Register value
+  */
+uint32_t TIM_GetCounter(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+  /* Get the Counter Register value */
+  return TIMx->CNT;
+}
+
+/**
+  * @brief  Gets the TIMx Prescaler value.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @retval Prescaler Register value.
+  */
+uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+  /* Get the Prescaler Register value */
+  return TIMx->PSC;
+}
+
+/**
+  * @brief  Enables or Disables the TIMx Update event.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  NewState: new state of the TIMx UDIS bit
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Set the Update Disable Bit */
+    TIMx->CR1 |= TIM_CR1_UDIS;
+  }
+  else
+  {
+    /* Reset the Update Disable Bit */
+    TIMx->CR1 &= (uint16_t)~TIM_CR1_UDIS;
+  }
+}
+
+/**
+  * @brief  Configures the TIMx Update Request Interrupt source.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  TIM_UpdateSource: specifies the Update source.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_UpdateSource_Global: Source of update is the counter
+  *                 overflow/underflow or the setting of UG bit, or an update
+  *                 generation through the slave mode controller.
+  *            @arg TIM_UpdateSource_Regular: Source of update is counter overflow/underflow.
+  * @retval None
+  */
+void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource));
+
+  if (TIM_UpdateSource != TIM_UpdateSource_Global)
+  {
+    /* Set the URS Bit */
+    TIMx->CR1 |= TIM_CR1_URS;
+  }
+  else
+  {
+    /* Reset the URS Bit */
+    TIMx->CR1 &= (uint16_t)~TIM_CR1_URS;
+  }
+}
+
+/**
+  * @brief  Enables or disables TIMx peripheral Preload register on ARR.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  NewState: new state of the TIMx peripheral Preload register
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Set the ARR Preload Bit */
+    TIMx->CR1 |= TIM_CR1_ARPE;
+  }
+  else
+  {
+    /* Reset the ARR Preload Bit */
+    TIMx->CR1 &= (uint16_t)~TIM_CR1_ARPE;
+  }
+}
+
+/**
+  * @brief  Selects the TIMx's One Pulse Mode.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  TIM_OPMode: specifies the OPM Mode to be used.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OPMode_Single
+  *            @arg TIM_OPMode_Repetitive
+  * @retval None
+  */
+void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_OPM_MODE(TIM_OPMode));
+
+  /* Reset the OPM Bit */
+  TIMx->CR1 &= (uint16_t)~TIM_CR1_OPM;
+
+  /* Configure the OPM Mode */
+  TIMx->CR1 |= TIM_OPMode;
+}
+
+/**
+  * @brief  Sets the TIMx Clock Division value.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_CKD: specifies the clock division value.
+  *          This parameter can be one of the following value:
+  *            @arg TIM_CKD_DIV1: TDTS = Tck_tim
+  *            @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim
+  *            @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim
+  * @retval None
+  */
+void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_CKD_DIV(TIM_CKD));
+
+  /* Reset the CKD Bits */
+  TIMx->CR1 &= (uint16_t)(~TIM_CR1_CKD);
+
+  /* Set the CKD value */
+  TIMx->CR1 |= TIM_CKD;
+}
+
+/**
+  * @brief  Enables or disables the specified TIM peripheral.
+  * @param  TIMx: where x can be 1 to 14 to select the TIMx peripheral.
+  * @param  NewState: new state of the TIMx peripheral.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx)); 
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the TIM Counter */
+    TIMx->CR1 |= TIM_CR1_CEN;
+  }
+  else
+  {
+    /* Disable the TIM Counter */
+    TIMx->CR1 &= (uint16_t)~TIM_CR1_CEN;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group2 Output Compare management functions
+ *  @brief    Output Compare management functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Output Compare management functions #####
+ ===============================================================================  
+   
+      
+        ##### TIM Driver: how to use it in Output Compare Mode #####
+ ===============================================================================
+    [..] 
+    To use the Timer in Output Compare mode, the following steps are mandatory:
+       
+      (#) Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) 
+          function
+       
+      (#) Configure the TIM pins by configuring the corresponding GPIO pins
+       
+      (#) Configure the Time base unit as described in the first part of this driver, 
+        (++) if needed, else the Timer will run with the default configuration:
+            Autoreload value = 0xFFFF
+        (++) Prescaler value = 0x0000
+        (++) Counter mode = Up counting
+        (++) Clock Division = TIM_CKD_DIV1
+          
+      (#) Fill the TIM_OCInitStruct with the desired parameters including:
+        (++) The TIM Output Compare mode: TIM_OCMode
+        (++) TIM Output State: TIM_OutputState
+        (++) TIM Pulse value: TIM_Pulse
+        (++) TIM Output Compare Polarity : TIM_OCPolarity
+       
+      (#) Call TIM_OCxInit(TIMx, &TIM_OCInitStruct) to configure the desired 
+          channel with the corresponding configuration
+       
+      (#) Call the TIM_Cmd(ENABLE) function to enable the TIM counter.
+       
+      -@- All other functions can be used separately to modify, if needed,
+          a specific feature of the Timer. 
+          
+      -@- In case of PWM mode, this function is mandatory:
+          TIM_OCxPreloadConfig(TIMx, TIM_OCPreload_ENABLE); 
+              
+      -@- If the corresponding interrupt or DMA request are needed, the user should:
+        (+@) Enable the NVIC (or the DMA) to use the TIM interrupts (or DMA requests). 
+        (+@) Enable the corresponding interrupt (or DMA request) using the function 
+             TIM_ITConfig(TIMx, TIM_IT_CCx) (or TIM_DMA_Cmd(TIMx, TIM_DMA_CCx))   
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Initializes the TIMx Channel1 according to the specified parameters in
+  *         the TIM_OCInitStruct.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains
+  *         the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+
+  /* Disable the Channel 1: Reset the CC1E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC1E;
+  
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR1 register value */
+  tmpccmrx = TIMx->CCMR1;
+    
+  /* Reset the Output Compare Mode Bits */
+  tmpccmrx &= (uint16_t)~TIM_CCMR1_OC1M;
+  tmpccmrx &= (uint16_t)~TIM_CCMR1_CC1S;
+  /* Select the Output Compare Mode */
+  tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= (uint16_t)~TIM_CCER_CC1P;
+  /* Set the Output Compare Polarity */
+  tmpccer |= TIM_OCInitStruct->TIM_OCPolarity;
+  
+  /* Set the Output State */
+  tmpccer |= TIM_OCInitStruct->TIM_OutputState;
+    
+  if((TIMx == TIM1) || (TIMx == TIM8))
+  {
+    assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+    assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+    assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    
+    /* Reset the Output N Polarity level */
+    tmpccer &= (uint16_t)~TIM_CCER_CC1NP;
+    /* Set the Output N Polarity */
+    tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity;
+    /* Reset the Output N State */
+    tmpccer &= (uint16_t)~TIM_CCER_CC1NE;
+    
+    /* Set the Output N State */
+    tmpccer |= TIM_OCInitStruct->TIM_OutputNState;
+    /* Reset the Output Compare and Output Compare N IDLE State */
+    tmpcr2 &= (uint16_t)~TIM_CR2_OIS1;
+    tmpcr2 &= (uint16_t)~TIM_CR2_OIS1N;
+    /* Set the Output Idle state */
+    tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState;
+    /* Set the Output N Idle state */
+    tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState;
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmrx;
+  
+  /* Set the Capture Compare Register value */
+  TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Initializes the TIMx Channel2 according to the specified parameters 
+  *         in the TIM_OCInitStruct.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains
+  *         the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+
+  /* Disable the Channel 2: Reset the CC2E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC2E;
+  
+  /* Get the TIMx CCER register value */  
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR1 register value */
+  tmpccmrx = TIMx->CCMR1;
+    
+  /* Reset the Output Compare mode and Capture/Compare selection Bits */
+  tmpccmrx &= (uint16_t)~TIM_CCMR1_OC2M;
+  tmpccmrx &= (uint16_t)~TIM_CCMR1_CC2S;
+  
+  /* Select the Output Compare Mode */
+  tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8);
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= (uint16_t)~TIM_CCER_CC2P;
+  /* Set the Output Compare Polarity */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 4);
+  
+  /* Set the Output State */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 4);
+    
+  if((TIMx == TIM1) || (TIMx == TIM8))
+  {
+    assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+    assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+    assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    
+    /* Reset the Output N Polarity level */
+    tmpccer &= (uint16_t)~TIM_CCER_CC2NP;
+    /* Set the Output N Polarity */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 4);
+    /* Reset the Output N State */
+    tmpccer &= (uint16_t)~TIM_CCER_CC2NE;
+    
+    /* Set the Output N State */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 4);
+    /* Reset the Output Compare and Output Compare N IDLE State */
+    tmpcr2 &= (uint16_t)~TIM_CR2_OIS2;
+    tmpcr2 &= (uint16_t)~TIM_CR2_OIS2N;
+    /* Set the Output Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 2);
+    /* Set the Output N Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 2);
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmrx;
+  
+  /* Set the Capture Compare Register value */
+  TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Initializes the TIMx Channel3 according to the specified parameters
+  *         in the TIM_OCInitStruct.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains
+  *         the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+
+  /* Disable the Channel 3: Reset the CC2E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC3E;
+  
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR2 register value */
+  tmpccmrx = TIMx->CCMR2;
+    
+  /* Reset the Output Compare mode and Capture/Compare selection Bits */
+  tmpccmrx &= (uint16_t)~TIM_CCMR2_OC3M;
+  tmpccmrx &= (uint16_t)~TIM_CCMR2_CC3S;  
+  /* Select the Output Compare Mode */
+  tmpccmrx |= TIM_OCInitStruct->TIM_OCMode;
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= (uint16_t)~TIM_CCER_CC3P;
+  /* Set the Output Compare Polarity */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 8);
+  
+  /* Set the Output State */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 8);
+    
+  if((TIMx == TIM1) || (TIMx == TIM8))
+  {
+    assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState));
+    assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity));
+    assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState));
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    
+    /* Reset the Output N Polarity level */
+    tmpccer &= (uint16_t)~TIM_CCER_CC3NP;
+    /* Set the Output N Polarity */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 8);
+    /* Reset the Output N State */
+    tmpccer &= (uint16_t)~TIM_CCER_CC3NE;
+    
+    /* Set the Output N State */
+    tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 8);
+    /* Reset the Output Compare and Output Compare N IDLE State */
+    tmpcr2 &= (uint16_t)~TIM_CR2_OIS3;
+    tmpcr2 &= (uint16_t)~TIM_CR2_OIS3N;
+    /* Set the Output Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 4);
+    /* Set the Output N Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 4);
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR2 */
+  TIMx->CCMR2 = tmpccmrx;
+  
+  /* Set the Capture Compare Register value */
+  TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Initializes the TIMx Channel4 according to the specified parameters
+  *         in the TIM_OCInitStruct.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure that contains
+  *         the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0;
+   
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx)); 
+  assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode));
+  assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity));   
+
+  /* Disable the Channel 4: Reset the CC4E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC4E;
+  
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+  /* Get the TIMx CR2 register value */
+  tmpcr2 =  TIMx->CR2;
+  
+  /* Get the TIMx CCMR2 register value */
+  tmpccmrx = TIMx->CCMR2;
+    
+  /* Reset the Output Compare mode and Capture/Compare selection Bits */
+  tmpccmrx &= (uint16_t)~TIM_CCMR2_OC4M;
+  tmpccmrx &= (uint16_t)~TIM_CCMR2_CC4S;
+  
+  /* Select the Output Compare Mode */
+  tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8);
+  
+  /* Reset the Output Polarity level */
+  tmpccer &= (uint16_t)~TIM_CCER_CC4P;
+  /* Set the Output Compare Polarity */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 12);
+  
+  /* Set the Output State */
+  tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 12);
+  
+  if((TIMx == TIM1) || (TIMx == TIM8))
+  {
+    assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState));
+    /* Reset the Output Compare IDLE State */
+    tmpcr2 &=(uint16_t) ~TIM_CR2_OIS4;
+    /* Set the Output Idle state */
+    tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 6);
+  }
+  /* Write to TIMx CR2 */
+  TIMx->CR2 = tmpcr2;
+  
+  /* Write to TIMx CCMR2 */  
+  TIMx->CCMR2 = tmpccmrx;
+    
+  /* Set the Capture Compare Register value */
+  TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse;
+  
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Fills each TIM_OCInitStruct member with its default value.
+  * @param  TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct)
+{
+  /* Set the default configuration */
+  TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing;
+  TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable;
+  TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable;
+  TIM_OCInitStruct->TIM_Pulse = 0x00000000;
+  TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High;
+  TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High;
+  TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset;
+  TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset;
+}
+
+/**
+  * @brief  Selects the TIM Output Compare Mode.
+  * @note   This function disables the selected channel before changing the Output
+  *         Compare Mode. If needed, user has to enable this channel using
+  *         TIM_CCxCmd() and TIM_CCxNCmd() functions.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_Channel: specifies the TIM Channel
+  *          This parameter can be one of the following values:
+  *            @arg TIM_Channel_1: TIM Channel 1
+  *            @arg TIM_Channel_2: TIM Channel 2
+  *            @arg TIM_Channel_3: TIM Channel 3
+  *            @arg TIM_Channel_4: TIM Channel 4
+  * @param  TIM_OCMode: specifies the TIM Output Compare Mode.
+  *           This parameter can be one of the following values:
+  *            @arg TIM_OCMode_Timing
+  *            @arg TIM_OCMode_Active
+  *            @arg TIM_OCMode_Toggle
+  *            @arg TIM_OCMode_PWM1
+  *            @arg TIM_OCMode_PWM2
+  *            @arg TIM_ForcedAction_Active
+  *            @arg TIM_ForcedAction_InActive
+  * @retval None
+  */
+void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
+{
+  uint32_t tmp = 0;
+  uint16_t tmp1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_CHANNEL(TIM_Channel));
+  assert_param(IS_TIM_OCM(TIM_OCMode));
+
+  tmp = (uint32_t) TIMx;
+  tmp += CCMR_OFFSET;
+
+  tmp1 = CCER_CCE_SET << (uint16_t)TIM_Channel;
+
+  /* Disable the Channel: Reset the CCxE Bit */
+  TIMx->CCER &= (uint16_t) ~tmp1;
+
+  if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
+  {
+    tmp += (TIM_Channel>>1);
+
+    /* Reset the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp &= CCMR_OC13M_MASK;
+   
+    /* Configure the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp |= TIM_OCMode;
+  }
+  else
+  {
+    tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1;
+
+    /* Reset the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp &= CCMR_OC24M_MASK;
+    
+    /* Configure the OCxM bits in the CCMRx register */
+    *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8);
+  }
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare1 Register value
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  Compare1: specifies the Capture Compare1 register new value.
+  * @retval None
+  */
+void TIM_SetCompare1(TIM_TypeDef* TIMx, uint32_t Compare1)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+
+  /* Set the Capture Compare1 Register value */
+  TIMx->CCR1 = Compare1;
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare2 Register value
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  Compare2: specifies the Capture Compare2 register new value.
+  * @retval None
+  */
+void TIM_SetCompare2(TIM_TypeDef* TIMx, uint32_t Compare2)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+
+  /* Set the Capture Compare2 Register value */
+  TIMx->CCR2 = Compare2;
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare3 Register value
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  Compare3: specifies the Capture Compare3 register new value.
+  * @retval None
+  */
+void TIM_SetCompare3(TIM_TypeDef* TIMx, uint32_t Compare3)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+
+  /* Set the Capture Compare3 Register value */
+  TIMx->CCR3 = Compare3;
+}
+
+/**
+  * @brief  Sets the TIMx Capture Compare4 Register value
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  Compare4: specifies the Capture Compare4 register new value.
+  * @retval None
+  */
+void TIM_SetCompare4(TIM_TypeDef* TIMx, uint32_t Compare4)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+
+  /* Set the Capture Compare4 Register value */
+  TIMx->CCR4 = Compare4;
+}
+
+/**
+  * @brief  Forces the TIMx output 1 waveform to active or inactive level.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ForcedAction_Active: Force active level on OC1REF
+  *            @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF.
+  * @retval None
+  */
+void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC1M Bits */
+  tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC1M;
+
+  /* Configure The Forced output Mode */
+  tmpccmr1 |= TIM_ForcedAction;
+
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Forces the TIMx output 2 waveform to active or inactive level.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ForcedAction_Active: Force active level on OC2REF
+  *            @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF.
+  * @retval None
+  */
+void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC2M Bits */
+  tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC2M;
+
+  /* Configure The Forced output Mode */
+  tmpccmr1 |= (uint16_t)(TIM_ForcedAction << 8);
+
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Forces the TIMx output 3 waveform to active or inactive level.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ForcedAction_Active: Force active level on OC3REF
+  *            @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF.
+  * @retval None
+  */
+void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC1M Bits */
+  tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC3M;
+
+  /* Configure The Forced output Mode */
+  tmpccmr2 |= TIM_ForcedAction;
+
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Forces the TIMx output 4 waveform to active or inactive level.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ForcedAction: specifies the forced Action to be set to the output waveform.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ForcedAction_Active: Force active level on OC4REF
+  *            @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF.
+  * @retval None
+  */
+void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction)
+{
+  uint16_t tmpccmr2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction));
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC2M Bits */
+  tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC4M;
+
+  /* Configure The Forced output Mode */
+  tmpccmr2 |= (uint16_t)(TIM_ForcedAction << 8);
+
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR1.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPreload_Enable
+  *            @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC1PE Bit */
+  tmpccmr1 &= (uint16_t)(~TIM_CCMR1_OC1PE);
+
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr1 |= TIM_OCPreload;
+
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR2.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPreload_Enable
+  *            @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC2PE Bit */
+  tmpccmr1 &= (uint16_t)(~TIM_CCMR1_OC2PE);
+
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr1 |= (uint16_t)(TIM_OCPreload << 8);
+
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR3.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPreload_Enable
+  *            @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC3PE Bit */
+  tmpccmr2 &= (uint16_t)(~TIM_CCMR2_OC3PE);
+
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr2 |= TIM_OCPreload;
+
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Enables or disables the TIMx peripheral Preload register on CCR4.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPreload: new state of the TIMx peripheral Preload register
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPreload_Enable
+  *            @arg TIM_OCPreload_Disable
+  * @retval None
+  */
+void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload)
+{
+  uint16_t tmpccmr2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload));
+
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC4PE Bit */
+  tmpccmr2 &= (uint16_t)(~TIM_CCMR2_OC4PE);
+
+  /* Enable or Disable the Output Compare Preload feature */
+  tmpccmr2 |= (uint16_t)(TIM_OCPreload << 8);
+
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 1 Fast feature.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *            @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+  /* Get the TIMx CCMR1 register value */
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC1FE Bit */
+  tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC1FE;
+
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr1 |= TIM_OCFast;
+
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 2 Fast feature.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *            @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+  /* Get the TIMx CCMR1 register value */
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC2FE Bit */
+  tmpccmr1 &= (uint16_t)(~TIM_CCMR1_OC2FE);
+
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr1 |= (uint16_t)(TIM_OCFast << 8);
+
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 3 Fast feature.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *            @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr2 = 0;
+  
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+  /* Get the TIMx CCMR2 register value */
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC3FE Bit */
+  tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC3FE;
+
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr2 |= TIM_OCFast;
+
+  /* Write to TIMx CCMR2 */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Configures the TIMx Output Compare 4 Fast feature.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCFast: new state of the Output Compare Fast Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCFast_Enable: TIM output compare fast enable
+  *            @arg TIM_OCFast_Disable: TIM output compare fast disable
+  * @retval None
+  */
+void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast)
+{
+  uint16_t tmpccmr2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast));
+
+  /* Get the TIMx CCMR2 register value */
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC4FE Bit */
+  tmpccmr2 &= (uint16_t)(~TIM_CCMR2_OC4FE);
+
+  /* Enable or Disable the Output Compare Fast Bit */
+  tmpccmr2 |= (uint16_t)(TIM_OCFast << 8);
+
+  /* Write to TIMx CCMR2 */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF1 signal on an external event
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCClear_Enable: TIM Output clear enable
+  *            @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC1CE Bit */
+  tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC1CE;
+
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr1 |= TIM_OCClear;
+
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF2 signal on an external event
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCClear_Enable: TIM Output clear enable
+  *            @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr1 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Reset the OC2CE Bit */
+  tmpccmr1 &= (uint16_t)~TIM_CCMR1_OC2CE;
+
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr1 |= (uint16_t)(TIM_OCClear << 8);
+
+  /* Write to TIMx CCMR1 register */
+  TIMx->CCMR1 = tmpccmr1;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF3 signal on an external event
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCClear_Enable: TIM Output clear enable
+  *            @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC3CE Bit */
+  tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC3CE;
+
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr2 |= TIM_OCClear;
+
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Clears or safeguards the OCREF4 signal on an external event
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCClear: new state of the Output Compare Clear Enable Bit.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCClear_Enable: TIM Output clear enable
+  *            @arg TIM_OCClear_Disable: TIM Output clear disable
+  * @retval None
+  */
+void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear)
+{
+  uint16_t tmpccmr2 = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear));
+
+  tmpccmr2 = TIMx->CCMR2;
+
+  /* Reset the OC4CE Bit */
+  tmpccmr2 &= (uint16_t)~TIM_CCMR2_OC4CE;
+
+  /* Enable or Disable the Output Compare Clear Bit */
+  tmpccmr2 |= (uint16_t)(TIM_OCClear << 8);
+
+  /* Write to TIMx CCMR2 register */
+  TIMx->CCMR2 = tmpccmr2;
+}
+
+/**
+  * @brief  Configures the TIMx channel 1 polarity.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_OCPolarity: specifies the OC1 Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPolarity_High: Output Compare active high
+  *            @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+  tmpccer = TIMx->CCER;
+
+  /* Set or Reset the CC1P Bit */
+  tmpccer &= (uint16_t)(~TIM_CCER_CC1P);
+  tmpccer |= TIM_OCPolarity;
+
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx Channel 1N polarity.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_OCNPolarity: specifies the OC1N Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCNPolarity_High: Output Compare active high
+  *            @arg TIM_OCNPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity)
+{
+  uint16_t tmpccer = 0;
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+   
+  tmpccer = TIMx->CCER;
+
+  /* Set or Reset the CC1NP Bit */
+  tmpccer &= (uint16_t)~TIM_CCER_CC1NP;
+  tmpccer |= TIM_OCNPolarity;
+
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx channel 2 polarity.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_OCPolarity: specifies the OC2 Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPolarity_High: Output Compare active high
+  *            @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+  tmpccer = TIMx->CCER;
+
+  /* Set or Reset the CC2P Bit */
+  tmpccer &= (uint16_t)(~TIM_CCER_CC2P);
+  tmpccer |= (uint16_t)(TIM_OCPolarity << 4);
+
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx Channel 2N polarity.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_OCNPolarity: specifies the OC2N Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCNPolarity_High: Output Compare active high
+  *            @arg TIM_OCNPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity)
+{
+  uint16_t tmpccer = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+  
+  tmpccer = TIMx->CCER;
+
+  /* Set or Reset the CC2NP Bit */
+  tmpccer &= (uint16_t)~TIM_CCER_CC2NP;
+  tmpccer |= (uint16_t)(TIM_OCNPolarity << 4);
+
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx channel 3 polarity.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPolarity: specifies the OC3 Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPolarity_High: Output Compare active high
+  *            @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+  tmpccer = TIMx->CCER;
+
+  /* Set or Reset the CC3P Bit */
+  tmpccer &= (uint16_t)~TIM_CCER_CC3P;
+  tmpccer |= (uint16_t)(TIM_OCPolarity << 8);
+
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx Channel 3N polarity.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_OCNPolarity: specifies the OC3N Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCNPolarity_High: Output Compare active high
+  *            @arg TIM_OCNPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity)
+{
+  uint16_t tmpccer = 0;
+ 
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity));
+    
+  tmpccer = TIMx->CCER;
+
+  /* Set or Reset the CC3NP Bit */
+  tmpccer &= (uint16_t)~TIM_CCER_CC3NP;
+  tmpccer |= (uint16_t)(TIM_OCNPolarity << 8);
+
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configures the TIMx channel 4 polarity.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_OCPolarity: specifies the OC4 Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_OCPolarity_High: Output Compare active high
+  *            @arg TIM_OCPolarity_Low: Output Compare active low
+  * @retval None
+  */
+void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity)
+{
+  uint16_t tmpccer = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity));
+
+  tmpccer = TIMx->CCER;
+
+  /* Set or Reset the CC4P Bit */
+  tmpccer &= (uint16_t)~TIM_CCER_CC4P;
+  tmpccer |= (uint16_t)(TIM_OCPolarity << 12);
+
+  /* Write to TIMx CCER register */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Enables or disables the TIM Capture Compare Channel x.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_Channel: specifies the TIM Channel
+  *          This parameter can be one of the following values:
+  *            @arg TIM_Channel_1: TIM Channel 1
+  *            @arg TIM_Channel_2: TIM Channel 2
+  *            @arg TIM_Channel_3: TIM Channel 3
+  *            @arg TIM_Channel_4: TIM Channel 4
+  * @param  TIM_CCx: specifies the TIM Channel CCxE bit new state.
+  *          This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. 
+  * @retval None
+  */
+void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx)
+{
+  uint16_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx)); 
+  assert_param(IS_TIM_CHANNEL(TIM_Channel));
+  assert_param(IS_TIM_CCX(TIM_CCx));
+
+  tmp = CCER_CCE_SET << TIM_Channel;
+
+  /* Reset the CCxE Bit */
+  TIMx->CCER &= (uint16_t)~ tmp;
+
+  /* Set or reset the CCxE Bit */ 
+  TIMx->CCER |=  (uint16_t)(TIM_CCx << TIM_Channel);
+}
+
+/**
+  * @brief  Enables or disables the TIM Capture Compare Channel xN.
+  * @param  TIMx: where x can be 1 or 8 to select the TIM peripheral.
+  * @param  TIM_Channel: specifies the TIM Channel
+  *          This parameter can be one of the following values:
+  *            @arg TIM_Channel_1: TIM Channel 1
+  *            @arg TIM_Channel_2: TIM Channel 2
+  *            @arg TIM_Channel_3: TIM Channel 3
+  * @param  TIM_CCxN: specifies the TIM Channel CCxNE bit new state.
+  *          This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. 
+  * @retval None
+  */
+void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN)
+{
+  uint16_t tmp = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel));
+  assert_param(IS_TIM_CCXN(TIM_CCxN));
+
+  tmp = CCER_CCNE_SET << TIM_Channel;
+
+  /* Reset the CCxNE Bit */
+  TIMx->CCER &= (uint16_t) ~tmp;
+
+  /* Set or reset the CCxNE Bit */ 
+  TIMx->CCER |=  (uint16_t)(TIM_CCxN << TIM_Channel);
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group3 Input Capture management functions
+ *  @brief    Input Capture management functions 
+ *
+@verbatim   
+ ===============================================================================
+                  ##### Input Capture management functions #####
+ ===============================================================================  
+         
+            ##### TIM Driver: how to use it in Input Capture Mode #####
+ ===============================================================================
+    [..]    
+    To use the Timer in Input Capture mode, the following steps are mandatory:
+       
+      (#) Enable TIM clock using RCC_APBxPeriphClockCmd(RCC_APBxPeriph_TIMx, ENABLE) 
+          function
+       
+      (#) Configure the TIM pins by configuring the corresponding GPIO pins
+       
+      (#) Configure the Time base unit as described in the first part of this driver,
+          if needed, else the Timer will run with the default configuration:
+        (++) Autoreload value = 0xFFFF
+        (++) Prescaler value = 0x0000
+        (++) Counter mode = Up counting
+        (++) Clock Division = TIM_CKD_DIV1
+          
+      (#) Fill the TIM_ICInitStruct with the desired parameters including:
+        (++) TIM Channel: TIM_Channel
+        (++) TIM Input Capture polarity: TIM_ICPolarity
+        (++) TIM Input Capture selection: TIM_ICSelection
+        (++) TIM Input Capture Prescaler: TIM_ICPrescaler
+        (++) TIM Input CApture filter value: TIM_ICFilter
+       
+      (#) Call TIM_ICInit(TIMx, &TIM_ICInitStruct) to configure the desired channel 
+          with the corresponding configuration and to measure only frequency 
+          or duty cycle of the input signal, or, Call TIM_PWMIConfig(TIMx, &TIM_ICInitStruct) 
+          to configure the desired channels with the corresponding configuration 
+          and to measure the frequency and the duty cycle of the input signal
+          
+      (#) Enable the NVIC or the DMA to read the measured frequency. 
+          
+      (#) Enable the corresponding interrupt (or DMA request) to read the Captured 
+          value, using the function TIM_ITConfig(TIMx, TIM_IT_CCx) 
+          (or TIM_DMA_Cmd(TIMx, TIM_DMA_CCx)) 
+       
+      (#) Call the TIM_Cmd(ENABLE) function to enable the TIM counter.
+       
+      (#) Use TIM_GetCapturex(TIMx); to read the captured value.
+       
+      -@- All other functions can be used separately to modify, if needed,
+          a specific feature of the Timer. 
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Initializes the TIM peripheral according to the specified parameters
+  *         in the TIM_ICInitStruct.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure that contains
+  *         the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity));
+  assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler));
+  assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter));
+  
+  if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+  {
+    /* TI1 Configuration */
+    TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2)
+  {
+    /* TI2 Configuration */
+    assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+    TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3)
+  {
+    /* TI3 Configuration */
+    assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+    TI3_Config(TIMx,  TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else
+  {
+    /* TI4 Configuration */
+    assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+    TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity,
+               TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+}
+
+/**
+  * @brief  Fills each TIM_ICInitStruct member with its default value.
+  * @param  TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+  /* Set the default configuration */
+  TIM_ICInitStruct->TIM_Channel = TIM_Channel_1;
+  TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising;
+  TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI;
+  TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1;
+  TIM_ICInitStruct->TIM_ICFilter = 0x00;
+}
+
+/**
+  * @brief  Configures the TIM peripheral according to the specified parameters
+  *         in the TIM_ICInitStruct to measure an external PWM signal.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5,8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure that contains
+  *         the configuration information for the specified TIM peripheral.
+  * @retval None
+  */
+void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct)
+{
+  uint16_t icoppositepolarity = TIM_ICPolarity_Rising;
+  uint16_t icoppositeselection = TIM_ICSelection_DirectTI;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+
+  /* Select the Opposite Input Polarity */
+  if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising)
+  {
+    icoppositepolarity = TIM_ICPolarity_Falling;
+  }
+  else
+  {
+    icoppositepolarity = TIM_ICPolarity_Rising;
+  }
+  /* Select the Opposite Input */
+  if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI)
+  {
+    icoppositeselection = TIM_ICSelection_IndirectTI;
+  }
+  else
+  {
+    icoppositeselection = TIM_ICSelection_DirectTI;
+  }
+  if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1)
+  {
+    /* TI1 Configuration */
+    TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+    /* TI2 Configuration */
+    TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+  else
+  { 
+    /* TI2 Configuration */
+    TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection,
+               TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+    /* TI1 Configuration */
+    TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter);
+    /* Set the Input Capture Prescaler value */
+    TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler);
+  }
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 1 value.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @retval Capture Compare 1 Register value.
+  */
+uint32_t TIM_GetCapture1(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+
+  /* Get the Capture 1 Register value */
+  return TIMx->CCR1;
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 2 value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @retval Capture Compare 2 Register value.
+  */
+uint32_t TIM_GetCapture2(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+
+  /* Get the Capture 2 Register value */
+  return TIMx->CCR2;
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 3 value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @retval Capture Compare 3 Register value.
+  */
+uint32_t TIM_GetCapture3(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx)); 
+
+  /* Get the Capture 3 Register value */
+  return TIMx->CCR3;
+}
+
+/**
+  * @brief  Gets the TIMx Input Capture 4 value.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @retval Capture Compare 4 Register value.
+  */
+uint32_t TIM_GetCapture4(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+
+  /* Get the Capture 4 Register value */
+  return TIMx->CCR4;
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 1 prescaler.
+  * @param  TIMx: where x can be 1 to 14 except 6 and 7, to select the TIM peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture1 prescaler new value.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPSC_DIV1: no prescaler
+  *            @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *            @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *            @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+  /* Reset the IC1PSC Bits */
+  TIMx->CCMR1 &= (uint16_t)~TIM_CCMR1_IC1PSC;
+
+  /* Set the IC1PSC value */
+  TIMx->CCMR1 |= TIM_ICPSC;
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 2 prescaler.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture2 prescaler new value.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPSC_DIV1: no prescaler
+  *            @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *            @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *            @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+  /* Reset the IC2PSC Bits */
+  TIMx->CCMR1 &= (uint16_t)~TIM_CCMR1_IC2PSC;
+
+  /* Set the IC2PSC value */
+  TIMx->CCMR1 |= (uint16_t)(TIM_ICPSC << 8);
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 3 prescaler.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture3 prescaler new value.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPSC_DIV1: no prescaler
+  *            @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *            @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *            @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+  /* Reset the IC3PSC Bits */
+  TIMx->CCMR2 &= (uint16_t)~TIM_CCMR2_IC3PSC;
+
+  /* Set the IC3PSC value */
+  TIMx->CCMR2 |= TIM_ICPSC;
+}
+
+/**
+  * @brief  Sets the TIMx Input Capture 4 prescaler.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPSC: specifies the Input Capture4 prescaler new value.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPSC_DIV1: no prescaler
+  *            @arg TIM_ICPSC_DIV2: capture is done once every 2 events
+  *            @arg TIM_ICPSC_DIV4: capture is done once every 4 events
+  *            @arg TIM_ICPSC_DIV8: capture is done once every 8 events
+  * @retval None
+  */
+void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC)
+{  
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC));
+
+  /* Reset the IC4PSC Bits */
+  TIMx->CCMR2 &= (uint16_t)~TIM_CCMR2_IC4PSC;
+
+  /* Set the IC4PSC value */
+  TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8);
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group4 Advanced-control timers (TIM1 and TIM8) specific features
+ *  @brief   Advanced-control timers (TIM1 and TIM8) specific features
+ *
+@verbatim   
+ ===============================================================================
+      ##### Advanced-control timers (TIM1 and TIM8) specific features #####
+ ===============================================================================  
+        
+             ##### TIM Driver: how to use the Break feature #####
+ ===============================================================================
+    [..] 
+    After configuring the Timer channel(s) in the appropriate Output Compare mode: 
+                         
+      (#) Fill the TIM_BDTRInitStruct with the desired parameters for the Timer
+          Break Polarity, dead time, Lock level, the OSSI/OSSR State and the 
+          AOE(automatic output enable).
+               
+      (#) Call TIM_BDTRConfig(TIMx, &TIM_BDTRInitStruct) to configure the Timer
+          
+      (#) Enable the Main Output using TIM_CtrlPWMOutputs(TIM1, ENABLE) 
+          
+      (#) Once the break even occurs, the Timer's output signals are put in reset
+          state or in a known state (according to the configuration made in
+          TIM_BDTRConfig() function).
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the Break feature, dead time, Lock level, OSSI/OSSR State
+  *         and the AOE(automatic output enable).
+  * @param  TIMx: where x can be  1 or 8 to select the TIM 
+  * @param  TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that
+  *         contains the BDTR Register configuration  information for the TIM peripheral.
+  * @retval None
+  */
+void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState));
+  assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState));
+  assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel));
+  assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break));
+  assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity));
+  assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput));
+
+  /* Set the Lock level, the Break enable Bit and the Polarity, the OSSR State,
+     the OSSI State, the dead time value and the Automatic Output Enable Bit */
+  TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState |
+             TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime |
+             TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity |
+             TIM_BDTRInitStruct->TIM_AutomaticOutput;
+}
+
+/**
+  * @brief  Fills each TIM_BDTRInitStruct member with its default value.
+  * @param  TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which
+  *         will be initialized.
+  * @retval None
+  */
+void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct)
+{
+  /* Set the default configuration */
+  TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable;
+  TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable;
+  TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF;
+  TIM_BDTRInitStruct->TIM_DeadTime = 0x00;
+  TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable;
+  TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low;
+  TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable;
+}
+
+/**
+  * @brief  Enables or disables the TIM peripheral Main Outputs.
+  * @param  TIMx: where x can be 1 or 8 to select the TIMx peripheral.
+  * @param  NewState: new state of the TIM peripheral Main Outputs.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the TIM Main Output */
+    TIMx->BDTR |= TIM_BDTR_MOE;
+  }
+  else
+  {
+    /* Disable the TIM Main Output */
+    TIMx->BDTR &= (uint16_t)~TIM_BDTR_MOE;
+  }  
+}
+
+/**
+  * @brief  Selects the TIM peripheral Commutation event.
+  * @param  TIMx: where x can be  1 or 8 to select the TIMx peripheral
+  * @param  NewState: new state of the Commutation event.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Set the COM Bit */
+    TIMx->CR2 |= TIM_CR2_CCUS;
+  }
+  else
+  {
+    /* Reset the COM Bit */
+    TIMx->CR2 &= (uint16_t)~TIM_CR2_CCUS;
+  }
+}
+
+/**
+  * @brief  Sets or Resets the TIM peripheral Capture Compare Preload Control bit.
+  * @param  TIMx: where x can be  1 or 8 to select the TIMx peripheral
+  * @param  NewState: new state of the Capture Compare Preload Control bit
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST4_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Set the CCPC Bit */
+    TIMx->CR2 |= TIM_CR2_CCPC;
+  }
+  else
+  {
+    /* Reset the CCPC Bit */
+    TIMx->CR2 &= (uint16_t)~TIM_CR2_CCPC;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group5 Interrupts DMA and flags management functions
+ *  @brief    Interrupts, DMA and flags management functions 
+ *
+@verbatim   
+ ===============================================================================
+          ##### Interrupts, DMA and flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified TIM interrupts.
+  * @param  TIMx: where x can be 1 to 14 to select the TIMx peripheral.
+  * @param  TIM_IT: specifies the TIM interrupts sources to be enabled or disabled.
+  *          This parameter can be any combination of the following values:
+  *            @arg TIM_IT_Update: TIM update Interrupt source
+  *            @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+  *            @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+  *            @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+  *            @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+  *            @arg TIM_IT_COM: TIM Commutation Interrupt source
+  *            @arg TIM_IT_Trigger: TIM Trigger Interrupt source
+  *            @arg TIM_IT_Break: TIM Break Interrupt source
+  *  
+  * @note   For TIM6 and TIM7 only the parameter TIM_IT_Update can be used
+  * @note   For TIM9 and TIM12 only one of the following parameters can be used: TIM_IT_Update,
+  *          TIM_IT_CC1, TIM_IT_CC2 or TIM_IT_Trigger. 
+  * @note   For TIM10, TIM11, TIM13 and TIM14 only one of the following parameters can
+  *          be used: TIM_IT_Update or TIM_IT_CC1   
+  * @note   TIM_IT_COM and TIM_IT_Break can be used only with TIM1 and TIM8 
+  *        
+  * @param  NewState: new state of the TIM interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState)
+{  
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_IT(TIM_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the Interrupt sources */
+    TIMx->DIER |= TIM_IT;
+  }
+  else
+  {
+    /* Disable the Interrupt sources */
+    TIMx->DIER &= (uint16_t)~TIM_IT;
+  }
+}
+
+/**
+  * @brief  Configures the TIMx event to be generate by software.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  TIM_EventSource: specifies the event source.
+  *          This parameter can be one or more of the following values:	   
+  *            @arg TIM_EventSource_Update: Timer update Event source
+  *            @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source
+  *            @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source
+  *            @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source
+  *            @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source
+  *            @arg TIM_EventSource_COM: Timer COM event source  
+  *            @arg TIM_EventSource_Trigger: Timer Trigger Event source
+  *            @arg TIM_EventSource_Break: Timer Break event source
+  * 
+  * @note   TIM6 and TIM7 can only generate an update event. 
+  * @note   TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8.
+  *        
+  * @retval None
+  */
+void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource)
+{ 
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource));
+ 
+  /* Set the event sources */
+  TIMx->EGR = TIM_EventSource;
+}
+
+/**
+  * @brief  Checks whether the specified TIM flag is set or not.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  TIM_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_FLAG_Update: TIM update Flag
+  *            @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+  *            @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+  *            @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+  *            @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+  *            @arg TIM_FLAG_COM: TIM Commutation Flag
+  *            @arg TIM_FLAG_Trigger: TIM Trigger Flag
+  *            @arg TIM_FLAG_Break: TIM Break Flag
+  *            @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 over capture Flag
+  *            @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 over capture Flag
+  *            @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 over capture Flag
+  *            @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 over capture Flag
+  *
+  * @note   TIM6 and TIM7 can have only one update flag. 
+  * @note   TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8.    
+  *
+  * @retval The new state of TIM_FLAG (SET or RESET).
+  */
+FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG)
+{ 
+  ITStatus bitstatus = RESET;  
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_GET_FLAG(TIM_FLAG));
+
+  
+  if ((TIMx->SR & TIM_FLAG) != (uint16_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the TIMx's pending flags.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  TIM_FLAG: specifies the flag bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg TIM_FLAG_Update: TIM update Flag
+  *            @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag
+  *            @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag
+  *            @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag
+  *            @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag
+  *            @arg TIM_FLAG_COM: TIM Commutation Flag
+  *            @arg TIM_FLAG_Trigger: TIM Trigger Flag
+  *            @arg TIM_FLAG_Break: TIM Break Flag
+  *            @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 over capture Flag
+  *            @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 over capture Flag
+  *            @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 over capture Flag
+  *            @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 over capture Flag
+  *
+  * @note   TIM6 and TIM7 can have only one update flag. 
+  * @note   TIM_FLAG_COM and TIM_FLAG_Break are used only with TIM1 and TIM8.
+  *    
+  * @retval None
+  */
+void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG)
+{  
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+   
+  /* Clear the flags */
+  TIMx->SR = (uint16_t)~TIM_FLAG;
+}
+
+/**
+  * @brief  Checks whether the TIM interrupt has occurred or not.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  TIM_IT: specifies the TIM interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_IT_Update: TIM update Interrupt source
+  *            @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+  *            @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+  *            @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+  *            @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+  *            @arg TIM_IT_COM: TIM Commutation Interrupt source
+  *            @arg TIM_IT_Trigger: TIM Trigger Interrupt source
+  *            @arg TIM_IT_Break: TIM Break Interrupt source
+  *
+  * @note   TIM6 and TIM7 can generate only an update interrupt.
+  * @note   TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8.
+  *     
+  * @retval The new state of the TIM_IT(SET or RESET).
+  */
+ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT)
+{
+  ITStatus bitstatus = RESET;  
+  uint16_t itstatus = 0x0, itenable = 0x0;
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+  assert_param(IS_TIM_GET_IT(TIM_IT));
+   
+  itstatus = TIMx->SR & TIM_IT;
+  
+  itenable = TIMx->DIER & TIM_IT;
+  if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the TIMx's interrupt pending bits.
+  * @param  TIMx: where x can be 1 to 14 to select the TIM peripheral.
+  * @param  TIM_IT: specifies the pending bit to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg TIM_IT_Update: TIM1 update Interrupt source
+  *            @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source
+  *            @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source
+  *            @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source
+  *            @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source
+  *            @arg TIM_IT_COM: TIM Commutation Interrupt source
+  *            @arg TIM_IT_Trigger: TIM Trigger Interrupt source
+  *            @arg TIM_IT_Break: TIM Break Interrupt source
+  *
+  * @note   TIM6 and TIM7 can generate only an update interrupt.
+  * @note   TIM_IT_COM and TIM_IT_Break are used only with TIM1 and TIM8.
+  *      
+  * @retval None
+  */
+void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_ALL_PERIPH(TIMx));
+
+  /* Clear the IT pending Bit */
+  TIMx->SR = (uint16_t)~TIM_IT;
+}
+
+/**
+  * @brief  Configures the TIMx's DMA interface.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_DMABase: DMA Base address.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_DMABase_CR1  
+  *            @arg TIM_DMABase_CR2
+  *            @arg TIM_DMABase_SMCR
+  *            @arg TIM_DMABase_DIER
+  *            @arg TIM1_DMABase_SR
+  *            @arg TIM_DMABase_EGR
+  *            @arg TIM_DMABase_CCMR1
+  *            @arg TIM_DMABase_CCMR2
+  *            @arg TIM_DMABase_CCER
+  *            @arg TIM_DMABase_CNT   
+  *            @arg TIM_DMABase_PSC   
+  *            @arg TIM_DMABase_ARR
+  *            @arg TIM_DMABase_RCR
+  *            @arg TIM_DMABase_CCR1
+  *            @arg TIM_DMABase_CCR2
+  *            @arg TIM_DMABase_CCR3  
+  *            @arg TIM_DMABase_CCR4
+  *            @arg TIM_DMABase_BDTR
+  *            @arg TIM_DMABase_DCR
+  * @param  TIM_DMABurstLength: DMA Burst length. This parameter can be one value
+  *         between: TIM_DMABurstLength_1Transfer and TIM_DMABurstLength_18Transfers.
+  * @retval None
+  */
+void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_DMA_BASE(TIM_DMABase)); 
+  assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength));
+
+  /* Set the DMA Base and the DMA Burst Length */
+  TIMx->DCR = TIM_DMABase | TIM_DMABurstLength;
+}
+
+/**
+  * @brief  Enables or disables the TIMx's DMA Requests.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the TIM peripheral.
+  * @param  TIM_DMASource: specifies the DMA Request sources.
+  *          This parameter can be any combination of the following values:
+  *            @arg TIM_DMA_Update: TIM update Interrupt source
+  *            @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source
+  *            @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source
+  *            @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source
+  *            @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source
+  *            @arg TIM_DMA_COM: TIM Commutation DMA source
+  *            @arg TIM_DMA_Trigger: TIM Trigger DMA source
+  * @param  NewState: new state of the DMA Request sources.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState)
+{ 
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST5_PERIPH(TIMx)); 
+  assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the DMA sources */
+    TIMx->DIER |= TIM_DMASource; 
+  }
+  else
+  {
+    /* Disable the DMA sources */
+    TIMx->DIER &= (uint16_t)~TIM_DMASource;
+  }
+}
+
+/**
+  * @brief  Selects the TIMx peripheral Capture Compare DMA source.
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  NewState: new state of the Capture Compare DMA source
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Set the CCDS Bit */
+    TIMx->CR2 |= TIM_CR2_CCDS;
+  }
+  else
+  {
+    /* Reset the CCDS Bit */
+    TIMx->CR2 &= (uint16_t)~TIM_CR2_CCDS;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group6 Clocks management functions
+ *  @brief    Clocks management functions
+ *
+@verbatim   
+ ===============================================================================
+                  ##### Clocks management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the TIMx internal Clock
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @retval None
+  */
+void TIM_InternalClockConfig(TIM_TypeDef* TIMx)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+
+  /* Disable slave mode to clock the prescaler directly with the internal clock */
+  TIMx->SMCR &=  (uint16_t)~TIM_SMCR_SMS;
+}
+
+/**
+  * @brief  Configures the TIMx Internal Trigger as External Clock
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_InputTriggerSource: Trigger source.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_TS_ITR0: Internal Trigger 0
+  *            @arg TIM_TS_ITR1: Internal Trigger 1
+  *            @arg TIM_TS_ITR2: Internal Trigger 2
+  *            @arg TIM_TS_ITR3: Internal Trigger 3
+  * @retval None
+  */
+void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource));
+
+  /* Select the Internal Trigger */
+  TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource);
+
+  /* Select the External clock mode1 */
+  TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+
+/**
+  * @brief  Configures the TIMx Trigger as External Clock
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13 or 14  
+  *         to select the TIM peripheral.
+  * @param  TIM_TIxExternalCLKSource: Trigger source.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector
+  *            @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1
+  *            @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2
+  * @param  TIM_ICPolarity: specifies the TIx Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPolarity_Rising
+  *            @arg TIM_ICPolarity_Falling
+  * @param  ICFilter: specifies the filter value.
+  *          This parameter must be a value between 0x0 and 0xF.
+  * @retval None
+  */
+void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource,
+                                uint16_t TIM_ICPolarity, uint16_t ICFilter)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx));
+  assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity));
+  assert_param(IS_TIM_IC_FILTER(ICFilter));
+
+  /* Configure the Timer Input Clock Source */
+  if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2)
+  {
+    TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+  }
+  else
+  {
+    TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter);
+  }
+  /* Select the Trigger source */
+  TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource);
+  /* Select the External clock mode1 */
+  TIMx->SMCR |= TIM_SlaveMode_External1;
+}
+
+/**
+  * @brief  Configures the External clock Mode1
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF.
+  *            @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2.
+  *            @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4.
+  *            @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8.
+  * @param  TIM_ExtTRGPolarity: The external Trigger Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active.
+  *            @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active.
+  * @param  ExtTRGFilter: External Trigger Filter.
+  *          This parameter must be a value between 0x00 and 0x0F
+  * @retval None
+  */
+void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler,
+                            uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter)
+{
+  uint16_t tmpsmcr = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+  assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+  assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+  /* Configure the ETR Clock source */
+  TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+  
+  /* Get the TIMx SMCR register value */
+  tmpsmcr = TIMx->SMCR;
+
+  /* Reset the SMS Bits */
+  tmpsmcr &= (uint16_t)~TIM_SMCR_SMS;
+
+  /* Select the External clock mode1 */
+  tmpsmcr |= TIM_SlaveMode_External1;
+
+  /* Select the Trigger selection : ETRF */
+  tmpsmcr &= (uint16_t)~TIM_SMCR_TS;
+  tmpsmcr |= TIM_TS_ETRF;
+
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+}
+
+/**
+  * @brief  Configures the External clock Mode2
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF.
+  *            @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2.
+  *            @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4.
+  *            @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8.
+  * @param  TIM_ExtTRGPolarity: The external Trigger Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active.
+  *            @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active.
+  * @param  ExtTRGFilter: External Trigger Filter.
+  *          This parameter must be a value between 0x00 and 0x0F
+  * @retval None
+  */
+void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, 
+                             uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+  assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+  assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+  /* Configure the ETR Clock source */
+  TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter);
+
+  /* Enable the External clock mode2 */
+  TIMx->SMCR |= TIM_SMCR_ECE;
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group7 Synchronization management functions
+ *  @brief    Synchronization management functions 
+ *
+@verbatim   
+ ===============================================================================
+                ##### Synchronization management functions #####
+ ===============================================================================  
+                         
+          ##### TIM Driver: how to use it in synchronization Mode #####
+ ===============================================================================
+    [..] 
+    
+    *** Case of two/several Timers ***
+    ==================================
+    [..]
+      (#) Configure the Master Timers using the following functions:
+        (++) void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); 
+        (++) void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode);  
+      (#) Configure the Slave Timers using the following functions: 
+        (++) void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource);  
+        (++) void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); 
+          
+    *** Case of Timers and external trigger(ETR pin) ***
+    ====================================================
+    [..]           
+      (#) Configure the External trigger using this function:
+        (++) void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity,
+                               uint16_t ExtTRGFilter);
+      (#) Configure the Slave Timers using the following functions: 
+        (++) void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource);  
+        (++) void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); 
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Selects the Input Trigger source
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13 or 14  
+  *         to select the TIM peripheral.
+  * @param  TIM_InputTriggerSource: The Input Trigger source.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_TS_ITR0: Internal Trigger 0
+  *            @arg TIM_TS_ITR1: Internal Trigger 1
+  *            @arg TIM_TS_ITR2: Internal Trigger 2
+  *            @arg TIM_TS_ITR3: Internal Trigger 3
+  *            @arg TIM_TS_TI1F_ED: TI1 Edge Detector
+  *            @arg TIM_TS_TI1FP1: Filtered Timer Input 1
+  *            @arg TIM_TS_TI2FP2: Filtered Timer Input 2
+  *            @arg TIM_TS_ETRF: External Trigger input
+  * @retval None
+  */
+void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource)
+{
+  uint16_t tmpsmcr = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST1_PERIPH(TIMx)); 
+  assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource));
+
+  /* Get the TIMx SMCR register value */
+  tmpsmcr = TIMx->SMCR;
+
+  /* Reset the TS Bits */
+  tmpsmcr &= (uint16_t)~TIM_SMCR_TS;
+
+  /* Set the Input Trigger source */
+  tmpsmcr |= TIM_InputTriggerSource;
+
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+}
+
+/**
+  * @brief  Selects the TIMx Trigger Output Mode.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the TIM peripheral.
+  *     
+  * @param  TIM_TRGOSource: specifies the Trigger Output source.
+  *   This parameter can be one of the following values:
+  *
+  *  - For all TIMx
+  *            @arg TIM_TRGOSource_Reset:  The UG bit in the TIM_EGR register is used as the trigger output(TRGO)
+  *            @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output(TRGO)
+  *            @arg TIM_TRGOSource_Update: The update event is selected as the trigger output(TRGO)
+  *
+  *  - For all TIMx except TIM6 and TIM7
+  *            @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag
+  *                                     is to be set, as soon as a capture or compare match occurs(TRGO)
+  *            @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output(TRGO)
+  *            @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output(TRGO)
+  *            @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output(TRGO)
+  *            @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output(TRGO)
+  *
+  * @retval None
+  */
+void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST5_PERIPH(TIMx));
+  assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource));
+
+  /* Reset the MMS Bits */
+  TIMx->CR2 &= (uint16_t)~TIM_CR2_MMS;
+  /* Select the TRGO source */
+  TIMx->CR2 |=  TIM_TRGOSource;
+}
+
+/**
+  * @brief  Selects the TIMx Slave Mode.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM peripheral.
+  * @param  TIM_SlaveMode: specifies the Timer Slave Mode.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal(TRGI) reinitialize 
+  *                                      the counter and triggers an update of the registers
+  *            @arg TIM_SlaveMode_Gated:     The counter clock is enabled when the trigger signal (TRGI) is high
+  *            @arg TIM_SlaveMode_Trigger:   The counter starts at a rising edge of the trigger TRGI
+  *            @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter
+  * @retval None
+  */
+void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode));
+
+  /* Reset the SMS Bits */
+  TIMx->SMCR &= (uint16_t)~TIM_SMCR_SMS;
+
+  /* Select the Slave Mode */
+  TIMx->SMCR |= TIM_SlaveMode;
+}
+
+/**
+  * @brief  Sets or Resets the TIMx Master/Slave Mode.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM peripheral.
+  * @param  TIM_MasterSlaveMode: specifies the Timer Master Slave Mode.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer
+  *                                             and its slaves (through TRGO)
+  *            @arg TIM_MasterSlaveMode_Disable: No action
+  * @retval None
+  */
+void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode));
+
+  /* Reset the MSM Bit */
+  TIMx->SMCR &= (uint16_t)~TIM_SMCR_MSM;
+  
+  /* Set or Reset the MSM Bit */
+  TIMx->SMCR |= TIM_MasterSlaveMode;
+}
+
+/**
+  * @brief  Configures the TIMx External Trigger (ETR).
+  * @param  TIMx: where x can be  1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ExtTRGPrescaler: The external Trigger Prescaler.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF.
+  *            @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2.
+  *            @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4.
+  *            @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8.
+  * @param  TIM_ExtTRGPolarity: The external Trigger Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active.
+  *            @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active.
+  * @param  ExtTRGFilter: External Trigger Filter.
+  *          This parameter must be a value between 0x00 and 0x0F
+  * @retval None
+  */
+void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler,
+                   uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter)
+{
+  uint16_t tmpsmcr = 0;
+
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST3_PERIPH(TIMx));
+  assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler));
+  assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity));
+  assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter));
+
+  tmpsmcr = TIMx->SMCR;
+
+  /* Reset the ETR Bits */
+  tmpsmcr &= SMCR_ETR_MASK;
+
+  /* Set the Prescaler, the Filter value and the Polarity */
+  tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8)));
+
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group8 Specific interface management functions
+ *  @brief    Specific interface management functions 
+ *
+@verbatim   
+ ===============================================================================
+            ##### Specific interface management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the TIMx Encoder Interface.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_EncoderMode: specifies the TIMx Encoder Mode.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level.
+  *            @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level.
+  *            @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending
+  *                                       on the level of the other input.
+  * @param  TIM_IC1Polarity: specifies the IC1 Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPolarity_Falling: IC Falling edge.
+  *            @arg TIM_ICPolarity_Rising: IC Rising edge.
+  * @param  TIM_IC2Polarity: specifies the IC2 Polarity
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPolarity_Falling: IC Falling edge.
+  *            @arg TIM_ICPolarity_Rising: IC Rising edge.
+  * @retval None
+  */
+void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode,
+                                uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity)
+{
+  uint16_t tmpsmcr = 0;
+  uint16_t tmpccmr1 = 0;
+  uint16_t tmpccer = 0;
+    
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode));
+  assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity));
+  assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity));
+
+  /* Get the TIMx SMCR register value */
+  tmpsmcr = TIMx->SMCR;
+
+  /* Get the TIMx CCMR1 register value */
+  tmpccmr1 = TIMx->CCMR1;
+
+  /* Get the TIMx CCER register value */
+  tmpccer = TIMx->CCER;
+
+  /* Set the encoder Mode */
+  tmpsmcr &= (uint16_t)~TIM_SMCR_SMS;
+  tmpsmcr |= TIM_EncoderMode;
+
+  /* Select the Capture Compare 1 and the Capture Compare 2 as input */
+  tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR1_CC2S);
+  tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0;
+
+  /* Set the TI1 and the TI2 Polarities */
+  tmpccer &= ((uint16_t)~TIM_CCER_CC1P) & ((uint16_t)~TIM_CCER_CC2P);
+  tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4));
+
+  /* Write to TIMx SMCR */
+  TIMx->SMCR = tmpsmcr;
+
+  /* Write to TIMx CCMR1 */
+  TIMx->CCMR1 = tmpccmr1;
+
+  /* Write to TIMx CCER */
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Enables or disables the TIMx's Hall sensor interface.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  NewState: new state of the TIMx Hall sensor interface.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_TIM_LIST2_PERIPH(TIMx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  if (NewState != DISABLE)
+  {
+    /* Set the TI1S Bit */
+    TIMx->CR2 |= TIM_CR2_TI1S;
+  }
+  else
+  {
+    /* Reset the TI1S Bit */
+    TIMx->CR2 &= (uint16_t)~TIM_CR2_TI1S;
+  }
+}
+/**
+  * @}
+  */
+
+/** @defgroup TIM_Group9 Specific remapping management function
+ *  @brief   Specific remapping management function
+ *
+@verbatim   
+ ===============================================================================
+              ##### Specific remapping management function #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the TIM2, TIM5 and TIM11 Remapping input capabilities.
+  * @param  TIMx: where x can be 2, 5 or 11 to select the TIM peripheral.
+  * @param  TIM_Remap: specifies the TIM input remapping source.
+  *          This parameter can be one of the following values:
+  *            @arg TIM2_TIM8_TRGO: TIM2 ITR1 input is connected to TIM8 Trigger output(default)
+  *            @arg TIM2_ETH_PTP:   TIM2 ITR1 input is connected to ETH PTP trogger output.
+  *            @arg TIM2_USBFS_SOF: TIM2 ITR1 input is connected to USB FS SOF. 
+  *            @arg TIM2_USBHS_SOF: TIM2 ITR1 input is connected to USB HS SOF. 
+  *            @arg TIM5_GPIO:      TIM5 CH4 input is connected to dedicated Timer pin(default)
+  *            @arg TIM5_LSI:       TIM5 CH4 input is connected to LSI clock.
+  *            @arg TIM5_LSE:       TIM5 CH4 input is connected to LSE clock.
+  *            @arg TIM5_RTC:       TIM5 CH4 input is connected to RTC Output event.
+  *            @arg TIM11_GPIO:     TIM11 CH4 input is connected to dedicated Timer pin(default) 
+  *            @arg TIM11_HSE:      TIM11 CH4 input is connected to HSE_RTC clock
+  *                                 (HSE divided by a programmable prescaler)  
+  * @retval None
+  */
+void TIM_RemapConfig(TIM_TypeDef* TIMx, uint16_t TIM_Remap)
+{
+ /* Check the parameters */
+  assert_param(IS_TIM_LIST6_PERIPH(TIMx));
+  assert_param(IS_TIM_REMAP(TIM_Remap));
+
+  /* Set the Timer remapping configuration */
+  TIMx->OR =  TIM_Remap;
+}
+/**
+  * @}
+  */
+
+/**
+  * @brief  Configure the TI1 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13 or 14 
+  *         to select the TIM peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPolarity_Rising
+  *            @arg TIM_ICPolarity_Falling
+  *            @arg TIM_ICPolarity_BothEdge  
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1.
+  *            @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2.
+  *            @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *          This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr1 = 0, tmpccer = 0;
+
+  /* Disable the Channel 1: Reset the CC1E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC1E;
+  tmpccmr1 = TIMx->CCMR1;
+  tmpccer = TIMx->CCER;
+
+  /* Select the Input and set the filter */
+  tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR1_IC1F);
+  tmpccmr1 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4));
+
+  /* Select the Polarity and set the CC1E Bit */
+  tmpccer &= (uint16_t)~(TIM_CCER_CC1P | TIM_CCER_CC1NP);
+  tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E);
+
+  /* Write to TIMx CCMR1 and CCER registers */
+  TIMx->CCMR1 = tmpccmr1;
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configure the TI2 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5, 8, 9 or 12 to select the TIM 
+  *         peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPolarity_Rising
+  *            @arg TIM_ICPolarity_Falling
+  *            @arg TIM_ICPolarity_BothEdge   
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2.
+  *            @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1.
+  *            @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *          This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr1 = 0, tmpccer = 0, tmp = 0;
+
+  /* Disable the Channel 2: Reset the CC2E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC2E;
+  tmpccmr1 = TIMx->CCMR1;
+  tmpccer = TIMx->CCER;
+  tmp = (uint16_t)(TIM_ICPolarity << 4);
+
+  /* Select the Input and set the filter */
+  tmpccmr1 &= ((uint16_t)~TIM_CCMR1_CC2S) & ((uint16_t)~TIM_CCMR1_IC2F);
+  tmpccmr1 |= (uint16_t)(TIM_ICFilter << 12);
+  tmpccmr1 |= (uint16_t)(TIM_ICSelection << 8);
+
+  /* Select the Polarity and set the CC2E Bit */
+  tmpccer &= (uint16_t)~(TIM_CCER_CC2P | TIM_CCER_CC2NP);
+  tmpccer |=  (uint16_t)(tmp | (uint16_t)TIM_CCER_CC2E);
+
+  /* Write to TIMx CCMR1 and CCER registers */
+  TIMx->CCMR1 = tmpccmr1 ;
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configure the TI3 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPolarity_Rising
+  *            @arg TIM_ICPolarity_Falling
+  *            @arg TIM_ICPolarity_BothEdge         
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3.
+  *            @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4.
+  *            @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *          This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+
+  /* Disable the Channel 3: Reset the CC3E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC3E;
+  tmpccmr2 = TIMx->CCMR2;
+  tmpccer = TIMx->CCER;
+  tmp = (uint16_t)(TIM_ICPolarity << 8);
+
+  /* Select the Input and set the filter */
+  tmpccmr2 &= ((uint16_t)~TIM_CCMR1_CC1S) & ((uint16_t)~TIM_CCMR2_IC3F);
+  tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4));
+
+  /* Select the Polarity and set the CC3E Bit */
+  tmpccer &= (uint16_t)~(TIM_CCER_CC3P | TIM_CCER_CC3NP);
+  tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC3E);
+
+  /* Write to TIMx CCMR2 and CCER registers */
+  TIMx->CCMR2 = tmpccmr2;
+  TIMx->CCER = tmpccer;
+}
+
+/**
+  * @brief  Configure the TI4 as Input.
+  * @param  TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral.
+  * @param  TIM_ICPolarity : The Input Polarity.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICPolarity_Rising
+  *            @arg TIM_ICPolarity_Falling
+  *            @arg TIM_ICPolarity_BothEdge     
+  * @param  TIM_ICSelection: specifies the input to be used.
+  *          This parameter can be one of the following values:
+  *            @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4.
+  *            @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3.
+  *            @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC.
+  * @param  TIM_ICFilter: Specifies the Input Capture Filter.
+  *          This parameter must be a value between 0x00 and 0x0F.
+  * @retval None
+  */
+static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection,
+                       uint16_t TIM_ICFilter)
+{
+  uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0;
+
+  /* Disable the Channel 4: Reset the CC4E Bit */
+  TIMx->CCER &= (uint16_t)~TIM_CCER_CC4E;
+  tmpccmr2 = TIMx->CCMR2;
+  tmpccer = TIMx->CCER;
+  tmp = (uint16_t)(TIM_ICPolarity << 12);
+
+  /* Select the Input and set the filter */
+  tmpccmr2 &= ((uint16_t)~TIM_CCMR1_CC2S) & ((uint16_t)~TIM_CCMR1_IC2F);
+  tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8);
+  tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12);
+
+  /* Select the Polarity and set the CC4E Bit */
+  tmpccer &= (uint16_t)~(TIM_CCER_CC4P | TIM_CCER_CC4NP);
+  tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC4E);
+
+  /* Write to TIMx CCMR2 and CCER registers */
+  TIMx->CCMR2 = tmpccmr2;
+  TIMx->CCER = tmpccer ;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c
new file mode 100644
index 0000000000000000000000000000000000000000..f786c942c69f734caae3482b17ec9c9f47b43caa
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c
@@ -0,0 +1,1486 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_usart.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Universal synchronous asynchronous receiver
+  *          transmitter (USART):           
+  *           + Initialization and Configuration
+  *           + Data transfers
+  *           + Multi-Processor Communication
+  *           + LIN mode
+  *           + Half-duplex mode
+  *           + Smartcard mode
+  *           + IrDA mode
+  *           + DMA transfers management
+  *           + Interrupts and flags management 
+  *           
+  @verbatim       
+ ===============================================================================
+                        ##### How to use this driver #####
+ ===============================================================================
+    [..]
+      (#) Enable peripheral clock using the following functions
+          RCC_APB2PeriphClockCmd(RCC_APB2Periph_USARTx, ENABLE) for USART1 and USART6 
+          RCC_APB1PeriphClockCmd(RCC_APB1Periph_USARTx, ENABLE) for USART2, USART3, 
+          UART4 or UART5.
+  
+      (#) According to the USART mode, enable the GPIO clocks using 
+          RCC_AHB1PeriphClockCmd() function. (The I/O can be TX, RX, CTS, 
+          or/and SCLK). 
+  
+      (#) Peripheral's alternate function: 
+        (++) Connect the pin to the desired peripherals' Alternate 
+            Function (AF) using GPIO_PinAFConfig() function
+        (++) Configure the desired pin in alternate function by:
+            GPIO_InitStruct->GPIO_Mode = GPIO_Mode_AF
+        (++) Select the type, pull-up/pull-down and output speed via 
+            GPIO_PuPd, GPIO_OType and GPIO_Speed members
+        (++) Call GPIO_Init() function
+          
+      (#) Program the Baud Rate, Word Length , Stop Bit, Parity, Hardware 
+          flow control and Mode(Receiver/Transmitter) using the USART_Init()
+          function.
+  
+      (#) For synchronous mode, enable the clock and program the polarity,
+          phase and last bit using the USART_ClockInit() function.
+  
+      (#) Enable the NVIC and the corresponding interrupt using the function 
+         USART_ITConfig() if you need to use interrupt mode. 
+  
+      (#) When using the DMA mode 
+        (++) Configure the DMA using DMA_Init() function
+        (++) Active the needed channel Request using USART_DMACmd() function
+   
+      (#) Enable the USART using the USART_Cmd() function.
+   
+      (#) Enable the DMA using the DMA_Cmd() function, when using DMA mode. 
+    
+      -@- Refer to Multi-Processor, LIN, half-duplex, Smartcard, IrDA sub-sections
+          for more details
+    
+    [..]        
+    In order to reach higher communication baudrates, it is possible to
+    enable the oversampling by 8 mode using the function USART_OverSampling8Cmd().
+    This function should be called after enabling the USART clock (RCC_APBxPeriphClockCmd())
+    and before calling the function USART_Init().
+            
+    @endverbatim        
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************  
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_usart.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup USART 
+  * @brief USART driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/*!< USART CR1 register clear Mask ((~(uint16_t)0xE9F3)) */
+#define CR1_CLEAR_MASK            ((uint16_t)(USART_CR1_M | USART_CR1_PCE | \
+                                              USART_CR1_PS | USART_CR1_TE | \
+                                              USART_CR1_RE))
+
+/*!< USART CR2 register clock bits clear Mask ((~(uint16_t)0xF0FF)) */
+#define CR2_CLOCK_CLEAR_MASK      ((uint16_t)(USART_CR2_CLKEN | USART_CR2_CPOL | \
+                                              USART_CR2_CPHA | USART_CR2_LBCL))
+
+/*!< USART CR3 register clear Mask ((~(uint16_t)0xFCFF)) */
+#define CR3_CLEAR_MASK            ((uint16_t)(USART_CR3_RTSE | USART_CR3_CTSE))
+
+/*!< USART Interrupts mask */
+#define IT_MASK                   ((uint16_t)0x001F)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup USART_Private_Functions
+  * @{
+  */
+
+/** @defgroup USART_Group1 Initialization and Configuration functions
+ *  @brief   Initialization and Configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+            ##### Initialization and Configuration functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to initialize the USART 
+    in asynchronous and in synchronous modes.
+      (+) For the asynchronous mode only these parameters can be configured: 
+        (++) Baud Rate
+        (++) Word Length 
+        (++) Stop Bit
+        (++) Parity: If the parity is enabled, then the MSB bit of the data written
+             in the data register is transmitted but is changed by the parity bit.
+             Depending on the frame length defined by the M bit (8-bits or 9-bits),
+             the possible USART frame formats are as listed in the following table:
+   +-------------------------------------------------------------+     
+   |   M bit |  PCE bit  |            USART frame                |
+   |---------------------|---------------------------------------|             
+   |    0    |    0      |    | SB | 8 bit data | STB |          |
+   |---------|-----------|---------------------------------------|  
+   |    0    |    1      |    | SB | 7 bit data | PB | STB |     |
+   |---------|-----------|---------------------------------------|  
+   |    1    |    0      |    | SB | 9 bit data | STB |          |
+   |---------|-----------|---------------------------------------|  
+   |    1    |    1      |    | SB | 8 bit data | PB | STB |     |
+   +-------------------------------------------------------------+            
+        (++) Hardware flow control
+        (++) Receiver/transmitter modes
+
+    [..]
+    The USART_Init() function follows the USART  asynchronous configuration 
+    procedure (details for the procedure are available in reference manual (RM0090)).
+
+     (+) For the synchronous mode in addition to the asynchronous mode parameters these 
+         parameters should be also configured:
+        (++) USART Clock Enabled
+        (++) USART polarity
+        (++) USART phase
+        (++) USART LastBit
+  
+    [..]
+    These parameters can be configured using the USART_ClockInit() function.
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Deinitializes the USARTx peripheral registers to their default reset values.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @retval None
+  */
+void USART_DeInit(USART_TypeDef* USARTx)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+
+  if (USARTx == USART1)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE);
+  }
+  else if (USARTx == USART2)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE);
+  }
+  else if (USARTx == USART3)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE);
+  }    
+  else if (USARTx == UART4)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE);
+  }
+  else if (USARTx == UART5)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE);
+  }  
+  else if (USARTx == USART6)
+  {
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART6, ENABLE);
+    RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART6, DISABLE);
+  }
+  else if (USARTx == UART7)
+  {
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART7, ENABLE);
+    RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART7, DISABLE);
+  }     
+  else
+  {
+    if (USARTx == UART8)
+    { 
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART8, ENABLE);
+      RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART8, DISABLE);
+    }
+  }
+}
+
+/**
+  * @brief  Initializes the USARTx peripheral according to the specified
+  *         parameters in the USART_InitStruct .
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_InitStruct: pointer to a USART_InitTypeDef structure that contains
+  *         the configuration information for the specified USART peripheral.
+  * @retval None
+  */
+void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct)
+{
+  uint32_t tmpreg = 0x00, apbclock = 0x00;
+  uint32_t integerdivider = 0x00;
+  uint32_t fractionaldivider = 0x00;
+  RCC_ClocksTypeDef RCC_ClocksStatus;
+
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate));  
+  assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength));
+  assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits));
+  assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity));
+  assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode));
+  assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl));
+
+  /* The hardware flow control is available only for USART1, USART2, USART3 and USART6 */
+  if (USART_InitStruct->USART_HardwareFlowControl != USART_HardwareFlowControl_None)
+  {
+    assert_param(IS_USART_1236_PERIPH(USARTx));
+  }
+
+/*---------------------------- USART CR2 Configuration -----------------------*/
+  tmpreg = USARTx->CR2;
+
+  /* Clear STOP[13:12] bits */
+  tmpreg &= (uint32_t)~((uint32_t)USART_CR2_STOP);
+
+  /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit :
+      Set STOP[13:12] bits according to USART_StopBits value */
+  tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits;
+  
+  /* Write to USART CR2 */
+  USARTx->CR2 = (uint16_t)tmpreg;
+
+/*---------------------------- USART CR1 Configuration -----------------------*/
+  tmpreg = USARTx->CR1;
+
+  /* Clear M, PCE, PS, TE and RE bits */
+  tmpreg &= (uint32_t)~((uint32_t)CR1_CLEAR_MASK);
+
+  /* Configure the USART Word Length, Parity and mode: 
+     Set the M bits according to USART_WordLength value 
+     Set PCE and PS bits according to USART_Parity value
+     Set TE and RE bits according to USART_Mode value */
+  tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity |
+            USART_InitStruct->USART_Mode;
+
+  /* Write to USART CR1 */
+  USARTx->CR1 = (uint16_t)tmpreg;
+
+/*---------------------------- USART CR3 Configuration -----------------------*/  
+  tmpreg = USARTx->CR3;
+
+  /* Clear CTSE and RTSE bits */
+  tmpreg &= (uint32_t)~((uint32_t)CR3_CLEAR_MASK);
+
+  /* Configure the USART HFC : 
+      Set CTSE and RTSE bits according to USART_HardwareFlowControl value */
+  tmpreg |= USART_InitStruct->USART_HardwareFlowControl;
+
+  /* Write to USART CR3 */
+  USARTx->CR3 = (uint16_t)tmpreg;
+
+/*---------------------------- USART BRR Configuration -----------------------*/
+  /* Configure the USART Baud Rate */
+  RCC_GetClocksFreq(&RCC_ClocksStatus);
+
+  if ((USARTx == USART1) || (USARTx == USART6))
+  {
+    apbclock = RCC_ClocksStatus.PCLK2_Frequency;
+  }
+  else
+  {
+    apbclock = RCC_ClocksStatus.PCLK1_Frequency;
+  }
+  
+  /* Determine the integer part */
+  if ((USARTx->CR1 & USART_CR1_OVER8) != 0)
+  {
+    /* Integer part computing in case Oversampling mode is 8 Samples */
+    integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->USART_BaudRate)));    
+  }
+  else /* if ((USARTx->CR1 & USART_CR1_OVER8) == 0) */
+  {
+    /* Integer part computing in case Oversampling mode is 16 Samples */
+    integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->USART_BaudRate)));    
+  }
+  tmpreg = (integerdivider / 100) << 4;
+
+  /* Determine the fractional part */
+  fractionaldivider = integerdivider - (100 * (tmpreg >> 4));
+
+  /* Implement the fractional part in the register */
+  if ((USARTx->CR1 & USART_CR1_OVER8) != 0)
+  {
+    tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07);
+  }
+  else /* if ((USARTx->CR1 & USART_CR1_OVER8) == 0) */
+  {
+    tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F);
+  }
+  
+  /* Write to USART BRR register */
+  USARTx->BRR = (uint16_t)tmpreg;
+}
+
+/**
+  * @brief  Fills each USART_InitStruct member with its default value.
+  * @param  USART_InitStruct: pointer to a USART_InitTypeDef structure which will
+  *         be initialized.
+  * @retval None
+  */
+void USART_StructInit(USART_InitTypeDef* USART_InitStruct)
+{
+  /* USART_InitStruct members default value */
+  USART_InitStruct->USART_BaudRate = 9600;
+  USART_InitStruct->USART_WordLength = USART_WordLength_8b;
+  USART_InitStruct->USART_StopBits = USART_StopBits_1;
+  USART_InitStruct->USART_Parity = USART_Parity_No ;
+  USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx;
+  USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None;  
+}
+
+/**
+  * @brief  Initializes the USARTx peripheral Clock according to the 
+  *         specified parameters in the USART_ClockInitStruct .
+  * @param  USARTx: where x can be 1, 2, 3 or 6 to select the USART peripheral.
+  * @param  USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef structure that
+  *         contains the configuration information for the specified  USART peripheral.
+  * @note   The Smart Card and Synchronous modes are not available for UART4 and UART5.    
+  * @retval None
+  */
+void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+  uint32_t tmpreg = 0x00;
+  /* Check the parameters */
+  assert_param(IS_USART_1236_PERIPH(USARTx));
+  assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock));
+  assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL));
+  assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA));
+  assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit));
+  
+/*---------------------------- USART CR2 Configuration -----------------------*/
+  tmpreg = USARTx->CR2;
+  /* Clear CLKEN, CPOL, CPHA and LBCL bits */
+  tmpreg &= (uint32_t)~((uint32_t)CR2_CLOCK_CLEAR_MASK);
+  /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/
+  /* Set CLKEN bit according to USART_Clock value */
+  /* Set CPOL bit according to USART_CPOL value */
+  /* Set CPHA bit according to USART_CPHA value */
+  /* Set LBCL bit according to USART_LastBit value */
+  tmpreg |= (uint32_t)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | 
+                 USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit;
+  /* Write to USART CR2 */
+  USARTx->CR2 = (uint16_t)tmpreg;
+}
+
+/**
+  * @brief  Fills each USART_ClockInitStruct member with its default value.
+  * @param  USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef structure
+  *         which will be initialized.
+  * @retval None
+  */
+void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct)
+{
+  /* USART_ClockInitStruct members default value */
+  USART_ClockInitStruct->USART_Clock = USART_Clock_Disable;
+  USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low;
+  USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge;
+  USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable;
+}
+
+/**
+  * @brief  Enables or disables the specified USART peripheral.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the USARTx peripheral.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the selected USART by setting the UE bit in the CR1 register */
+    USARTx->CR1 |= USART_CR1_UE;
+  }
+  else
+  {
+    /* Disable the selected USART by clearing the UE bit in the CR1 register */
+    USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_UE);
+  }
+}
+
+/**
+  * @brief  Sets the system clock prescaler.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_Prescaler: specifies the prescaler clock. 
+  * @note   The function is used for IrDA mode with UART4 and UART5.   
+  * @retval None
+  */
+void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler)
+{ 
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  
+  /* Clear the USART prescaler */
+  USARTx->GTPR &= USART_GTPR_GT;
+  /* Set the USART prescaler */
+  USARTx->GTPR |= USART_Prescaler;
+}
+
+/**
+  * @brief  Enables or disables the USART's 8x oversampling mode.
+  * @note   This function has to be called before calling USART_Init() function
+  *         in order to have correct baudrate Divider value.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the USART 8x oversampling mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the 8x Oversampling mode by setting the OVER8 bit in the CR1 register */
+    USARTx->CR1 |= USART_CR1_OVER8;
+  }
+  else
+  {
+    /* Disable the 8x Oversampling mode by clearing the OVER8 bit in the CR1 register */
+    USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_OVER8);
+  }
+}  
+
+/**
+  * @brief  Enables or disables the USART's one bit sampling method.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the USART one bit sampling method.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the one bit method by setting the ONEBITE bit in the CR3 register */
+    USARTx->CR3 |= USART_CR3_ONEBIT;
+  }
+  else
+  {
+    /* Disable the one bit method by clearing the ONEBITE bit in the CR3 register */
+    USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Group2 Data transfers functions
+ *  @brief   Data transfers functions 
+ *
+@verbatim   
+ ===============================================================================
+                      ##### Data transfers functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to manage the USART data 
+    transfers.
+    [..]
+    During an USART reception, data shifts in least significant bit first through 
+    the RX pin. In this mode, the USART_DR register consists of a buffer (RDR) 
+    between the internal bus and the received shift register.
+    [..]
+    When a transmission is taking place, a write instruction to the USART_DR register 
+    stores the data in the TDR register and which is copied in the shift register 
+    at the end of the current transmission.
+    [..]
+    The read access of the USART_DR register can be done using the USART_ReceiveData()
+    function and returns the RDR buffered value. Whereas a write access to the USART_DR 
+    can be done using USART_SendData() function and stores the written data into 
+    TDR buffer.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Transmits single data through the USARTx peripheral.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  Data: the data to transmit.
+  * @retval None
+  */
+void USART_SendData(USART_TypeDef* USARTx, uint16_t Data)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_DATA(Data)); 
+    
+  /* Transmit Data */
+  USARTx->DR = (Data & (uint16_t)0x01FF);
+}
+
+/**
+  * @brief  Returns the most recent received data by the USARTx peripheral.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @retval The received data.
+  */
+uint16_t USART_ReceiveData(USART_TypeDef* USARTx)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  
+  /* Receive Data */
+  return (uint16_t)(USARTx->DR & (uint16_t)0x01FF);
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Group3 MultiProcessor Communication functions
+ *  @brief   Multi-Processor Communication functions 
+ *
+@verbatim   
+ ===============================================================================
+              ##### Multi-Processor Communication functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to manage the USART 
+    multiprocessor communication.
+    [..]
+    For instance one of the USARTs can be the master, its TX output is connected 
+    to the RX input of the other USART. The others are slaves, their respective 
+    TX outputs are logically ANDed together and connected to the RX input of the 
+    master.
+    [..]
+    USART multiprocessor communication is possible through the following procedure:
+      (#) Program the Baud rate, Word length = 9 bits, Stop bits, Parity, Mode 
+          transmitter or Mode receiver and hardware flow control values using 
+          the USART_Init() function.
+      (#) Configures the USART address using the USART_SetAddress() function.
+      (#) Configures the wake up method (USART_WakeUp_IdleLine or USART_WakeUp_AddressMark)
+          using USART_WakeUpConfig() function only for the slaves.
+      (#) Enable the USART using the USART_Cmd() function.
+      (#) Enter the USART slaves in mute mode using USART_ReceiverWakeUpCmd() function.
+    [..]
+    The USART Slave exit from mute mode when receive the wake up condition.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Sets the address of the USART node.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_Address: Indicates the address of the USART node.
+  * @retval None
+  */
+void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_ADDRESS(USART_Address)); 
+    
+  /* Clear the USART address */
+  USARTx->CR2 &= (uint16_t)~((uint16_t)USART_CR2_ADD);
+  /* Set the USART address node */
+  USARTx->CR2 |= USART_Address;
+}
+
+/**
+  * @brief  Determines if the USART is in mute mode or not.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the USART mute mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState)); 
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the USART mute mode  by setting the RWU bit in the CR1 register */
+    USARTx->CR1 |= USART_CR1_RWU;
+  }
+  else
+  {
+    /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */
+    USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_RWU);
+  }
+}
+/**
+  * @brief  Selects the USART WakeUp method.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_WakeUp: specifies the USART wakeup method.
+  *          This parameter can be one of the following values:
+  *            @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection
+  *            @arg USART_WakeUp_AddressMark: WakeUp by an address mark
+  * @retval None
+  */
+void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_WAKEUP(USART_WakeUp));
+  
+  USARTx->CR1 &= (uint16_t)~((uint16_t)USART_CR1_WAKE);
+  USARTx->CR1 |= USART_WakeUp;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Group4 LIN mode functions
+ *  @brief   LIN mode functions 
+ *
+@verbatim   
+ ===============================================================================
+                        ##### LIN mode functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to manage the USART LIN 
+    Mode communication.
+    [..]
+    In LIN mode, 8-bit data format with 1 stop bit is required in accordance with 
+    the LIN standard.
+    [..]
+    Only this LIN Feature is supported by the USART IP:
+      (+) LIN Master Synchronous Break send capability and LIN slave break detection
+          capability :  13-bit break generation and 10/11 bit break detection
+
+    [..]
+    USART LIN Master transmitter communication is possible through the following 
+    procedure:
+      (#) Program the Baud rate, Word length = 8bits, Stop bits = 1bit, Parity, 
+        Mode transmitter or Mode receiver and hardware flow control values using 
+        the USART_Init() function.
+      (#) Enable the USART using the USART_Cmd() function.
+      (#) Enable the LIN mode using the USART_LINCmd() function.
+      (#) Send the break character using USART_SendBreak() function.
+    [..]
+    USART LIN Master receiver communication is possible through the following procedure:
+      (#) Program the Baud rate, Word length = 8bits, Stop bits = 1bit, Parity, 
+          Mode transmitter or Mode receiver and hardware flow control values using 
+          the USART_Init() function.
+      (#) Enable the USART using the USART_Cmd() function.
+      (#) Configures the break detection length using the USART_LINBreakDetectLengthConfig()
+          function.
+      (#) Enable the LIN mode using the USART_LINCmd() function.
+
+      -@- In LIN mode, the following bits must be kept cleared:
+       (+@) CLKEN in the USART_CR2 register,
+       (+@) STOP[1:0], SCEN, HDSEL and IREN in the USART_CR3 register.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Sets the USART LIN Break detection length.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_LINBreakDetectLength: specifies the LIN break detection length.
+  *          This parameter can be one of the following values:
+  *            @arg USART_LINBreakDetectLength_10b: 10-bit break detection
+  *            @arg USART_LINBreakDetectLength_11b: 11-bit break detection
+  * @retval None
+  */
+void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength));
+  
+  USARTx->CR2 &= (uint16_t)~((uint16_t)USART_CR2_LBDL);
+  USARTx->CR2 |= USART_LINBreakDetectLength;  
+}
+
+/**
+  * @brief  Enables or disables the USART's LIN mode.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the USART LIN mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the LIN mode by setting the LINEN bit in the CR2 register */
+    USARTx->CR2 |= USART_CR2_LINEN;
+  }
+  else
+  {
+    /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */
+    USARTx->CR2 &= (uint16_t)~((uint16_t)USART_CR2_LINEN);
+  }
+}
+
+/**
+  * @brief  Transmits break characters.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @retval None
+  */
+void USART_SendBreak(USART_TypeDef* USARTx)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  
+  /* Send break characters */
+  USARTx->CR1 |= USART_CR1_SBK;
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Group5 Halfduplex mode function
+ *  @brief   Half-duplex mode function 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### Half-duplex mode function #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to manage the USART 
+    Half-duplex communication.
+    [..]
+    The USART can be configured to follow a single-wire half-duplex protocol where 
+    the TX and RX lines are internally connected.
+    [..]
+    USART Half duplex communication is possible through the following procedure:
+      (#) Program the Baud rate, Word length, Stop bits, Parity, Mode transmitter 
+          or Mode receiver and hardware flow control values using the USART_Init()
+          function.
+      (#) Configures the USART address using the USART_SetAddress() function.
+      (#) Enable the USART using the USART_Cmd() function.
+      (#) Enable the half duplex mode using USART_HalfDuplexCmd() function.
+
+
+    -@- The RX pin is no longer used
+    -@- In Half-duplex mode the following bits must be kept cleared:
+      (+@) LINEN and CLKEN bits in the USART_CR2 register.
+      (+@) SCEN and IREN bits in the USART_CR3 register.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the USART's Half Duplex communication.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the USART Communication.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  
+  if (NewState != DISABLE)
+  {
+    /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */
+    USARTx->CR3 |= USART_CR3_HDSEL;
+  }
+  else
+  {
+    /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */
+    USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_HDSEL);
+  }
+}
+
+/**
+  * @}
+  */
+
+
+/** @defgroup USART_Group6 Smartcard mode functions
+ *  @brief   Smartcard mode functions 
+ *
+@verbatim   
+ ===============================================================================
+                              ##### Smartcard mode functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to manage the USART 
+    Smartcard communication.
+    [..]
+    The Smartcard interface is designed to support asynchronous protocol Smartcards as
+    defined in the ISO 7816-3 standard.
+    [..]
+    The USART can provide a clock to the smartcard through the SCLK output.
+    In smartcard mode, SCLK is not associated to the communication but is simply derived 
+    from the internal peripheral input clock through a 5-bit prescaler.
+    [..]
+    Smartcard communication is possible through the following procedure:
+      (#) Configures the Smartcard Prescaler using the USART_SetPrescaler() function.
+      (#) Configures the Smartcard Guard Time using the USART_SetGuardTime() function.
+      (#) Program the USART clock using the USART_ClockInit() function as following:
+        (++) USART Clock enabled
+        (++) USART CPOL Low
+        (++) USART CPHA on first edge
+        (++) USART Last Bit Clock Enabled
+      (#) Program the Smartcard interface using the USART_Init() function as following:
+        (++) Word Length = 9 Bits
+        (++) 1.5 Stop Bit
+        (++) Even parity
+        (++) BaudRate = 12096 baud
+        (++) Hardware flow control disabled (RTS and CTS signals)
+        (++) Tx and Rx enabled
+      (#) POptionally you can enable the parity error interrupt using the USART_ITConfig()
+          function
+      (#) PEnable the USART using the USART_Cmd() function.
+      (#) PEnable the Smartcard NACK using the USART_SmartCardNACKCmd() function.
+      (#) PEnable the Smartcard interface using the USART_SmartCardCmd() function.
+
+    Please refer to the ISO 7816-3 specification for more details.
+
+      -@- It is also possible to choose 0.5 stop bit for receiving but it is recommended 
+          to use 1.5 stop bits for both transmitting and receiving to avoid switching 
+          between the two configurations.
+      -@- In smartcard mode, the following bits must be kept cleared:
+        (+@) LINEN bit in the USART_CR2 register.
+        (+@) HDSEL and IREN bits in the USART_CR3 register.
+      -@- Smartcard mode is available on USART peripherals only (not available on UART4 
+          and UART5 peripherals).
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Sets the specified USART guard time.
+  * @param  USARTx: where x can be 1, 2, 3 or 6 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_GuardTime: specifies the guard time.   
+  * @retval None
+  */
+void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime)
+{    
+  /* Check the parameters */
+  assert_param(IS_USART_1236_PERIPH(USARTx));
+  
+  /* Clear the USART Guard time */
+  USARTx->GTPR &= USART_GTPR_PSC;
+  /* Set the USART guard time */
+  USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08);
+}
+
+/**
+  * @brief  Enables or disables the USART's Smart Card mode.
+  * @param  USARTx: where x can be 1, 2, 3 or 6 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the Smart Card mode.
+  *          This parameter can be: ENABLE or DISABLE.      
+  * @retval None
+  */
+void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_1236_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the SC mode by setting the SCEN bit in the CR3 register */
+    USARTx->CR3 |= USART_CR3_SCEN;
+  }
+  else
+  {
+    /* Disable the SC mode by clearing the SCEN bit in the CR3 register */
+    USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_SCEN);
+  }
+}
+
+/**
+  * @brief  Enables or disables NACK transmission.
+  * @param  USARTx: where x can be 1, 2, 3 or 6 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the NACK transmission.
+  *          This parameter can be: ENABLE or DISABLE.  
+  * @retval None
+  */
+void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_1236_PERIPH(USARTx)); 
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+  if (NewState != DISABLE)
+  {
+    /* Enable the NACK transmission by setting the NACK bit in the CR3 register */
+    USARTx->CR3 |= USART_CR3_NACK;
+  }
+  else
+  {
+    /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */
+    USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_NACK);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Group7 IrDA mode functions
+ *  @brief   IrDA mode functions 
+ *
+@verbatim   
+ ===============================================================================
+                        ##### IrDA mode functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to manage the USART 
+    IrDA communication.
+    [..]
+    IrDA is a half duplex communication protocol. If the Transmitter is busy, any data
+    on the IrDA receive line will be ignored by the IrDA decoder and if the Receiver 
+    is busy, data on the TX from the USART to IrDA will not be encoded by IrDA.
+    While receiving data, transmission should be avoided as the data to be transmitted
+    could be corrupted.
+    [..]
+    IrDA communication is possible through the following procedure:
+      (#) Program the Baud rate, Word length = 8 bits, Stop bits, Parity, Transmitter/Receiver 
+          modes and hardware flow control values using the USART_Init() function.
+      (#) Enable the USART using the USART_Cmd() function.
+      (#) Configures the IrDA pulse width by configuring the prescaler using  
+          the USART_SetPrescaler() function.
+      (#) Configures the IrDA  USART_IrDAMode_LowPower or USART_IrDAMode_Normal mode
+          using the USART_IrDAConfig() function.
+      (#) Enable the IrDA using the USART_IrDACmd() function.
+
+      -@- A pulse of width less than two and greater than one PSC period(s) may or may
+          not be rejected.
+      -@- The receiver set up time should be managed by software. The IrDA physical layer
+          specification specifies a minimum of 10 ms delay between transmission and 
+          reception (IrDA is a half duplex protocol).
+      -@- In IrDA mode, the following bits must be kept cleared:
+        (+@) LINEN, STOP and CLKEN bits in the USART_CR2 register.
+        (+@) SCEN and HDSEL bits in the USART_CR3 register.
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Configures the USART's IrDA interface.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_IrDAMode: specifies the IrDA mode.
+  *          This parameter can be one of the following values:
+  *            @arg USART_IrDAMode_LowPower
+  *            @arg USART_IrDAMode_Normal
+  * @retval None
+  */
+void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_IRDA_MODE(USART_IrDAMode));
+    
+  USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_IRLP);
+  USARTx->CR3 |= USART_IrDAMode;
+}
+
+/**
+  * @brief  Enables or disables the USART's IrDA interface.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  NewState: new state of the IrDA mode.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+    
+  if (NewState != DISABLE)
+  {
+    /* Enable the IrDA mode by setting the IREN bit in the CR3 register */
+    USARTx->CR3 |= USART_CR3_IREN;
+  }
+  else
+  {
+    /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */
+    USARTx->CR3 &= (uint16_t)~((uint16_t)USART_CR3_IREN);
+  }
+}
+
+/**
+  * @}
+  */
+
+/** @defgroup USART_Group8 DMA transfers management functions
+ *  @brief   DMA transfers management functions
+ *
+@verbatim   
+ ===============================================================================
+              ##### DMA transfers management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+  
+/**
+  * @brief  Enables or disables the USART's DMA interface.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_DMAReq: specifies the DMA request.
+  *          This parameter can be any combination of the following values:
+  *            @arg USART_DMAReq_Tx: USART DMA transmit request
+  *            @arg USART_DMAReq_Rx: USART DMA receive request
+  * @param  NewState: new state of the DMA Request sources.
+  *          This parameter can be: ENABLE or DISABLE.   
+  * @retval None
+  */
+void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_DMAREQ(USART_DMAReq));  
+  assert_param(IS_FUNCTIONAL_STATE(NewState)); 
+
+  if (NewState != DISABLE)
+  {
+    /* Enable the DMA transfer for selected requests by setting the DMAT and/or
+       DMAR bits in the USART CR3 register */
+    USARTx->CR3 |= USART_DMAReq;
+  }
+  else
+  {
+    /* Disable the DMA transfer for selected requests by clearing the DMAT and/or
+       DMAR bits in the USART CR3 register */
+    USARTx->CR3 &= (uint16_t)~USART_DMAReq;
+  }
+}
+
+/**
+  * @}
+  */
+  
+/** @defgroup USART_Group9 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions 
+ *
+@verbatim   
+ ===============================================================================
+            ##### Interrupts and flags management functions #####
+ ===============================================================================  
+    [..]
+    This subsection provides a set of functions allowing to configure the USART 
+    Interrupts sources, DMA channels requests and check or clear the flags or 
+    pending bits status.
+    The user should identify which mode will be used in his application to manage 
+    the communication: Polling mode, Interrupt mode or DMA mode. 
+    
+    *** Polling Mode ***
+    ====================
+    [..]
+    In Polling Mode, the SPI communication can be managed by 10 flags:
+      (#) USART_FLAG_TXE : to indicate the status of the transmit buffer register
+      (#) USART_FLAG_RXNE : to indicate the status of the receive buffer register
+      (#) USART_FLAG_TC : to indicate the status of the transmit operation
+      (#) USART_FLAG_IDLE : to indicate the status of the Idle Line             
+      (#) USART_FLAG_CTS : to indicate the status of the nCTS input
+      (#) USART_FLAG_LBD : to indicate the status of the LIN break detection
+      (#) USART_FLAG_NE : to indicate if a noise error occur
+      (#) USART_FLAG_FE : to indicate if a frame error occur
+      (#) USART_FLAG_PE : to indicate if a parity error occur
+      (#) USART_FLAG_ORE : to indicate if an Overrun error occur
+    [..]
+    In this Mode it is advised to use the following functions:
+      (+) FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG);
+      (+) void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG);
+
+    *** Interrupt Mode ***
+    ======================
+    [..]
+    In Interrupt Mode, the USART communication can be managed by 8 interrupt sources
+    and 10 pending bits: 
+
+      (#) Pending Bits:
+
+        (##) USART_IT_TXE : to indicate the status of the transmit buffer register
+        (##) USART_IT_RXNE : to indicate the status of the receive buffer register
+        (##) USART_IT_TC : to indicate the status of the transmit operation
+        (##) USART_IT_IDLE : to indicate the status of the Idle Line             
+        (##) USART_IT_CTS : to indicate the status of the nCTS input
+        (##) USART_IT_LBD : to indicate the status of the LIN break detection
+        (##) USART_IT_NE : to indicate if a noise error occur
+        (##) USART_IT_FE : to indicate if a frame error occur
+        (##) USART_IT_PE : to indicate if a parity error occur
+        (##) USART_IT_ORE : to indicate if an Overrun error occur
+
+      (#) Interrupt Source:
+
+        (##) USART_IT_TXE : specifies the interrupt source for the Tx buffer empty 
+                            interrupt. 
+        (##) USART_IT_RXNE : specifies the interrupt source for the Rx buffer not 
+                             empty interrupt.
+        (##) USART_IT_TC : specifies the interrupt source for the Transmit complete 
+                           interrupt. 
+        (##) USART_IT_IDLE : specifies the interrupt source for the Idle Line interrupt.             
+        (##) USART_IT_CTS : specifies the interrupt source for the CTS interrupt. 
+        (##) USART_IT_LBD : specifies the interrupt source for the LIN break detection
+                            interrupt. 
+        (##) USART_IT_PE : specifies the interrupt source for the parity error interrupt. 
+        (##) USART_IT_ERR :  specifies the interrupt source for the errors interrupt.
+
+      -@@- Some parameters are coded in order to use them as interrupt source 
+          or as pending bits.
+    [..]
+    In this Mode it is advised to use the following functions:
+      (+) void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState);
+      (+) ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT);
+      (+) void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT);
+
+    *** DMA Mode ***
+    ================
+    [..]
+    In DMA Mode, the USART communication can be managed by 2 DMA Channel requests:
+      (#) USART_DMAReq_Tx: specifies the Tx buffer DMA transfer request
+      (#) USART_DMAReq_Rx: specifies the Rx buffer DMA transfer request
+    [..]
+    In this Mode it is advised to use the following function:
+      (+) void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState);
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables or disables the specified USART interrupts.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_IT: specifies the USART interrupt sources to be enabled or disabled.
+  *          This parameter can be one of the following values:
+  *            @arg USART_IT_CTS:  CTS change interrupt
+  *            @arg USART_IT_LBD:  LIN Break detection interrupt
+  *            @arg USART_IT_TXE:  Transmit Data Register empty interrupt
+  *            @arg USART_IT_TC:   Transmission complete interrupt
+  *            @arg USART_IT_RXNE: Receive Data register not empty interrupt
+  *            @arg USART_IT_IDLE: Idle line detection interrupt
+  *            @arg USART_IT_PE:   Parity Error interrupt
+  *            @arg USART_IT_ERR:  Error interrupt(Frame error, noise error, overrun error)
+  * @param  NewState: new state of the specified USARTx interrupts.
+  *          This parameter can be: ENABLE or DISABLE.
+  * @retval None
+  */
+void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState)
+{
+  uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00;
+  uint32_t usartxbase = 0x00;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_CONFIG_IT(USART_IT));
+  assert_param(IS_FUNCTIONAL_STATE(NewState));
+
+  /* The CTS interrupt is not available for UART4 and UART5 */
+  if (USART_IT == USART_IT_CTS)
+  {
+    assert_param(IS_USART_1236_PERIPH(USARTx));
+  } 
+    
+  usartxbase = (uint32_t)USARTx;
+
+  /* Get the USART register index */
+  usartreg = (((uint8_t)USART_IT) >> 0x05);
+
+  /* Get the interrupt position */
+  itpos = USART_IT & IT_MASK;
+  itmask = (((uint32_t)0x01) << itpos);
+    
+  if (usartreg == 0x01) /* The IT is in CR1 register */
+  {
+    usartxbase += 0x0C;
+  }
+  else if (usartreg == 0x02) /* The IT is in CR2 register */
+  {
+    usartxbase += 0x10;
+  }
+  else /* The IT is in CR3 register */
+  {
+    usartxbase += 0x14; 
+  }
+  if (NewState != DISABLE)
+  {
+    *(__IO uint32_t*)usartxbase  |= itmask;
+  }
+  else
+  {
+    *(__IO uint32_t*)usartxbase &= ~itmask;
+  }
+}
+
+/**
+  * @brief  Checks whether the specified USART flag is set or not.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_FLAG: specifies the flag to check.
+  *          This parameter can be one of the following values:
+  *            @arg USART_FLAG_CTS:  CTS Change flag (not available for UART4 and UART5)
+  *            @arg USART_FLAG_LBD:  LIN Break detection flag
+  *            @arg USART_FLAG_TXE:  Transmit data register empty flag
+  *            @arg USART_FLAG_TC:   Transmission Complete flag
+  *            @arg USART_FLAG_RXNE: Receive data register not empty flag
+  *            @arg USART_FLAG_IDLE: Idle Line detection flag
+  *            @arg USART_FLAG_ORE:  OverRun Error flag
+  *            @arg USART_FLAG_NE:   Noise Error flag
+  *            @arg USART_FLAG_FE:   Framing Error flag
+  *            @arg USART_FLAG_PE:   Parity Error flag
+  * @retval The new state of USART_FLAG (SET or RESET).
+  */
+FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG)
+{
+  FlagStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_FLAG(USART_FLAG));
+
+  /* The CTS flag is not available for UART4 and UART5 */
+  if (USART_FLAG == USART_FLAG_CTS)
+  {
+    assert_param(IS_USART_1236_PERIPH(USARTx));
+  } 
+    
+  if ((USARTx->SR & USART_FLAG) != (uint16_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears the USARTx's pending flags.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_FLAG: specifies the flag to clear.
+  *          This parameter can be any combination of the following values:
+  *            @arg USART_FLAG_CTS:  CTS Change flag (not available for UART4 and UART5).
+  *            @arg USART_FLAG_LBD:  LIN Break detection flag.
+  *            @arg USART_FLAG_TC:   Transmission Complete flag.
+  *            @arg USART_FLAG_RXNE: Receive data register not empty flag.
+  *   
+  * @note   PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun 
+  *          error) and IDLE (Idle line detected) flags are cleared by software 
+  *          sequence: a read operation to USART_SR register (USART_GetFlagStatus()) 
+  *          followed by a read operation to USART_DR register (USART_ReceiveData()).
+  * @note   RXNE flag can be also cleared by a read to the USART_DR register 
+  *          (USART_ReceiveData()).
+  * @note   TC flag can be also cleared by software sequence: a read operation to 
+  *          USART_SR register (USART_GetFlagStatus()) followed by a write operation
+  *          to USART_DR register (USART_SendData()).
+  * @note   TXE flag is cleared only by a write to the USART_DR register 
+  *          (USART_SendData()).
+  *   
+  * @retval None
+  */
+void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG)
+{
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_CLEAR_FLAG(USART_FLAG));
+
+  /* The CTS flag is not available for UART4 and UART5 */
+  if ((USART_FLAG & USART_FLAG_CTS) == USART_FLAG_CTS)
+  {
+    assert_param(IS_USART_1236_PERIPH(USARTx));
+  } 
+       
+  USARTx->SR = (uint16_t)~USART_FLAG;
+}
+
+/**
+  * @brief  Checks whether the specified USART interrupt has occurred or not.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_IT: specifies the USART interrupt source to check.
+  *          This parameter can be one of the following values:
+  *            @arg USART_IT_CTS:  CTS change interrupt (not available for UART4 and UART5)
+  *            @arg USART_IT_LBD:  LIN Break detection interrupt
+  *            @arg USART_IT_TXE:  Transmit Data Register empty interrupt
+  *            @arg USART_IT_TC:   Transmission complete interrupt
+  *            @arg USART_IT_RXNE: Receive Data register not empty interrupt
+  *            @arg USART_IT_IDLE: Idle line detection interrupt
+  *            @arg USART_IT_ORE_RX : OverRun Error interrupt if the RXNEIE bit is set
+  *            @arg USART_IT_ORE_ER : OverRun Error interrupt if the EIE bit is set  
+  *            @arg USART_IT_NE:   Noise Error interrupt
+  *            @arg USART_IT_FE:   Framing Error interrupt
+  *            @arg USART_IT_PE:   Parity Error interrupt
+  * @retval The new state of USART_IT (SET or RESET).
+  */
+ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT)
+{
+  uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00;
+  ITStatus bitstatus = RESET;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_GET_IT(USART_IT)); 
+
+  /* The CTS interrupt is not available for UART4 and UART5 */ 
+  if (USART_IT == USART_IT_CTS)
+  {
+    assert_param(IS_USART_1236_PERIPH(USARTx));
+  } 
+    
+  /* Get the USART register index */
+  usartreg = (((uint8_t)USART_IT) >> 0x05);
+  /* Get the interrupt position */
+  itmask = USART_IT & IT_MASK;
+  itmask = (uint32_t)0x01 << itmask;
+  
+  if (usartreg == 0x01) /* The IT  is in CR1 register */
+  {
+    itmask &= USARTx->CR1;
+  }
+  else if (usartreg == 0x02) /* The IT  is in CR2 register */
+  {
+    itmask &= USARTx->CR2;
+  }
+  else /* The IT  is in CR3 register */
+  {
+    itmask &= USARTx->CR3;
+  }
+  
+  bitpos = USART_IT >> 0x08;
+  bitpos = (uint32_t)0x01 << bitpos;
+  bitpos &= USARTx->SR;
+  if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET))
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  
+  return bitstatus;  
+}
+
+/**
+  * @brief  Clears the USARTx's interrupt pending bits.
+  * @param  USARTx: where x can be 1, 2, 3, 4, 5, 6, 7 or 8 to select the USART or 
+  *         UART peripheral.
+  * @param  USART_IT: specifies the interrupt pending bit to clear.
+  *          This parameter can be one of the following values:
+  *            @arg USART_IT_CTS:  CTS change interrupt (not available for UART4 and UART5)
+  *            @arg USART_IT_LBD:  LIN Break detection interrupt
+  *            @arg USART_IT_TC:   Transmission complete interrupt. 
+  *            @arg USART_IT_RXNE: Receive Data register not empty interrupt.
+  *
+  * @note   PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun 
+  *          error) and IDLE (Idle line detected) pending bits are cleared by 
+  *          software sequence: a read operation to USART_SR register 
+  *          (USART_GetITStatus()) followed by a read operation to USART_DR register 
+  *          (USART_ReceiveData()).
+  * @note   RXNE pending bit can be also cleared by a read to the USART_DR register 
+  *          (USART_ReceiveData()).
+  * @note   TC pending bit can be also cleared by software sequence: a read 
+  *          operation to USART_SR register (USART_GetITStatus()) followed by a write 
+  *          operation to USART_DR register (USART_SendData()).
+  * @note   TXE pending bit is cleared only by a write to the USART_DR register 
+  *          (USART_SendData()).
+  *  
+  * @retval None
+  */
+void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT)
+{
+  uint16_t bitpos = 0x00, itmask = 0x00;
+  /* Check the parameters */
+  assert_param(IS_USART_ALL_PERIPH(USARTx));
+  assert_param(IS_USART_CLEAR_IT(USART_IT)); 
+
+  /* The CTS interrupt is not available for UART4 and UART5 */
+  if (USART_IT == USART_IT_CTS)
+  {
+    assert_param(IS_USART_1236_PERIPH(USARTx));
+  } 
+    
+  bitpos = USART_IT >> 0x08;
+  itmask = ((uint16_t)0x01 << (uint16_t)bitpos);
+  USARTx->SR = (uint16_t)~itmask;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c
new file mode 100644
index 0000000000000000000000000000000000000000..54c221a4efe82124065294eeeee03cb74f016665
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_wwdg.c
@@ -0,0 +1,307 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_wwdg.c
+  * @author  MCD Application Team
+  * @version V1.3.0
+  * @date    08-November-2013
+  * @brief   This file provides firmware functions to manage the following 
+  *          functionalities of the Window watchdog (WWDG) peripheral:           
+  *           + Prescaler, Refresh window and Counter configuration
+  *           + WWDG activation
+  *           + Interrupts and flags management
+  *             
+ @verbatim    
+ ===============================================================================
+                           ##### WWDG features #####
+ ===============================================================================
+    [..]                                      
+        Once enabled the WWDG generates a system reset on expiry of a programmed
+        time period, unless the program refreshes the counter (downcounter) 
+        before to reach 0x3F value (i.e. a reset is generated when the counter
+        value rolls over from 0x40 to 0x3F). 
+        An MCU reset is also generated if the counter value is refreshed
+        before the counter has reached the refresh window value. This 
+        implies that the counter must be refreshed in a limited window.
+              
+        Once enabled the WWDG cannot be disabled except by a system reset.                          
+          
+        WWDGRST flag in RCC_CSR register can be used to inform when a WWDG
+        reset occurs.
+             
+        The WWDG counter input clock is derived from the APB clock divided 
+        by a programmable prescaler.
+                
+        WWDG counter clock = PCLK1 / Prescaler
+        WWDG timeout = (WWDG counter clock) * (counter value)
+                       
+        Min-max timeout value @42 MHz(PCLK1): ~97.5 us / ~49.9 ms
+                             
+                      ##### How to use this driver #####
+ ===============================================================================
+    [..]
+      (#) Enable WWDG clock using RCC_APB1PeriphClockCmd(RCC_APB1Periph_WWDG, ENABLE) function
+              
+      (#) Configure the WWDG prescaler using WWDG_SetPrescaler() function
+                             
+      (#) Configure the WWDG refresh window using WWDG_SetWindowValue() function
+              
+      (#) Set the WWDG counter value and start it using WWDG_Enable() function.
+          When the WWDG is enabled the counter value should be configured to 
+          a value greater than 0x40 to prevent generating an immediate reset.     
+              
+      (#) Optionally you can enable the Early wakeup interrupt which is 
+          generated when the counter reach 0x40.
+          Once enabled this interrupt cannot be disabled except by a system reset.
+                  
+      (#) Then the application program must refresh the WWDG counter at regular
+          intervals during normal operation to prevent an MCU reset, using
+          WWDG_SetCounter() function. This operation must occur only when
+          the counter value is lower than the refresh window value, 
+          programmed using WWDG_SetWindowValue().         
+  
+    @endverbatim                               
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32f4xx_wwdg.h"
+#include "stm32f4xx_rcc.h"
+
+/** @addtogroup STM32F4xx_StdPeriph_Driver
+  * @{
+  */
+
+/** @defgroup WWDG 
+  * @brief WWDG driver modules
+  * @{
+  */
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+
+/* ----------- WWDG registers bit address in the alias region ----------- */
+#define WWDG_OFFSET       (WWDG_BASE - PERIPH_BASE)
+/* Alias word address of EWI bit */
+#define CFR_OFFSET        (WWDG_OFFSET + 0x04)
+#define EWI_BitNumber     0x09
+#define CFR_EWI_BB        (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4))
+
+/* --------------------- WWDG registers bit mask ------------------------ */
+/* CFR register bit mask */
+#define CFR_WDGTB_MASK    ((uint32_t)0xFFFFFE7F)
+#define CFR_W_MASK        ((uint32_t)0xFFFFFF80)
+#define BIT_MASK          ((uint8_t)0x7F)
+
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/** @defgroup WWDG_Private_Functions
+  * @{
+  */
+
+/** @defgroup WWDG_Group1 Prescaler, Refresh window and Counter configuration functions
+ *  @brief   Prescaler, Refresh window and Counter configuration functions 
+ *
+@verbatim   
+ ===============================================================================
+    ##### Prescaler, Refresh window and Counter configuration functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Deinitializes the WWDG peripheral registers to their default reset values.
+  * @param  None
+  * @retval None
+  */
+void WWDG_DeInit(void)
+{
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE);
+  RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE);
+}
+
+/**
+  * @brief  Sets the WWDG Prescaler.
+  * @param  WWDG_Prescaler: specifies the WWDG Prescaler.
+  *   This parameter can be one of the following values:
+  *     @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1
+  *     @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2
+  *     @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4
+  *     @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8
+  * @retval None
+  */
+void WWDG_SetPrescaler(uint32_t WWDG_Prescaler)
+{
+  uint32_t tmpreg = 0;
+  /* Check the parameters */
+  assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler));
+  /* Clear WDGTB[1:0] bits */
+  tmpreg = WWDG->CFR & CFR_WDGTB_MASK;
+  /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */
+  tmpreg |= WWDG_Prescaler;
+  /* Store the new value */
+  WWDG->CFR = tmpreg;
+}
+
+/**
+  * @brief  Sets the WWDG window value.
+  * @param  WindowValue: specifies the window value to be compared to the downcounter.
+  *   This parameter value must be lower than 0x80.
+  * @retval None
+  */
+void WWDG_SetWindowValue(uint8_t WindowValue)
+{
+  __IO uint32_t tmpreg = 0;
+
+  /* Check the parameters */
+  assert_param(IS_WWDG_WINDOW_VALUE(WindowValue));
+  /* Clear W[6:0] bits */
+
+  tmpreg = WWDG->CFR & CFR_W_MASK;
+
+  /* Set W[6:0] bits according to WindowValue value */
+  tmpreg |= WindowValue & (uint32_t) BIT_MASK;
+
+  /* Store the new value */
+  WWDG->CFR = tmpreg;
+}
+
+/**
+  * @brief  Enables the WWDG Early Wakeup interrupt(EWI).
+  * @note   Once enabled this interrupt cannot be disabled except by a system reset.
+  * @param  None
+  * @retval None
+  */
+void WWDG_EnableIT(void)
+{
+  *(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE;
+}
+
+/**
+  * @brief  Sets the WWDG counter value.
+  * @param  Counter: specifies the watchdog counter value.
+  *   This parameter must be a number between 0x40 and 0x7F (to prevent generating
+  *   an immediate reset) 
+  * @retval None
+  */
+void WWDG_SetCounter(uint8_t Counter)
+{
+  /* Check the parameters */
+  assert_param(IS_WWDG_COUNTER(Counter));
+  /* Write to T[6:0] bits to configure the counter value, no need to do
+     a read-modify-write; writing a 0 to WDGA bit does nothing */
+  WWDG->CR = Counter & BIT_MASK;
+}
+/**
+  * @}
+  */
+
+/** @defgroup WWDG_Group2 WWDG activation functions
+ *  @brief   WWDG activation functions 
+ *
+@verbatim   
+ ===============================================================================
+                    ##### WWDG activation function #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Enables WWDG and load the counter value.                  
+  * @param  Counter: specifies the watchdog counter value.
+  *   This parameter must be a number between 0x40 and 0x7F (to prevent generating
+  *   an immediate reset)
+  * @retval None
+  */
+void WWDG_Enable(uint8_t Counter)
+{
+  /* Check the parameters */
+  assert_param(IS_WWDG_COUNTER(Counter));
+  WWDG->CR = WWDG_CR_WDGA | Counter;
+}
+/**
+  * @}
+  */
+
+/** @defgroup WWDG_Group3 Interrupts and flags management functions
+ *  @brief   Interrupts and flags management functions 
+ *
+@verbatim   
+ ===============================================================================
+            ##### Interrupts and flags management functions #####
+ ===============================================================================  
+
+@endverbatim
+  * @{
+  */
+
+/**
+  * @brief  Checks whether the Early Wakeup interrupt flag is set or not.
+  * @param  None
+  * @retval The new state of the Early Wakeup interrupt flag (SET or RESET)
+  */
+FlagStatus WWDG_GetFlagStatus(void)
+{
+  FlagStatus bitstatus = RESET;
+    
+  if ((WWDG->SR) != (uint32_t)RESET)
+  {
+    bitstatus = SET;
+  }
+  else
+  {
+    bitstatus = RESET;
+  }
+  return bitstatus;
+}
+
+/**
+  * @brief  Clears Early Wakeup interrupt flag.
+  * @param  None
+  * @retval None
+  */
+void WWDG_ClearFlag(void)
+{
+  WWDG->SR = (uint32_t)RESET;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_conf_template.h b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_conf_template.h
new file mode 100644
index 0000000000000000000000000000000000000000..b1a20f947ea9885eec53c1874c0f706402e487f6
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_conf_template.h
@@ -0,0 +1,82 @@
+/**
+  ******************************************************************************
+  * @file    usbd_conf_template.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   usb device configuration template file
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CONF__H__
+#define __USBD_CONF__H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_conf.h"
+
+/** @defgroup USB_CONF_Exported_Defines
+  * @{
+  */ 
+#define USE_USB_OTG_HS  
+
+#define USBD_CFG_MAX_NUM           1
+#define USB_MAX_STR_DESC_SIZ       64 
+#define USBD_EP0_MAX_PACKET_SIZE   64
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CONF_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CONF_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+#endif //__USBD_CONF__H__
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_core.h b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_core.h
new file mode 100644
index 0000000000000000000000000000000000000000..ce5659aa214442fea221b02d7b6a64534f3f164e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_core.h
@@ -0,0 +1,121 @@
+/**
+  ******************************************************************************
+  * @file    usbd_core.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   Header file for usbd_core.c
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_CORE_H
+#define __USBD_CORE_H
+
+/* Includes ------------------------------------------------------------------*/
+//#include "usb_dcd.h"
+#include "usb_core.h"
+#include "usbd_def.h"
+#include "usbd_conf.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+  
+/** @defgroup USBD_CORE
+  * @brief This file is the Header file for usbd_core.c file
+  * @{
+  */ 
+
+
+/** @defgroup USBD_CORE_Exported_Defines
+  * @{
+  */ 
+
+typedef enum {
+  USBD_OK   = 0,
+  USBD_BUSY,
+  USBD_FAIL,
+}USBD_Status;
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_CORE_Exported_TypesDefinitions
+  * @{
+  */
+ 
+
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USBD_CORE_Exported_Macros
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_CORE_Exported_Variables
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_CORE_Exported_FunctionsPrototype
+  * @{
+  */ 
+void USBD_Init(USB_OTG_CORE_HANDLE *pdev,
+               USB_OTG_CORE_ID_TypeDef coreID, 
+               USBD_DEVICE *pDevice,                  
+               USBD_Class_cb_TypeDef *class_cb, 
+               USBD_Usr_cb_TypeDef *usr_cb);
+
+USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev);
+
+USBD_Status USBD_ClrCfg(USB_OTG_CORE_HANDLE  *pdev, uint8_t cfgidx);
+
+USBD_Status USBD_SetCfg(USB_OTG_CORE_HANDLE  *pdev, uint8_t cfgidx);
+
+/**
+  * @}
+  */ 
+
+#endif /* __USBD_CORE_H */
+
+/**
+  * @}
+  */ 
+
+/**
+* @}
+*/ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_def.h b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_def.h
new file mode 100644
index 0000000000000000000000000000000000000000..7c0cff76be62a7fd6776d925f33df009542ffdb7
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_def.h
@@ -0,0 +1,156 @@
+/**
+  ******************************************************************************
+  * @file    usbd_def.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   general defines for the usb device library 
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+
+#ifndef __USBD_DEF_H
+#define __USBD_DEF_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_conf.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+  
+/** @defgroup USB_DEF
+  * @brief general defines for the usb device library file
+  * @{
+  */ 
+
+/** @defgroup USB_DEF_Exported_Defines
+  * @{
+  */ 
+
+#ifndef NULL
+#define NULL    0
+#endif
+
+#define  USB_LEN_DEV_QUALIFIER_DESC                     0x0A
+#define  USB_LEN_DEV_DESC                               0x12
+#define  USB_LEN_CFG_DESC                               0x09
+#define  USB_LEN_IF_DESC                                0x09
+#define  USB_LEN_EP_DESC                                0x07
+#define  USB_LEN_OTG_DESC                               0x03
+
+#define  USBD_IDX_LANGID_STR                            0x00 
+#define  USBD_IDX_MFC_STR                               0x01 
+#define  USBD_IDX_PRODUCT_STR                           0x02
+#define  USBD_IDX_SERIAL_STR                            0x03 
+#define  USBD_IDX_CONFIG_STR                            0x04 
+#define  USBD_IDX_INTERFACE_STR                         0x05 
+
+#define  USB_REQ_TYPE_STANDARD                          0x00
+#define  USB_REQ_TYPE_CLASS                             0x20
+#define  USB_REQ_TYPE_VENDOR                            0x40
+#define  USB_REQ_TYPE_MASK                              0x60
+
+#define  USB_REQ_RECIPIENT_DEVICE                       0x00
+#define  USB_REQ_RECIPIENT_INTERFACE                    0x01
+#define  USB_REQ_RECIPIENT_ENDPOINT                     0x02
+#define  USB_REQ_RECIPIENT_MASK                         0x03
+
+#define  USB_REQ_GET_STATUS                             0x00
+#define  USB_REQ_CLEAR_FEATURE                          0x01
+#define  USB_REQ_SET_FEATURE                            0x03
+#define  USB_REQ_SET_ADDRESS                            0x05
+#define  USB_REQ_GET_DESCRIPTOR                         0x06
+#define  USB_REQ_SET_DESCRIPTOR                         0x07
+#define  USB_REQ_GET_CONFIGURATION                      0x08
+#define  USB_REQ_SET_CONFIGURATION                      0x09
+#define  USB_REQ_GET_INTERFACE                          0x0A
+#define  USB_REQ_SET_INTERFACE                          0x0B
+#define  USB_REQ_SYNCH_FRAME                            0x0C
+
+#define  USB_DESC_TYPE_DEVICE                              1
+#define  USB_DESC_TYPE_CONFIGURATION                       2
+#define  USB_DESC_TYPE_STRING                              3
+#define  USB_DESC_TYPE_INTERFACE                           4
+#define  USB_DESC_TYPE_ENDPOINT                            5
+#define  USB_DESC_TYPE_DEVICE_QUALIFIER                    6
+#define  USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION           7
+
+
+#define USB_CONFIG_REMOTE_WAKEUP                           2
+#define USB_CONFIG_SELF_POWERED                            1
+
+#define USB_FEATURE_EP_HALT                                0
+#define USB_FEATURE_REMOTE_WAKEUP                          1
+#define USB_FEATURE_TEST_MODE                              2
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_DEF_Exported_TypesDefinitions
+  * @{
+  */
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USBD_DEF_Exported_Macros
+  * @{
+  */ 
+#define  SWAPBYTE(addr)        (((uint16_t)(*((uint8_t *)(addr)))) + \
+                               (((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8))
+
+#define LOBYTE(x)  ((uint8_t)(x & 0x00FF))
+#define HIBYTE(x)  ((uint8_t)((x & 0xFF00) >>8))
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_DEF_Exported_Variables
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_DEF_Exported_FunctionsPrototype
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+#endif /* __USBD_DEF_H */
+
+/**
+  * @}
+  */ 
+
+/**
+* @}
+*/ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h
new file mode 100644
index 0000000000000000000000000000000000000000..5dc4cbe0c82396c36ce781ca8948ee057d858e6a
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_ioreq.h
@@ -0,0 +1,121 @@
+/**
+  ******************************************************************************
+  * @file    usbd_ioreq.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   header file for the usbd_ioreq.c file
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+
+#ifndef __USBD_IOREQ_H_
+#define __USBD_IOREQ_H_
+
+/* Includes ------------------------------------------------------------------*/
+#include  "usbd_core.h"
+#include  "usbd_def.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+  
+/** @defgroup USBD_IOREQ
+  * @brief header file for the usbd_ioreq.c file
+  * @{
+  */ 
+
+/** @defgroup USBD_IOREQ_Exported_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_IOREQ_Exported_Types
+  * @{
+  */
+
+
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USBD_IOREQ_Exported_Macros
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_IOREQ_Exported_Variables
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_IOREQ_Exported_FunctionsPrototype
+  * @{
+  */ 
+
+USBD_Status  USBD_CtlSendData (USB_OTG_CORE_HANDLE  *pdev, 
+                               uint8_t *buf,
+                               uint16_t len);
+
+USBD_Status  USBD_CtlContinueSendData (USB_OTG_CORE_HANDLE  *pdev, 
+                               uint8_t *pbuf,
+                               uint16_t len);
+
+USBD_Status USBD_CtlPrepareRx (USB_OTG_CORE_HANDLE  *pdev, 
+                               uint8_t *pbuf,                                 
+                               uint16_t len);
+
+USBD_Status  USBD_CtlContinueRx (USB_OTG_CORE_HANDLE  *pdev, 
+                              uint8_t *pbuf,                                          
+                              uint16_t len);
+
+USBD_Status  USBD_CtlSendStatus (USB_OTG_CORE_HANDLE  *pdev);
+
+USBD_Status  USBD_CtlReceiveStatus (USB_OTG_CORE_HANDLE  *pdev);
+
+uint16_t  USBD_GetRxCount (USB_OTG_CORE_HANDLE  *pdev , 
+                           uint8_t epnum);
+
+/**
+  * @}
+  */ 
+
+#endif /* __USBD_IOREQ_H_ */
+
+/**
+  * @}
+  */ 
+
+/**
+* @}
+*/ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_req.h b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_req.h
new file mode 100644
index 0000000000000000000000000000000000000000..f88416df3ad8897f3773b76b4abed97d02bceeee
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_req.h
@@ -0,0 +1,108 @@
+/**
+  ******************************************************************************
+  * @file    usbd_req.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   header file for the usbd_req.c file
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+
+#ifndef __USB_REQUEST_H_
+#define __USB_REQUEST_H_
+
+/* Includes ------------------------------------------------------------------*/
+#include  "usbd_def.h"
+#include  "usbd_core.h"
+#include  "usbd_conf.h"
+
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+  
+/** @defgroup USBD_REQ
+  * @brief header file for the usbd_ioreq.c file
+  * @{
+  */ 
+
+/** @defgroup USBD_REQ_Exported_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_REQ_Exported_Types
+  * @{
+  */
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USBD_REQ_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_REQ_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_REQ_Exported_FunctionsPrototype
+  * @{
+  */ 
+
+USBD_Status  USBD_StdDevReq (USB_OTG_CORE_HANDLE  *pdev, USB_SETUP_REQ  *req);
+USBD_Status  USBD_StdItfReq (USB_OTG_CORE_HANDLE  *pdev, USB_SETUP_REQ  *req);
+USBD_Status  USBD_StdEPReq (USB_OTG_CORE_HANDLE  *pdev, USB_SETUP_REQ  *req);
+void USBD_ParseSetupRequest( USB_OTG_CORE_HANDLE  *pdev,
+                                    USB_SETUP_REQ *req);
+
+void USBD_CtlError( USB_OTG_CORE_HANDLE  *pdev,
+                            USB_SETUP_REQ *req);
+
+void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len);
+/**
+  * @}
+  */ 
+
+#endif /* __USB_REQUEST_H_ */
+
+/**
+  * @}
+  */ 
+
+/**
+* @}
+*/ 
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_usr.h b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_usr.h
new file mode 100644
index 0000000000000000000000000000000000000000..bd5ff3e2e63575ac4730933af4a26f98c4c7bec8
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/inc/usbd_usr.h
@@ -0,0 +1,141 @@
+/**
+  ******************************************************************************
+  * @file    usbd_usr.h
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   Header file for usbd_usr.c
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USBD_USR_H__
+#define __USBD_USR_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+
+
+/** @addtogroup USBD_USER
+  * @{
+  */
+
+/** @addtogroup USBD_MSC_DEMO_USER_CALLBACKS
+  * @{
+  */
+
+/** @defgroup USBD_USR
+  * @brief This file is the Header file for usbd_usr.c
+  * @{
+  */ 
+
+
+/** @defgroup USBD_USR_Exported_Types
+  * @{
+  */ 
+
+extern  USBD_Usr_cb_TypeDef USR_cb;
+extern  USBD_Usr_cb_TypeDef USR_FS_cb;
+extern  USBD_Usr_cb_TypeDef USR_HS_cb;
+
+
+
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USBD_USR_Exported_Defines
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_USR_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_USR_Exported_Variables
+  * @{
+  */ 
+
+void     USBD_USR_Init(void);
+void     USBD_USR_DeviceReset (uint8_t speed);
+void     USBD_USR_DeviceConfigured (void);
+void     USBD_USR_DeviceSuspended(void);
+void     USBD_USR_DeviceResumed(void);
+
+void     USBD_USR_DeviceConnected(void);
+void     USBD_USR_DeviceDisconnected(void); 
+
+void     USBD_USR_FS_Init(void);
+void     USBD_USR_FS_DeviceReset (uint8_t speed);
+void     USBD_USR_FS_DeviceConfigured (void);
+void     USBD_USR_FS_DeviceSuspended(void);
+void     USBD_USR_FS_DeviceResumed(void);
+
+void     USBD_USR_FS_DeviceConnected(void);
+void     USBD_USR_FS_DeviceDisconnected(void);  
+
+void     USBD_USR_HS_Init(void);
+void     USBD_USR_HS_DeviceReset (uint8_t speed);
+void     USBD_USR_HS_DeviceConfigured (void);
+void     USBD_USR_HS_DeviceSuspended(void);
+void     USBD_USR_HS_DeviceResumed(void);
+
+void     USBD_USR_HS_DeviceConnected(void);
+void     USBD_USR_HS_DeviceDisconnected(void);  
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBD_USR_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+#endif /*__USBD_USR_H__*/
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
+
+
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_core.c b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_core.c
new file mode 100644
index 0000000000000000000000000000000000000000..fa647eb0f30bd37379c055c113213ddf03e32bf5
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_core.c
@@ -0,0 +1,506 @@
+/**
+  ******************************************************************************
+  * @file    usbd_core.c
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   This file provides all the USBD core functions.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_core.h"
+#include "usbd_req.h"
+#include "usbd_ioreq.h"
+#include "usb_dcd_int.h"
+#include "usb_bsp.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+* @{
+*/
+
+
+/** @defgroup USBD_CORE 
+* @brief usbd core module
+* @{
+*/ 
+
+/** @defgroup USBD_CORE_Private_TypesDefinitions
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USBD_CORE_Private_Defines
+* @{
+*/ 
+
+/**
+* @}
+*/ 
+
+
+/** @defgroup USBD_CORE_Private_Macros
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+
+
+/** @defgroup USBD_CORE_Private_FunctionPrototypes
+* @{
+*/ 
+static uint8_t USBD_SetupStage(USB_OTG_CORE_HANDLE *pdev);
+static uint8_t USBD_DataOutStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
+static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
+static uint8_t USBD_SOF(USB_OTG_CORE_HANDLE  *pdev);
+static uint8_t USBD_Reset(USB_OTG_CORE_HANDLE  *pdev);
+static uint8_t USBD_Suspend(USB_OTG_CORE_HANDLE  *pdev);
+static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE  *pdev);
+#ifdef VBUS_SENSING_ENABLED
+static uint8_t USBD_DevConnected(USB_OTG_CORE_HANDLE  *pdev);
+static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE  *pdev);
+#endif
+static uint8_t USBD_IsoINIncomplete(USB_OTG_CORE_HANDLE  *pdev);
+static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE  *pdev);
+static uint8_t  USBD_RunTestMode (USB_OTG_CORE_HANDLE  *pdev) ;
+/**
+* @}
+*/ 
+
+/** @defgroup USBD_CORE_Private_Variables
+* @{
+*/ 
+
+__IO USB_OTG_DCTL_TypeDef SET_TEST_MODE;
+
+USBD_DCD_INT_cb_TypeDef USBD_DCD_INT_cb = 
+{
+  USBD_DataOutStage,
+  USBD_DataInStage,
+  USBD_SetupStage,
+  USBD_SOF,
+  USBD_Reset,
+  USBD_Suspend,
+  USBD_Resume,
+  USBD_IsoINIncomplete,
+  USBD_IsoOUTIncomplete,
+#ifdef VBUS_SENSING_ENABLED
+USBD_DevConnected, 
+USBD_DevDisconnected,    
+#endif  
+};
+
+USBD_DCD_INT_cb_TypeDef  *USBD_DCD_INT_fops = &USBD_DCD_INT_cb;
+/**
+* @}
+*/ 
+
+/** @defgroup USBD_CORE_Private_Functions
+* @{
+*/ 
+
+/**
+* @brief  USBD_Init
+*         Initailizes the device stack and load the class driver
+* @param  pdev: device instance
+* @param  core_address: USB OTG core ID
+* @param  class_cb: Class callback structure address
+* @param  usr_cb: User callback structure address
+* @retval None
+*/
+void USBD_Init(USB_OTG_CORE_HANDLE *pdev,
+               USB_OTG_CORE_ID_TypeDef coreID,
+               USBD_DEVICE *pDevice,                  
+               USBD_Class_cb_TypeDef *class_cb, 
+               USBD_Usr_cb_TypeDef *usr_cb)
+{
+  /* Hardware Init */
+  USB_OTG_BSP_Init(pdev);  
+  
+  USBD_DeInit(pdev);
+  
+  /*Register class and user callbacks */
+  pdev->dev.class_cb = class_cb;
+  pdev->dev.usr_cb = usr_cb;  
+  pdev->dev.usr_device = pDevice;    
+  
+  /* set USB OTG core params */
+  DCD_Init(pdev , coreID);
+  
+  /* Upon Init call usr callback */
+  pdev->dev.usr_cb->Init();
+  
+  /* Enable Interrupts */
+  USB_OTG_BSP_EnableInterrupt(pdev);
+}
+
+/**
+* @brief  USBD_DeInit 
+*         Re-Initialize th device library
+* @param  pdev: device instance
+* @retval status: status
+*/
+USBD_Status USBD_DeInit(USB_OTG_CORE_HANDLE *pdev)
+{
+  /* Software Init */
+  
+  return USBD_OK;
+}
+
+/**
+* @brief  USBD_SetupStage 
+*         Handle the setup stage
+* @param  pdev: device instance
+* @retval status
+*/
+static uint8_t USBD_SetupStage(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_SETUP_REQ req;
+  
+  USBD_ParseSetupRequest(pdev , &req);
+  
+  switch (req.bmRequest & 0x1F) 
+  {
+  case USB_REQ_RECIPIENT_DEVICE:   
+    USBD_StdDevReq (pdev, &req);
+    break;
+    
+  case USB_REQ_RECIPIENT_INTERFACE:     
+    USBD_StdItfReq(pdev, &req);
+    break;
+    
+  case USB_REQ_RECIPIENT_ENDPOINT:        
+    USBD_StdEPReq(pdev, &req);   
+    break;
+    
+  default:           
+    DCD_EP_Stall(pdev , req.bmRequest & 0x80);
+    break;
+  }  
+  return USBD_OK;
+}
+
+/**
+* @brief  USBD_DataOutStage 
+*         Handle data out stage
+* @param  pdev: device instance
+* @param  epnum: endpoint index
+* @retval status
+*/
+static uint8_t USBD_DataOutStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
+{
+  USB_OTG_EP *ep;
+  
+  if(epnum == 0) 
+  {
+    ep = &pdev->dev.out_ep[0];
+    if ( pdev->dev.device_state == USB_OTG_EP0_DATA_OUT)
+    {
+      if(ep->rem_data_len > ep->maxpacket)
+      {
+        ep->rem_data_len -=  ep->maxpacket;
+        
+        if(pdev->cfg.dma_enable == 1)
+        {
+          /* in slave mode this, is handled by the RxSTSQLvl ISR */
+          ep->xfer_buff += ep->maxpacket; 
+        }        
+        USBD_CtlContinueRx (pdev, 
+                            ep->xfer_buff,
+                            MIN(ep->rem_data_len ,ep->maxpacket));
+      }
+      else
+      {
+        if((pdev->dev.class_cb->EP0_RxReady != NULL)&&
+           (pdev->dev.device_status == USB_OTG_CONFIGURED))
+        {
+          pdev->dev.class_cb->EP0_RxReady(pdev); 
+        }
+        USBD_CtlSendStatus(pdev);
+      }
+    }
+  }
+  else if((pdev->dev.class_cb->DataOut != NULL)&&
+          (pdev->dev.device_status == USB_OTG_CONFIGURED))
+  {
+    pdev->dev.class_cb->DataOut(pdev, epnum); 
+  }  
+  return USBD_OK;
+}
+
+/**
+* @brief  USBD_DataInStage 
+*         Handle data in stage
+* @param  pdev: device instance
+* @param  epnum: endpoint index
+* @retval status
+*/
+static uint8_t USBD_DataInStage(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
+{
+  USB_OTG_EP *ep;
+  
+  if(epnum == 0) 
+  {
+    ep = &pdev->dev.in_ep[0];
+    if ( pdev->dev.device_state == USB_OTG_EP0_DATA_IN)
+    {
+      if(ep->rem_data_len > ep->maxpacket)
+      {
+        ep->rem_data_len -=  ep->maxpacket;
+        if(pdev->cfg.dma_enable == 1)
+        {
+          /* in slave mode this, is handled by the TxFifoEmpty ISR */
+          ep->xfer_buff += ep->maxpacket;
+        }
+        USBD_CtlContinueSendData (pdev, 
+                                  ep->xfer_buff, 
+                                  ep->rem_data_len);
+      }
+      else
+      { /* last packet is MPS multiple, so send ZLP packet */
+        if((ep->total_data_len % ep->maxpacket == 0) &&
+           (ep->total_data_len >= ep->maxpacket) &&
+             (ep->total_data_len < ep->ctl_data_len ))
+        {
+          
+          USBD_CtlContinueSendData(pdev , NULL, 0);
+          ep->ctl_data_len = 0;
+        }
+        else
+        {
+          if((pdev->dev.class_cb->EP0_TxSent != NULL)&&
+             (pdev->dev.device_status == USB_OTG_CONFIGURED))
+          {
+            pdev->dev.class_cb->EP0_TxSent(pdev); 
+          }          
+          USBD_CtlReceiveStatus(pdev);
+        }
+      }
+    }
+    if (pdev->dev.test_mode == 1)
+    {
+      USBD_RunTestMode(pdev); 
+      pdev->dev.test_mode = 0;
+    }
+  }
+  else if((pdev->dev.class_cb->DataIn != NULL)&& 
+          (pdev->dev.device_status == USB_OTG_CONFIGURED))
+  {
+    pdev->dev.class_cb->DataIn(pdev, epnum); 
+  }  
+  return USBD_OK;
+}
+
+
+
+
+/**
+* @brief  USBD_RunTestMode 
+*         Launch test mode process
+* @param  pdev: device instance
+* @retval status
+*/
+static uint8_t  USBD_RunTestMode (USB_OTG_CORE_HANDLE  *pdev) 
+{
+  USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, SET_TEST_MODE.d32);
+  return USBD_OK;  
+}
+
+/**
+* @brief  USBD_Reset 
+*         Handle Reset event
+* @param  pdev: device instance
+* @retval status
+*/
+
+static uint8_t USBD_Reset(USB_OTG_CORE_HANDLE  *pdev)
+{
+  /* Open EP0 OUT */
+  DCD_EP_Open(pdev,
+              0x00,
+              USB_OTG_MAX_EP0_SIZE,
+              EP_TYPE_CTRL);
+  
+  /* Open EP0 IN */
+  DCD_EP_Open(pdev,
+              0x80,
+              USB_OTG_MAX_EP0_SIZE,
+              EP_TYPE_CTRL);
+  
+  /* Upon Reset call usr call back */
+  pdev->dev.device_status = USB_OTG_DEFAULT;
+  pdev->dev.usr_cb->DeviceReset(pdev->cfg.speed);
+  
+  return USBD_OK;
+}
+
+/**
+* @brief  USBD_Resume 
+*         Handle Resume event
+* @param  pdev: device instance
+* @retval status
+*/
+
+static uint8_t USBD_Resume(USB_OTG_CORE_HANDLE  *pdev)
+{
+  /* Upon Resume call usr call back */
+  pdev->dev.usr_cb->DeviceResumed(); 
+  pdev->dev.device_status = pdev->dev.device_old_status;  
+  pdev->dev.device_status = USB_OTG_CONFIGURED;  
+  return USBD_OK;
+}
+
+
+/**
+* @brief  USBD_Suspend 
+*         Handle Suspend event
+* @param  pdev: device instance
+* @retval status
+*/
+
+static uint8_t USBD_Suspend(USB_OTG_CORE_HANDLE  *pdev)
+{
+  pdev->dev.device_old_status = pdev->dev.device_status;
+  pdev->dev.device_status  = USB_OTG_SUSPENDED;
+  /* Upon Resume call usr call back */
+  pdev->dev.usr_cb->DeviceSuspended(); 
+  return USBD_OK;
+}
+
+
+/**
+* @brief  USBD_SOF 
+*         Handle SOF event
+* @param  pdev: device instance
+* @retval status
+*/
+
+static uint8_t USBD_SOF(USB_OTG_CORE_HANDLE  *pdev)
+{
+  if(pdev->dev.class_cb->SOF)
+  {
+    pdev->dev.class_cb->SOF(pdev); 
+  }
+  return USBD_OK;
+}
+/**
+* @brief  USBD_SetCfg 
+*        Configure device and start the interface
+* @param  pdev: device instance
+* @param  cfgidx: configuration index
+* @retval status
+*/
+
+USBD_Status USBD_SetCfg(USB_OTG_CORE_HANDLE  *pdev, uint8_t cfgidx)
+{
+  pdev->dev.class_cb->Init(pdev, cfgidx); 
+  
+  /* Upon set config call usr call back */
+  pdev->dev.usr_cb->DeviceConfigured();
+  return USBD_OK; 
+}
+
+/**
+* @brief  USBD_ClrCfg 
+*         Clear current configuration
+* @param  pdev: device instance
+* @param  cfgidx: configuration index
+* @retval status: USBD_Status
+*/
+USBD_Status USBD_ClrCfg(USB_OTG_CORE_HANDLE  *pdev, uint8_t cfgidx)
+{
+  pdev->dev.class_cb->DeInit(pdev, cfgidx);   
+  return USBD_OK;
+}
+
+/**
+* @brief  USBD_IsoINIncomplete 
+*         Handle iso in incomplete event
+* @param  pdev: device instance
+* @retval status
+*/
+static uint8_t USBD_IsoINIncomplete(USB_OTG_CORE_HANDLE  *pdev)
+{
+  pdev->dev.class_cb->IsoINIncomplete(pdev);   
+  return USBD_OK;
+}
+
+/**
+* @brief  USBD_IsoOUTIncomplete 
+*         Handle iso out incomplete event
+* @param  pdev: device instance
+* @retval status
+*/
+static uint8_t USBD_IsoOUTIncomplete(USB_OTG_CORE_HANDLE  *pdev)
+{
+  pdev->dev.class_cb->IsoOUTIncomplete(pdev);   
+  return USBD_OK;
+}
+
+#ifdef VBUS_SENSING_ENABLED
+/**
+* @brief  USBD_DevConnected 
+*         Handle device connection event
+* @param  pdev: device instance
+* @retval status
+*/
+static uint8_t USBD_DevConnected(USB_OTG_CORE_HANDLE  *pdev)
+{
+  pdev->dev.usr_cb->DeviceConnected();
+  pdev->dev.connection_status = 1;  
+  return USBD_OK;
+}
+
+/**
+* @brief  USBD_DevDisconnected 
+*         Handle device disconnection event
+* @param  pdev: device instance
+* @retval status
+*/
+static uint8_t USBD_DevDisconnected(USB_OTG_CORE_HANDLE  *pdev)
+{
+  pdev->dev.usr_cb->DeviceDisconnected();
+  pdev->dev.class_cb->DeInit(pdev, 0);
+  pdev->dev.connection_status = 0;    
+  return USBD_OK;
+}
+#endif
+/**
+* @}
+*/ 
+
+
+/**
+* @}
+*/ 
+
+
+/**
+* @}
+*/ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_ioreq.c b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_ioreq.c
new file mode 100644
index 0000000000000000000000000000000000000000..657c72e63bbf1416e4460e23f5ba99fbd64ccf0e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_ioreq.c
@@ -0,0 +1,245 @@
+/**
+  ******************************************************************************
+  * @file    usbd_ioreq.c
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012
+  * @brief   This file provides the IO requests APIs for control endpoints.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "usbd_ioreq.h"
+#include "usb_dcd.h"
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+
+
+/** @defgroup USBD_IOREQ 
+  * @brief control I/O requests module
+  * @{
+  */ 
+
+/** @defgroup USBD_IOREQ_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_IOREQ_Private_Defines
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_IOREQ_Private_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_IOREQ_Private_Variables
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_IOREQ_Private_FunctionPrototypes
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_IOREQ_Private_Functions
+  * @{
+  */ 
+
+/**
+* @brief  USBD_CtlSendData
+*         send data on the ctl pipe
+* @param  pdev: device instance
+* @param  buff: pointer to data buffer
+* @param  len: length of data to be sent
+* @retval status
+*/
+USBD_Status  USBD_CtlSendData (USB_OTG_CORE_HANDLE  *pdev, 
+                               uint8_t *pbuf,
+                               uint16_t len)
+{
+  USBD_Status ret = USBD_OK;
+  
+  pdev->dev.in_ep[0].total_data_len = len;
+  pdev->dev.in_ep[0].rem_data_len   = len;
+  pdev->dev.device_state = USB_OTG_EP0_DATA_IN;
+
+  DCD_EP_Tx (pdev, 0, pbuf, len);
+ 
+  return ret;
+}
+
+/**
+* @brief  USBD_CtlContinueSendData
+*         continue sending data on the ctl pipe
+* @param  pdev: device instance
+* @param  buff: pointer to data buffer
+* @param  len: length of data to be sent
+* @retval status
+*/
+USBD_Status  USBD_CtlContinueSendData (USB_OTG_CORE_HANDLE  *pdev, 
+                                       uint8_t *pbuf,
+                                       uint16_t len)
+{
+  USBD_Status ret = USBD_OK;
+  
+  DCD_EP_Tx (pdev, 0, pbuf, len);
+  
+  
+  return ret;
+}
+
+/**
+* @brief  USBD_CtlPrepareRx
+*         receive data on the ctl pipe
+* @param  pdev: USB OTG device instance
+* @param  buff: pointer to data buffer
+* @param  len: length of data to be received
+* @retval status
+*/
+USBD_Status  USBD_CtlPrepareRx (USB_OTG_CORE_HANDLE  *pdev,
+                                  uint8_t *pbuf,                                  
+                                  uint16_t len)
+{
+  USBD_Status ret = USBD_OK;
+  
+  pdev->dev.out_ep[0].total_data_len = len;
+  pdev->dev.out_ep[0].rem_data_len   = len;
+  pdev->dev.device_state = USB_OTG_EP0_DATA_OUT;
+  
+  DCD_EP_PrepareRx (pdev,
+                    0,
+                    pbuf,
+                    len);
+  
+
+  return ret;
+}
+
+/**
+* @brief  USBD_CtlContinueRx
+*         continue receive data on the ctl pipe
+* @param  pdev: USB OTG device instance
+* @param  buff: pointer to data buffer
+* @param  len: length of data to be received
+* @retval status
+*/
+USBD_Status  USBD_CtlContinueRx (USB_OTG_CORE_HANDLE  *pdev, 
+                                          uint8_t *pbuf,                                          
+                                          uint16_t len)
+{
+  USBD_Status ret = USBD_OK;
+  
+  DCD_EP_PrepareRx (pdev,
+                    0,                     
+                    pbuf,                         
+                    len);
+  return ret;
+}
+/**
+* @brief  USBD_CtlSendStatus
+*         send zero lzngth packet on the ctl pipe
+* @param  pdev: USB OTG device instance
+* @retval status
+*/
+USBD_Status  USBD_CtlSendStatus (USB_OTG_CORE_HANDLE  *pdev)
+{
+  USBD_Status ret = USBD_OK;
+  pdev->dev.device_state = USB_OTG_EP0_STATUS_IN;
+  DCD_EP_Tx (pdev,
+             0,
+             NULL, 
+             0); 
+  
+  USB_OTG_EP0_OutStart(pdev);  
+  
+  return ret;
+}
+
+/**
+* @brief  USBD_CtlReceiveStatus
+*         receive zero lzngth packet on the ctl pipe
+* @param  pdev: USB OTG device instance
+* @retval status
+*/
+USBD_Status  USBD_CtlReceiveStatus (USB_OTG_CORE_HANDLE  *pdev)
+{
+  USBD_Status ret = USBD_OK;
+  pdev->dev.device_state = USB_OTG_EP0_STATUS_OUT;  
+  DCD_EP_PrepareRx ( pdev,
+                    0,
+                    NULL,
+                    0);  
+
+  USB_OTG_EP0_OutStart(pdev);
+  
+  return ret;
+}
+
+
+/**
+* @brief  USBD_GetRxCount
+*         returns the received data length
+* @param  pdev: USB OTG device instance
+*         epnum: endpoint index
+* @retval Rx Data blength
+*/
+uint16_t  USBD_GetRxCount (USB_OTG_CORE_HANDLE  *pdev , uint8_t epnum)
+{
+  return pdev->dev.out_ep[epnum].xfer_count;
+}
+
+/**
+  * @}
+  */ 
+
+
+/**
+  * @}
+  */ 
+
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_req.c b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_req.c
new file mode 100644
index 0000000000000000000000000000000000000000..a798edb59254aa7912af6681456341d637763d59
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Core/src/usbd_req.c
@@ -0,0 +1,870 @@
+/**
+  ******************************************************************************
+  * @file    usbd_req.c
+  * @author  MCD Application Team
+  * @version V1.1.0
+  * @date    19-March-2012 
+  * @brief   This file provides the standard USB requests following chapter 9.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_dcd.h"
+#include "usbd_conf.h"
+#include "usbd_req.h"
+#include "usbd_ioreq.h"
+#include "usbd_desc.h"
+
+
+/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
+  * @{
+  */
+
+
+/** @defgroup USBD_REQ 
+  * @brief USB standard requests module
+  * @{
+  */ 
+
+/** @defgroup USBD_REQ_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_REQ_Private_Defines
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_REQ_Private_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_REQ_Private_Variables
+  * @{
+  */ 
+extern __IO USB_OTG_DCTL_TypeDef SET_TEST_MODE;
+
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+    #pragma data_alignment=4   
+  #endif
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */  
+__ALIGN_BEGIN uint32_t USBD_ep_status __ALIGN_END  = 0; 
+
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+    #pragma data_alignment=4   
+  #endif
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+__ALIGN_BEGIN uint32_t  USBD_default_cfg __ALIGN_END  = 0;
+
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+    #pragma data_alignment=4   
+  #endif
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+__ALIGN_BEGIN uint32_t  USBD_cfg_status __ALIGN_END  = 0;  
+
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined ( __ICCARM__ ) /*!< IAR Compiler */
+    #pragma data_alignment=4   
+  #endif
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+__ALIGN_BEGIN uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ] __ALIGN_END ;
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_REQ_Private_FunctionPrototypes
+  * @{
+  */ 
+static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE  *pdev, 
+                               USB_SETUP_REQ *req);
+
+static void USBD_SetAddress(USB_OTG_CORE_HANDLE  *pdev, 
+                            USB_SETUP_REQ *req);
+
+static void USBD_SetConfig(USB_OTG_CORE_HANDLE  *pdev, 
+                           USB_SETUP_REQ *req);
+
+static void USBD_GetConfig(USB_OTG_CORE_HANDLE  *pdev, 
+                           USB_SETUP_REQ *req);
+
+static void USBD_GetStatus(USB_OTG_CORE_HANDLE  *pdev, 
+                           USB_SETUP_REQ *req);
+
+static void USBD_SetFeature(USB_OTG_CORE_HANDLE  *pdev, 
+                            USB_SETUP_REQ *req);
+
+static void USBD_ClrFeature(USB_OTG_CORE_HANDLE  *pdev, 
+                            USB_SETUP_REQ *req);
+
+static uint8_t USBD_GetLen(uint8_t *buf);
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USBD_REQ_Private_Functions
+  * @{
+  */ 
+
+
+/**
+* @brief  USBD_StdDevReq
+*         Handle standard usb device requests
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+USBD_Status  USBD_StdDevReq (USB_OTG_CORE_HANDLE  *pdev, USB_SETUP_REQ  *req)
+{
+  USBD_Status ret = USBD_OK;  
+  
+  switch (req->bRequest) 
+  {
+  case USB_REQ_GET_DESCRIPTOR: 
+    
+    USBD_GetDescriptor (pdev, req) ;
+    break;
+    
+  case USB_REQ_SET_ADDRESS:                      
+    USBD_SetAddress(pdev, req);
+    break;
+    
+  case USB_REQ_SET_CONFIGURATION:                    
+    USBD_SetConfig (pdev , req);
+    break;
+    
+  case USB_REQ_GET_CONFIGURATION:                 
+    USBD_GetConfig (pdev , req);
+    break;
+    
+  case USB_REQ_GET_STATUS:                                  
+    USBD_GetStatus (pdev , req);
+    break;
+    
+    
+  case USB_REQ_SET_FEATURE:   
+    USBD_SetFeature (pdev , req);    
+    break;
+    
+  case USB_REQ_CLEAR_FEATURE:                                   
+    USBD_ClrFeature (pdev , req);
+    break;
+    
+  default:  
+    USBD_CtlError(pdev , req);
+    break;
+  }
+  
+  return ret;
+}
+
+/**
+* @brief  USBD_StdItfReq
+*         Handle standard usb interface requests
+* @param  pdev: USB OTG device instance
+* @param  req: usb request
+* @retval status
+*/
+USBD_Status  USBD_StdItfReq (USB_OTG_CORE_HANDLE  *pdev, USB_SETUP_REQ  *req)
+{
+  USBD_Status ret = USBD_OK; 
+  
+  switch (pdev->dev.device_status) 
+  {
+  case USB_OTG_CONFIGURED:
+    
+    if (LOBYTE(req->wIndex) <= USBD_ITF_MAX_NUM) 
+    {
+      pdev->dev.class_cb->Setup (pdev, req); 
+      
+      if((req->wLength == 0)&& (ret == USBD_OK))
+      {
+         USBD_CtlSendStatus(pdev);
+      }
+    } 
+    else 
+    {                                               
+       USBD_CtlError(pdev , req);
+    }
+    break;
+    
+  default:
+     USBD_CtlError(pdev , req);
+    break;
+  }
+  return ret;
+}
+
+/**
+* @brief  USBD_StdEPReq
+*         Handle standard usb endpoint requests
+* @param  pdev: USB OTG device instance
+* @param  req: usb request
+* @retval status
+*/
+USBD_Status  USBD_StdEPReq (USB_OTG_CORE_HANDLE  *pdev, USB_SETUP_REQ  *req)
+{
+  
+  uint8_t   ep_addr;
+  USBD_Status ret = USBD_OK; 
+  
+  ep_addr  = LOBYTE(req->wIndex);   
+  
+  switch (req->bRequest) 
+  {
+    
+  case USB_REQ_SET_FEATURE :
+    
+    switch (pdev->dev.device_status) 
+    {
+    case USB_OTG_ADDRESSED:          
+      if ((ep_addr != 0x00) && (ep_addr != 0x80)) 
+      {
+        DCD_EP_Stall(pdev , ep_addr);
+      }
+      break;	
+      
+    case USB_OTG_CONFIGURED:   
+      if (req->wValue == USB_FEATURE_EP_HALT)
+      {
+        if ((ep_addr != 0x00) && (ep_addr != 0x80)) 
+        { 
+          DCD_EP_Stall(pdev , ep_addr);
+          
+        }
+      }
+      pdev->dev.class_cb->Setup (pdev, req);   
+      USBD_CtlSendStatus(pdev);
+      
+      break;
+      
+    default:                         
+      USBD_CtlError(pdev , req);
+      break;    
+    }
+    break;
+    
+  case USB_REQ_CLEAR_FEATURE :
+    
+    switch (pdev->dev.device_status) 
+    {
+    case USB_OTG_ADDRESSED:          
+      if ((ep_addr != 0x00) && (ep_addr != 0x80)) 
+      {
+        DCD_EP_Stall(pdev , ep_addr);
+      }
+      break;	
+      
+    case USB_OTG_CONFIGURED:   
+      if (req->wValue == USB_FEATURE_EP_HALT)
+      {
+        if ((ep_addr != 0x00) && (ep_addr != 0x80)) 
+        {        
+          DCD_EP_ClrStall(pdev , ep_addr);
+          pdev->dev.class_cb->Setup (pdev, req);
+        }
+        USBD_CtlSendStatus(pdev);
+      }
+      break;
+      
+    default:                         
+       USBD_CtlError(pdev , req);
+      break;    
+    }
+    break;
+    
+  case USB_REQ_GET_STATUS:                  
+    switch (pdev->dev.device_status) 
+    {
+    case USB_OTG_ADDRESSED:          
+      if ((ep_addr != 0x00) && (ep_addr != 0x80)) 
+      {
+        DCD_EP_Stall(pdev , ep_addr);
+      }
+      break;	
+      
+    case USB_OTG_CONFIGURED:         
+      
+      
+      if ((ep_addr & 0x80)== 0x80)
+      {
+        if(pdev->dev.in_ep[ep_addr & 0x7F].is_stall)
+        {
+          USBD_ep_status = 0x0001;     
+        }
+        else
+        {
+          USBD_ep_status = 0x0000;  
+        }
+      }
+      else if ((ep_addr & 0x80)== 0x00)
+      {
+        if(pdev->dev.out_ep[ep_addr].is_stall)
+        {
+          USBD_ep_status = 0x0001;     
+        }
+        
+        else 
+        {
+          USBD_ep_status = 0x0000;     
+        }      
+      }
+      USBD_CtlSendData (pdev,
+                        (uint8_t *)&USBD_ep_status,
+                        2);
+      break;
+      
+    default:                         
+       USBD_CtlError(pdev , req);
+      break;
+    }
+    break;
+    
+  default:
+    break;
+  }
+  return ret;
+}
+/**
+* @brief  USBD_GetDescriptor
+*         Handle Get Descriptor requests
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+static void USBD_GetDescriptor(USB_OTG_CORE_HANDLE  *pdev, 
+                               USB_SETUP_REQ *req)
+{
+  uint16_t len;
+  uint8_t *pbuf;
+  
+    
+  switch (req->wValue >> 8)
+  {
+  case USB_DESC_TYPE_DEVICE:
+    pbuf = pdev->dev.usr_device->GetDeviceDescriptor(pdev->cfg.speed, &len);
+    if ((req->wLength == 64) ||( pdev->dev.device_status == USB_OTG_DEFAULT))  
+    {                  
+      len = 8;
+    }
+    break;
+    
+  case USB_DESC_TYPE_CONFIGURATION:
+      pbuf   = (uint8_t *)pdev->dev.class_cb->GetConfigDescriptor(pdev->cfg.speed, &len);
+#ifdef USB_OTG_HS_CORE
+    if((pdev->cfg.speed == USB_OTG_SPEED_FULL )&&
+       (pdev->cfg.phy_itface  == USB_OTG_ULPI_PHY))
+    {
+      pbuf   = (uint8_t *)pdev->dev.class_cb->GetOtherConfigDescriptor(pdev->cfg.speed, &len);
+    }
+#endif  
+    pbuf[1] = USB_DESC_TYPE_CONFIGURATION;
+    pdev->dev.pConfig_descriptor = pbuf;    
+    break;
+    
+  case USB_DESC_TYPE_STRING:
+    switch ((uint8_t)(req->wValue))
+    {
+    case USBD_IDX_LANGID_STR:
+     pbuf = pdev->dev.usr_device->GetLangIDStrDescriptor(pdev->cfg.speed, &len);        
+      break;
+      
+    case USBD_IDX_MFC_STR:
+      pbuf = pdev->dev.usr_device->GetManufacturerStrDescriptor(pdev->cfg.speed, &len);
+      break;
+      
+    case USBD_IDX_PRODUCT_STR:
+      pbuf = pdev->dev.usr_device->GetProductStrDescriptor(pdev->cfg.speed, &len);
+      break;
+      
+    case USBD_IDX_SERIAL_STR:
+      pbuf = pdev->dev.usr_device->GetSerialStrDescriptor(pdev->cfg.speed, &len);
+      break;
+      
+    case USBD_IDX_CONFIG_STR:
+      pbuf = pdev->dev.usr_device->GetConfigurationStrDescriptor(pdev->cfg.speed, &len);
+      break;
+      
+    case USBD_IDX_INTERFACE_STR:
+      pbuf = pdev->dev.usr_device->GetInterfaceStrDescriptor(pdev->cfg.speed, &len);
+      break;
+      
+    default:
+#ifdef USB_SUPPORT_USER_STRING_DESC
+      pbuf = pdev->dev.class_cb->GetUsrStrDescriptor(pdev->cfg.speed, (req->wValue) , &len);
+      break;
+#else      
+       USBD_CtlError(pdev , req);
+      return;
+#endif /* USBD_CtlError(pdev , req); */      
+    }
+    break;
+  case USB_DESC_TYPE_DEVICE_QUALIFIER:                   
+#ifdef USB_OTG_HS_CORE
+    if(pdev->cfg.speed == USB_OTG_SPEED_HIGH  )   
+    {
+      
+      pbuf   = (uint8_t *)pdev->dev.class_cb->GetConfigDescriptor(pdev->cfg.speed, &len);
+            
+      USBD_DeviceQualifierDesc[4]= pbuf[14];
+      USBD_DeviceQualifierDesc[5]= pbuf[15];
+      USBD_DeviceQualifierDesc[6]= pbuf[16];
+      
+      pbuf = USBD_DeviceQualifierDesc;
+      len  = USB_LEN_DEV_QUALIFIER_DESC;
+      break;
+    }
+    else
+    {
+      USBD_CtlError(pdev , req);
+      return;
+    }
+#else
+      USBD_CtlError(pdev , req);
+      return;
+#endif    
+
+  case USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION:
+#ifdef USB_OTG_HS_CORE   
+
+    if(pdev->cfg.speed == USB_OTG_SPEED_HIGH  )   
+    {
+      pbuf   = (uint8_t *)pdev->dev.class_cb->GetOtherConfigDescriptor(pdev->cfg.speed, &len);
+      pbuf[1] = USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION;
+      break; 
+    }
+    else
+    {
+      USBD_CtlError(pdev , req);
+      return;
+    }
+#else
+      USBD_CtlError(pdev , req);
+      return;
+#endif     
+
+    
+  default: 
+     USBD_CtlError(pdev , req);
+    return;
+  }
+  
+  if((len != 0)&& (req->wLength != 0))
+  {
+    
+    len = MIN(len , req->wLength);
+    
+    USBD_CtlSendData (pdev, 
+                      pbuf,
+                      len);
+  }
+  
+}
+
+/**
+* @brief  USBD_SetAddress
+*         Set device address
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+static void USBD_SetAddress(USB_OTG_CORE_HANDLE  *pdev, 
+                            USB_SETUP_REQ *req)
+{
+  uint8_t  dev_addr; 
+  
+  if ((req->wIndex == 0) && (req->wLength == 0)) 
+  {
+    dev_addr = (uint8_t)(req->wValue) & 0x7F;     
+    
+    if (pdev->dev.device_status == USB_OTG_CONFIGURED) 
+    {
+      USBD_CtlError(pdev , req);
+    } 
+    else 
+    {
+      pdev->dev.device_address = dev_addr;
+      DCD_EP_SetAddress(pdev, dev_addr);               
+      USBD_CtlSendStatus(pdev);                         
+      
+      if (dev_addr != 0) 
+      {
+        pdev->dev.device_status  = USB_OTG_ADDRESSED;
+      } 
+      else 
+      {
+        pdev->dev.device_status  = USB_OTG_DEFAULT; 
+      }
+    }
+  } 
+  else 
+  {
+     USBD_CtlError(pdev , req);                        
+  } 
+}
+
+/**
+* @brief  USBD_SetConfig
+*         Handle Set device configuration request
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+static void USBD_SetConfig(USB_OTG_CORE_HANDLE  *pdev, 
+                           USB_SETUP_REQ *req)
+{
+  
+  static uint8_t  cfgidx;
+  
+  cfgidx = (uint8_t)(req->wValue);                 
+  
+  if (cfgidx > USBD_CFG_MAX_NUM ) 
+  {            
+     USBD_CtlError(pdev , req);                              
+  } 
+  else 
+  {
+    switch (pdev->dev.device_status) 
+    {
+    case USB_OTG_ADDRESSED:
+      if (cfgidx) 
+      {                                			   							   							   				
+        pdev->dev.device_config = cfgidx;
+        pdev->dev.device_status = USB_OTG_CONFIGURED;
+        USBD_SetCfg(pdev , cfgidx);
+        USBD_CtlSendStatus(pdev);
+      }
+      else 
+      {
+         USBD_CtlSendStatus(pdev);
+      }
+      break;
+      
+    case USB_OTG_CONFIGURED:
+      if (cfgidx == 0) 
+      {                           
+        pdev->dev.device_status = USB_OTG_ADDRESSED;
+        pdev->dev.device_config = cfgidx;          
+        USBD_ClrCfg(pdev , cfgidx);
+        USBD_CtlSendStatus(pdev);
+        
+      } 
+      else  if (cfgidx != pdev->dev.device_config) 
+      {
+        /* Clear old configuration */
+        USBD_ClrCfg(pdev , pdev->dev.device_config);
+        
+        /* set new configuration */
+        pdev->dev.device_config = cfgidx;
+        USBD_SetCfg(pdev , cfgidx);
+        USBD_CtlSendStatus(pdev);
+      }
+      else
+      {
+        USBD_CtlSendStatus(pdev);
+      }
+      break;
+      
+    default:					
+       USBD_CtlError(pdev , req);                     
+      break;
+    }
+  }
+}
+
+/**
+* @brief  USBD_GetConfig
+*         Handle Get device configuration request
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+static void USBD_GetConfig(USB_OTG_CORE_HANDLE  *pdev, 
+                           USB_SETUP_REQ *req)
+{
+ 
+  if (req->wLength != 1) 
+  {                   
+     USBD_CtlError(pdev , req);
+  }
+  else 
+  {
+    switch (pdev->dev.device_status )  
+    {
+    case USB_OTG_ADDRESSED:                     
+      
+      USBD_CtlSendData (pdev, 
+                        (uint8_t *)&USBD_default_cfg,
+                        1);
+      break;
+      
+    case USB_OTG_CONFIGURED:                   
+      
+      USBD_CtlSendData (pdev, 
+                        &pdev->dev.device_config,
+                        1);
+      break;
+      
+    default:
+       USBD_CtlError(pdev , req);
+      break;
+    }
+  }
+}
+
+/**
+* @brief  USBD_GetStatus
+*         Handle Get Status request
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+static void USBD_GetStatus(USB_OTG_CORE_HANDLE  *pdev, 
+                           USB_SETUP_REQ *req)
+{
+  
+    
+  switch (pdev->dev.device_status) 
+  {
+  case USB_OTG_ADDRESSED:
+  case USB_OTG_CONFIGURED:
+    
+#ifdef USBD_SELF_POWERED
+    USBD_cfg_status = USB_CONFIG_SELF_POWERED;                                    
+#else
+    USBD_cfg_status = 0x00;                                    
+#endif
+                      
+    if (pdev->dev.DevRemoteWakeup) 
+    {
+      USBD_cfg_status |= USB_CONFIG_REMOTE_WAKEUP;                                
+    }
+    
+    USBD_CtlSendData (pdev, 
+                      (uint8_t *)&USBD_cfg_status,
+                      2);
+    break;
+    
+  default :
+    USBD_CtlError(pdev , req);                        
+    break;
+  }
+}
+
+
+/**
+* @brief  USBD_SetFeature
+*         Handle Set device feature request
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+static void USBD_SetFeature(USB_OTG_CORE_HANDLE  *pdev, 
+                            USB_SETUP_REQ *req)
+{
+
+  USB_OTG_DCTL_TypeDef     dctl;
+  uint8_t test_mode = 0;
+ 
+  if (req->wValue == USB_FEATURE_REMOTE_WAKEUP)
+  {
+    pdev->dev.DevRemoteWakeup = 1;  
+    pdev->dev.class_cb->Setup (pdev, req);   
+    USBD_CtlSendStatus(pdev);
+  }
+
+  else if ((req->wValue == USB_FEATURE_TEST_MODE) && 
+           ((req->wIndex & 0xFF) == 0))
+  {
+    dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
+    
+    test_mode = req->wIndex >> 8;
+    switch (test_mode) 
+    {
+    case 1: // TEST_J
+      dctl.b.tstctl = 1;
+      break;
+      
+    case 2: // TEST_K	
+      dctl.b.tstctl = 2;
+      break;
+      
+    case 3: // TEST_SE0_NAK
+      dctl.b.tstctl = 3;
+      break;
+      
+    case 4: // TEST_PACKET
+      dctl.b.tstctl = 4;
+      break;
+      
+    case 5: // TEST_FORCE_ENABLE
+      dctl.b.tstctl = 5;
+      break;
+    }
+    SET_TEST_MODE = dctl;
+    pdev->dev.test_mode = 1;
+    USBD_CtlSendStatus(pdev);
+  }
+
+}
+
+
+/**
+* @brief  USBD_ClrFeature
+*         Handle clear device feature request
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval status
+*/
+static void USBD_ClrFeature(USB_OTG_CORE_HANDLE  *pdev, 
+                            USB_SETUP_REQ *req)
+{
+  switch (pdev->dev.device_status)
+  {
+  case USB_OTG_ADDRESSED:
+  case USB_OTG_CONFIGURED:
+    if (req->wValue == USB_FEATURE_REMOTE_WAKEUP) 
+    {
+      pdev->dev.DevRemoteWakeup = 0; 
+      pdev->dev.class_cb->Setup (pdev, req);   
+      USBD_CtlSendStatus(pdev);
+    }
+    break;
+    
+  default :
+     USBD_CtlError(pdev , req);
+    break;
+  }
+}
+
+/**
+* @brief  USBD_ParseSetupRequest 
+*         Copy buffer into setup structure
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval None
+*/
+
+void USBD_ParseSetupRequest( USB_OTG_CORE_HANDLE  *pdev,
+                            USB_SETUP_REQ *req)
+{
+  req->bmRequest     = *(uint8_t *)  (pdev->dev.setup_packet);
+  req->bRequest      = *(uint8_t *)  (pdev->dev.setup_packet +  1);
+  req->wValue        = SWAPBYTE      (pdev->dev.setup_packet +  2);
+  req->wIndex        = SWAPBYTE      (pdev->dev.setup_packet +  4);
+  req->wLength       = SWAPBYTE      (pdev->dev.setup_packet +  6);
+  
+  pdev->dev.in_ep[0].ctl_data_len = req->wLength  ;
+  pdev->dev.device_state = USB_OTG_EP0_SETUP;
+}
+
+/**
+* @brief  USBD_CtlError 
+*         Handle USB low level Error
+* @param  pdev: device instance
+* @param  req: usb request
+* @retval None
+*/
+
+void USBD_CtlError( USB_OTG_CORE_HANDLE  *pdev,
+                            USB_SETUP_REQ *req)
+{
+  
+  DCD_EP_Stall(pdev , 0x80);
+  DCD_EP_Stall(pdev , 0);
+  USB_OTG_EP0_OutStart(pdev);  
+}
+
+
+/**
+  * @brief  USBD_GetString
+  *         Convert Ascii string into unicode one
+  * @param  desc : descriptor buffer
+  * @param  unicode : Formatted string buffer (unicode)
+  * @param  len : descriptor length
+  * @retval None
+  */
+void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len)
+{
+  uint8_t idx = 0;
+  
+  if (desc != NULL) 
+  {
+    *len =  USBD_GetLen(desc) * 2 + 2;    
+    unicode[idx++] = *len;
+    unicode[idx++] =  USB_DESC_TYPE_STRING;
+    
+    while (*desc != 0)
+    {
+      unicode[idx++] = *desc++;
+      unicode[idx++] =  0x00;
+    }
+  } 
+}
+
+/**
+  * @brief  USBD_GetLen
+  *         return the string length
+   * @param  buf : pointer to the ascii string buffer
+  * @retval string length
+  */
+static uint8_t USBD_GetLen(uint8_t *buf)
+{
+    uint8_t  len = 0;
+
+    while (*buf != 0)
+    {
+        len++;
+        buf++;
+    }
+
+    return len;
+}
+/**
+  * @}
+  */ 
+
+
+/**
+  * @}
+  */ 
+
+
+/**
+  * @}
+  */ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Release_Notes.html b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Release_Notes.html
new file mode 100644
index 0000000000000000000000000000000000000000..60f8ab872fa397ce0a07b799dda04ab9e9340425
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_Device_Library/Release_Notes.html
@@ -0,0 +1,950 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html xmlns:v="urn:schemas-microsoft-com:vml" xmlns:o="urn:schemas-microsoft-com:office:office" xmlns:w="urn:schemas-microsoft-com:office:word" xmlns:m="http://schemas.microsoft.com/office/2004/12/omml" xmlns="http://www.w3.org/TR/REC-html40"><head>
+<meta http-equiv="Content-Type" content="text/html; charset=windows-1252">
+<link rel="File-List" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/filelist.xml">
+<link rel="Edit-Time-Data" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/editdata.mso"><!--[if !mso]>
+<style>
+v\:* {behavior:url(#default#VML);}
+o\:* {behavior:url(#default#VML);}
+w\:* {behavior:url(#default#VML);}
+.shape {behavior:url(#default#VML);}
+</style>
+<![endif]-->
+
+
+
+<title>Release Notes for STM32F105/7xx, STM32F2xx and STM32F4xx USB Device Library</title><!--[if gte mso 9]><xml>
+ <o:DocumentProperties>
+  <o:Author>STMicroelectronics</o:Author>
+  <o:LastAuthor>Raouf Hosni</o:LastAuthor>
+  <o:Revision>39</o:Revision>
+  <o:TotalTime>137</o:TotalTime>
+  <o:Created>2009-02-27T19:26:00Z</o:Created>
+  <o:LastSaved>2010-10-15T11:07:00Z</o:LastSaved>
+  <o:Pages>3</o:Pages>
+  <o:Words>973</o:Words>
+  <o:Characters>5548</o:Characters>
+  <o:Company>STMicroelectronics</o:Company>
+  <o:Lines>46</o:Lines>
+  <o:Paragraphs>13</o:Paragraphs>
+  <o:CharactersWithSpaces>6508</o:CharactersWithSpaces>
+  <o:Version>12.00</o:Version>
+ </o:DocumentProperties>
+</xml><![endif]--><link rel="themeData" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/themedata.thmx">
+<link rel="colorSchemeMapping" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/colorschememapping.xml"><!--[if gte mso 9]><xml>
+ <w:WordDocument>
+  <w:Zoom>110</w:Zoom>
+  <w:TrackMoves>false</w:TrackMoves>
+  <w:TrackFormatting/>
+  <w:ValidateAgainstSchemas/>
+  <w:SaveIfXMLInvalid>false</w:SaveIfXMLInvalid>
+  <w:IgnoreMixedContent>false</w:IgnoreMixedContent>
+  <w:AlwaysShowPlaceholderText>false</w:AlwaysShowPlaceholderText>
+  <w:DoNotPromoteQF/>
+  <w:LidThemeOther>EN-US</w:LidThemeOther>
+  <w:LidThemeAsian>X-NONE</w:LidThemeAsian>
+  <w:LidThemeComplexScript>X-NONE</w:LidThemeComplexScript>
+  <w:Compatibility>
+   <w:BreakWrappedTables/>
+   <w:SnapToGridInCell/>
+   <w:WrapTextWithPunct/>
+   <w:UseAsianBreakRules/>
+   <w:DontGrowAutofit/>
+   <w:SplitPgBreakAndParaMark/>
+   <w:DontVertAlignCellWithSp/>
+   <w:DontBreakConstrainedForcedTables/>
+   <w:DontVertAlignInTxbx/>
+   <w:Word11KerningPairs/>
+   <w:CachedColBalance/>
+  </w:Compatibility>
+  <w:BrowserLevel>MicrosoftInternetExplorer4</w:BrowserLevel>
+  <m:mathPr>
+   <m:mathFont m:val="Cambria Math"/>
+   <m:brkBin m:val="before"/>
+   <m:brkBinSub m:val="&#45;-"/>
+   <m:smallFrac m:val="off"/>
+   <m:dispDef/>
+   <m:lMargin m:val="0"/>
+   <m:rMargin m:val="0"/>
+   <m:defJc m:val="centerGroup"/>
+   <m:wrapIndent m:val="1440"/>
+   <m:intLim m:val="subSup"/>
+   <m:naryLim m:val="undOvr"/>
+  </m:mathPr></w:WordDocument>
+</xml><![endif]--><!--[if gte mso 9]><xml>
+ <w:LatentStyles DefLockedState="false" DefUnhideWhenUsed="false"
+  DefSemiHidden="false" DefQFormat="false" LatentStyleCount="267">
+  <w:LsdException Locked="false" QFormat="true" Name="Normal"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 1"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 2"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 3"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 4"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 5"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 6"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 7"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 8"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 9"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="caption"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Title"/>
+  <w:LsdException Locked="false" Priority="1" Name="Default Paragraph Font"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Subtitle"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Strong"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Emphasis"/>
+  <w:LsdException Locked="false" Priority="99" Name="No List"/>
+  <w:LsdException Locked="false" Priority="99" SemiHidden="true"
+   Name="Placeholder Text"/>
+  <w:LsdException Locked="false" Priority="1" QFormat="true" Name="No Spacing"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 1"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 1"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 1"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="99" SemiHidden="true" Name="Revision"/>
+  <w:LsdException Locked="false" Priority="34" QFormat="true"
+   Name="List Paragraph"/>
+  <w:LsdException Locked="false" Priority="29" QFormat="true" Name="Quote"/>
+  <w:LsdException Locked="false" Priority="30" QFormat="true"
+   Name="Intense Quote"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 1"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 1"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 1"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 1"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 1"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 2"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 2"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 2"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 2"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 2"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 2"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 2"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 2"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 3"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 3"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 3"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 3"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 3"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 3"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 3"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 3"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 4"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 4"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 4"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 4"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 4"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 4"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 4"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 4"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 5"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 5"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 5"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 5"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 5"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 5"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 5"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 5"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 6"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 6"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 6"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 6"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 6"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 6"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 6"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 6"/>
+  <w:LsdException Locked="false" Priority="19" QFormat="true"
+   Name="Subtle Emphasis"/>
+  <w:LsdException Locked="false" Priority="21" QFormat="true"
+   Name="Intense Emphasis"/>
+  <w:LsdException Locked="false" Priority="31" QFormat="true"
+   Name="Subtle Reference"/>
+  <w:LsdException Locked="false" Priority="32" QFormat="true"
+   Name="Intense Reference"/>
+  <w:LsdException Locked="false" Priority="33" QFormat="true" Name="Book Title"/>
+  <w:LsdException Locked="false" Priority="37" SemiHidden="true"
+   UnhideWhenUsed="true" Name="Bibliography"/>
+  <w:LsdException Locked="false" Priority="39" SemiHidden="true"
+   UnhideWhenUsed="true" QFormat="true" Name="TOC Heading"/>
+ </w:LatentStyles>
+</xml><![endif]-->
+
+<style>
+<!--
+ /* Font Definitions */
+ @font-face
+	{font-family:"Cambria Math";
+	panose-1:2 4 5 3 5 4 6 3 2 4;
+	mso-font-charset:1;
+	mso-generic-font-family:roman;
+	mso-font-format:other;
+	mso-font-pitch:variable;
+	mso-font-signature:0 0 0 0 0 0;}
+@font-face
+	{font-family:Calibri;
+	panose-1:2 15 5 2 2 2 4 3 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:-1610611985 1073750139 0 0 159 0;}
+@font-face
+	{font-family:Tahoma;
+	panose-1:2 11 6 4 3 5 4 4 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:1627400839 -2147483648 8 0 66047 0;}
+@font-face
+	{font-family:Verdana;
+	panose-1:2 11 6 4 3 5 4 4 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:536871559 0 0 0 415 0;}
+ /* Style Definitions */
+ p.MsoNormal, li.MsoNormal, div.MsoNormal
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-parent:"";
+	margin:0in;
+	margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:12.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";}
+h1
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 1 Char";
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	mso-outline-level:1;
+	font-size:24.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;}
+h2
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 2 Char";
+	mso-style-next:Normal;
+	margin-top:12.0pt;
+	margin-right:0in;
+	margin-bottom:3.0pt;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	page-break-after:avoid;
+	mso-outline-level:2;
+	font-size:14.0pt;
+	font-family:"Arial","sans-serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;
+	font-style:italic;}
+h3
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 3 Char";
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	mso-outline-level:3;
+	font-size:13.5pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;}
+a:link, span.MsoHyperlink
+	{mso-style-unhide:no;
+	color:blue;
+	text-decoration:underline;
+	text-underline:single;}
+a:visited, span.MsoHyperlinkFollowed
+	{mso-style-unhide:no;
+	color:blue;
+	text-decoration:underline;
+	text-underline:single;}
+p
+	{mso-style-unhide:no;
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	font-size:12.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";}
+p.MsoAcetate, li.MsoAcetate, div.MsoAcetate
+	{mso-style-unhide:no;
+	mso-style-link:"Balloon Text Char";
+	margin:0in;
+	margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:8.0pt;
+	font-family:"Tahoma","sans-serif";
+	mso-fareast-font-family:"Times New Roman";}
+span.Heading1Char
+	{mso-style-name:"Heading 1 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 1";
+	mso-ansi-font-size:14.0pt;
+	mso-bidi-font-size:14.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#365F91;
+	mso-themecolor:accent1;
+	mso-themeshade:191;
+	font-weight:bold;}
+span.Heading2Char
+	{mso-style-name:"Heading 2 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 2";
+	mso-ansi-font-size:13.0pt;
+	mso-bidi-font-size:13.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#4F81BD;
+	mso-themecolor:accent1;
+	font-weight:bold;}
+span.Heading3Char
+	{mso-style-name:"Heading 3 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 3";
+	mso-ansi-font-size:12.0pt;
+	mso-bidi-font-size:12.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#4F81BD;
+	mso-themecolor:accent1;
+	font-weight:bold;}
+span.BalloonTextChar
+	{mso-style-name:"Balloon Text Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Balloon Text";
+	mso-ansi-font-size:8.0pt;
+	mso-bidi-font-size:8.0pt;
+	font-family:"Tahoma","sans-serif";
+	mso-ascii-font-family:Tahoma;
+	mso-hansi-font-family:Tahoma;
+	mso-bidi-font-family:Tahoma;}
+.MsoChpDefault
+	{mso-style-type:export-only;
+	mso-default-props:yes;
+	font-size:10.0pt;
+	mso-ansi-font-size:10.0pt;
+	mso-bidi-font-size:10.0pt;}
+@page WordSection1
+	{size:8.5in 11.0in;
+	margin:1.0in 1.25in 1.0in 1.25in;
+	mso-header-margin:.5in;
+	mso-footer-margin:.5in;
+	mso-paper-source:0;}
+div.WordSection1
+	{page:WordSection1;}
+ /* List Definitions */
+ @list l0
+	{mso-list-id:62067358;
+	mso-list-template-ids:-174943062;}
+@list l0:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l0:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1
+	{mso-list-id:128015942;
+	mso-list-template-ids:-90681214;}
+@list l1:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2
+	{mso-list-id:216556000;
+	mso-list-template-ids:925924412;}
+@list l2:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l2:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l2:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3
+	{mso-list-id:562446694;
+	mso-list-template-ids:913898366;}
+@list l3:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l3:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4
+	{mso-list-id:797802132;
+	mso-list-template-ids:-1971191336;}
+@list l4:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5
+	{mso-list-id:907304066;
+	mso-list-template-ids:1969781532;}
+@list l5:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6
+	{mso-list-id:1050613616;
+	mso-list-template-ids:-1009886748;}
+@list l6:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l6:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l6:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7
+	{mso-list-id:1234970193;
+	mso-list-template-ids:2055904002;}
+@list l7:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l7:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l7:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8
+	{mso-list-id:1846092290;
+	mso-list-template-ids:-768590846;}
+@list l8:level1
+	{mso-level-start-at:2;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9
+	{mso-list-id:1894656566;
+	mso-list-template-ids:1199983812;}
+@list l9:level1
+	{mso-level-start-at:2;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+ol
+	{margin-bottom:0in;}
+ul
+	{margin-bottom:0in;}
+-->
+</style><!--[if gte mso 10]>
+<style>
+ /* Style Definitions */
+ table.MsoNormalTable
+	{mso-style-name:"Table Normal";
+	mso-tstyle-rowband-size:0;
+	mso-tstyle-colband-size:0;
+	mso-style-noshow:yes;
+	mso-style-priority:99;
+	mso-style-qformat:yes;
+	mso-style-parent:"";
+	mso-padding-alt:0in 5.4pt 0in 5.4pt;
+	mso-para-margin:0in;
+	mso-para-margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:10.0pt;
+	font-family:"Times New Roman","serif";}
+</style>
+<![endif]--><!--[if gte mso 9]><xml>
+ <o:shapedefaults v:ext="edit" spidmax="7170"/>
+</xml><![endif]--><!--[if gte mso 9]><xml>
+ <o:shapelayout v:ext="edit">
+  <o:idmap v:ext="edit" data="1"/>
+ </o:shapelayout></xml><![endif]--><meta content="MCD Application Team" name="author"></head>
+<body style="" link="blue" vlink="blue">
+
+<div class="WordSection1">
+
+<p class="MsoNormal"><span style="font-family: &quot;Arial&quot;,&quot;sans-serif&quot;;"><o:p>&nbsp;</o:p></span></p>
+
+<div align="center">
+
+<table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+ <tbody><tr style="">
+  <td style="padding: 0in;" valign="top">
+  <table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+   <tbody><tr style="">
+    <td style="padding: 0in 5.4pt;" valign="top">
+    <p class="MsoNormal"><span style="font-size: 8pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: blue;"><a href="../../Release_Notes.html">Back to Release page</a></span><span style="font-size: 10pt;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+   <tr style="">
+    <td style="padding: 1.5pt;">
+    <h1 style="margin-bottom: 0.25in; text-align: center;" align="center"><span style="font-size: 20pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: rgb(51, 102, 255);">Release Notes for STM32F105/7xx, STM32F2xx and STM32F4xx&nbsp;USB Device Library</span><span style="font-size: 20pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><o:p></o:p></span></h1>
+    <p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: black;">Copyright
+    2012 STMicroelectronics</span><span style="color: black;"><u1:p></u1:p><o:p></o:p></span></p>
+    <p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: black;"><img style="border: 0px solid ; width: 86px; height: 65px;" alt="" id="_x0000_i1026" src="../../_htmresc/logo.bmp"></span><span style="font-size: 10pt;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+  </tbody></table>
+  <p class="MsoNormal"><span style="font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; display: none;"><o:p>&nbsp;</o:p></span></p>
+  <table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" width="900">
+   <tbody><tr style="">
+    <td style="padding: 0in;" valign="top">
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><span style="font-size: 12pt; color: white;">Contents<o:p></o:p></span></h2>
+    <ol style="margin-top: 0in;" start="1" type="1">
+     <li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><a href="#History">Update History</a><o:p></o:p></span></li>
+     <li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><a href="#License">License</a><o:p></o:p></span></li>
+    </ol>
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="History"></a><span style="font-size: 12pt; color: white;">Update History</span></h2><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 200px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.1.0 / 19-March-2012<o:p></o:p></span></h3>
+            <p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+
+            <ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Official support of </span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;">STM32F4xx</span> devices</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">All source files: license disclaimer text update and add link to the License file on ST Internet.<br></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Handle test mode in the set feature request</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Handle dynamically the USB SELF POWERED feature</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Handle correctly the USBD_CtlError process to take into account error during Control OUT stage</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Miscellaneous bug fix</span></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 171px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0 / 22-July-2011<o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">First official version for <span style="font-weight: bold; font-style: italic;">STM32F105/7xx</span> and <span style="font-weight: bold; font-style: italic;">STM32F2xx</span> devices</span></li></ul><span style="font-size: 10pt; font-family: Verdana;"></span><br><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"></span>
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="License"></a><span style="font-size: 12pt; color: white;">License<o:p></o:p></span></h2>
+    <p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use this&nbsp;</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">package</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"> except in compliance with the License. You may obtain a copy of the License at:<br><br></span></p><div style="text-align: center;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp; <a target="_blank" href="http://www.st.com/software_license_agreement_liberty_v2">http://www.st.com/software_license_agreement_liberty_v2</a></span><br><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"></span></div><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"><br>Unless
+required by applicable law or agreed to in writing, software
+distributed under the License is distributed on an "AS IS" BASIS, <br>WITHOUT
+WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See
+the License for the specific language governing permissions and
+limitations under the License.</span>
+    <div class="MsoNormal" style="text-align: center;" align="center"><span style="color: black;">
+    <hr align="center" size="2" width="100%">
+    </span></div>
+    <p class="MsoNormal" style="margin: 4.5pt 0in 4.5pt 0.25in; text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">For
+    complete documentation on </span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">STM32<span style="color: black;">
+    Microcontrollers visit </span><u><span style="color: blue;"><a href="http://www.st.com/internet/mcu/family/141.jsp" target="_blank">www.st.com/STM32</a></span></u></span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><u><span style="color: blue;"><a href="http://www.st.com/stm32" target="_blank"></a></span></u></span><span style="color: black;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+  </tbody></table>
+  <p class="MsoNormal"><span style="font-size: 10pt;"><o:p></o:p></span></p>
+  </td>
+ </tr>
+</tbody></table>
+
+</div>
+
+<p class="MsoNormal"><o:p>&nbsp;</o:p></p>
+
+</div>
+
+</body></html>
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/Release_Notes.html b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/Release_Notes.html
new file mode 100644
index 0000000000000000000000000000000000000000..1116edd3e14b97c21e21e619a636d31450c8e0a4
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/Release_Notes.html
@@ -0,0 +1,950 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html xmlns:v="urn:schemas-microsoft-com:vml" xmlns:o="urn:schemas-microsoft-com:office:office" xmlns:w="urn:schemas-microsoft-com:office:word" xmlns:m="http://schemas.microsoft.com/office/2004/12/omml" xmlns="http://www.w3.org/TR/REC-html40"><head>
+<meta http-equiv="Content-Type" content="text/html; charset=windows-1252">
+<link rel="File-List" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/filelist.xml">
+<link rel="Edit-Time-Data" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/editdata.mso"><!--[if !mso]>
+<style>
+v\:* {behavior:url(#default#VML);}
+o\:* {behavior:url(#default#VML);}
+w\:* {behavior:url(#default#VML);}
+.shape {behavior:url(#default#VML);}
+</style>
+<![endif]-->
+
+
+
+<title>Release Notes for STM32F105/7xx, STM32F2xx and STM32F4xx USB OTG Driver</title><!--[if gte mso 9]><xml>
+ <o:DocumentProperties>
+  <o:Author>STMicroelectronics</o:Author>
+  <o:LastAuthor>Raouf Hosni</o:LastAuthor>
+  <o:Revision>39</o:Revision>
+  <o:TotalTime>137</o:TotalTime>
+  <o:Created>2009-02-27T19:26:00Z</o:Created>
+  <o:LastSaved>2010-10-15T11:07:00Z</o:LastSaved>
+  <o:Pages>3</o:Pages>
+  <o:Words>973</o:Words>
+  <o:Characters>5548</o:Characters>
+  <o:Company>STMicroelectronics</o:Company>
+  <o:Lines>46</o:Lines>
+  <o:Paragraphs>13</o:Paragraphs>
+  <o:CharactersWithSpaces>6508</o:CharactersWithSpaces>
+  <o:Version>12.00</o:Version>
+ </o:DocumentProperties>
+</xml><![endif]--><link rel="themeData" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/themedata.thmx">
+<link rel="colorSchemeMapping" href="Release_Notes_for_STM32F2xx_StdPeriph_Driver_files/colorschememapping.xml"><!--[if gte mso 9]><xml>
+ <w:WordDocument>
+  <w:Zoom>110</w:Zoom>
+  <w:TrackMoves>false</w:TrackMoves>
+  <w:TrackFormatting/>
+  <w:ValidateAgainstSchemas/>
+  <w:SaveIfXMLInvalid>false</w:SaveIfXMLInvalid>
+  <w:IgnoreMixedContent>false</w:IgnoreMixedContent>
+  <w:AlwaysShowPlaceholderText>false</w:AlwaysShowPlaceholderText>
+  <w:DoNotPromoteQF/>
+  <w:LidThemeOther>EN-US</w:LidThemeOther>
+  <w:LidThemeAsian>X-NONE</w:LidThemeAsian>
+  <w:LidThemeComplexScript>X-NONE</w:LidThemeComplexScript>
+  <w:Compatibility>
+   <w:BreakWrappedTables/>
+   <w:SnapToGridInCell/>
+   <w:WrapTextWithPunct/>
+   <w:UseAsianBreakRules/>
+   <w:DontGrowAutofit/>
+   <w:SplitPgBreakAndParaMark/>
+   <w:DontVertAlignCellWithSp/>
+   <w:DontBreakConstrainedForcedTables/>
+   <w:DontVertAlignInTxbx/>
+   <w:Word11KerningPairs/>
+   <w:CachedColBalance/>
+  </w:Compatibility>
+  <w:BrowserLevel>MicrosoftInternetExplorer4</w:BrowserLevel>
+  <m:mathPr>
+   <m:mathFont m:val="Cambria Math"/>
+   <m:brkBin m:val="before"/>
+   <m:brkBinSub m:val="&#45;-"/>
+   <m:smallFrac m:val="off"/>
+   <m:dispDef/>
+   <m:lMargin m:val="0"/>
+   <m:rMargin m:val="0"/>
+   <m:defJc m:val="centerGroup"/>
+   <m:wrapIndent m:val="1440"/>
+   <m:intLim m:val="subSup"/>
+   <m:naryLim m:val="undOvr"/>
+  </m:mathPr></w:WordDocument>
+</xml><![endif]--><!--[if gte mso 9]><xml>
+ <w:LatentStyles DefLockedState="false" DefUnhideWhenUsed="false"
+  DefSemiHidden="false" DefQFormat="false" LatentStyleCount="267">
+  <w:LsdException Locked="false" QFormat="true" Name="Normal"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 1"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 2"/>
+  <w:LsdException Locked="false" QFormat="true" Name="heading 3"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 4"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 5"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 6"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 7"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 8"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="heading 9"/>
+  <w:LsdException Locked="false" SemiHidden="true" UnhideWhenUsed="true"
+   QFormat="true" Name="caption"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Title"/>
+  <w:LsdException Locked="false" Priority="1" Name="Default Paragraph Font"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Subtitle"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Strong"/>
+  <w:LsdException Locked="false" QFormat="true" Name="Emphasis"/>
+  <w:LsdException Locked="false" Priority="99" Name="No List"/>
+  <w:LsdException Locked="false" Priority="99" SemiHidden="true"
+   Name="Placeholder Text"/>
+  <w:LsdException Locked="false" Priority="1" QFormat="true" Name="No Spacing"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 1"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 1"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 1"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="99" SemiHidden="true" Name="Revision"/>
+  <w:LsdException Locked="false" Priority="34" QFormat="true"
+   Name="List Paragraph"/>
+  <w:LsdException Locked="false" Priority="29" QFormat="true" Name="Quote"/>
+  <w:LsdException Locked="false" Priority="30" QFormat="true"
+   Name="Intense Quote"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 1"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 1"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 1"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 1"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 1"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 1"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 1"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 2"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 2"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 2"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 2"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 2"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 2"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 2"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 2"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 2"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 2"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 3"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 3"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 3"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 3"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 3"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 3"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 3"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 3"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 3"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 3"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 4"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 4"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 4"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 4"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 4"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 4"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 4"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 4"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 4"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 4"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 5"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 5"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 5"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 5"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 5"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 5"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 5"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 5"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 5"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 5"/>
+  <w:LsdException Locked="false" Priority="60" Name="Light Shading Accent 6"/>
+  <w:LsdException Locked="false" Priority="61" Name="Light List Accent 6"/>
+  <w:LsdException Locked="false" Priority="62" Name="Light Grid Accent 6"/>
+  <w:LsdException Locked="false" Priority="63" Name="Medium Shading 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="64" Name="Medium Shading 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="65" Name="Medium List 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="66" Name="Medium List 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="67" Name="Medium Grid 1 Accent 6"/>
+  <w:LsdException Locked="false" Priority="68" Name="Medium Grid 2 Accent 6"/>
+  <w:LsdException Locked="false" Priority="69" Name="Medium Grid 3 Accent 6"/>
+  <w:LsdException Locked="false" Priority="70" Name="Dark List Accent 6"/>
+  <w:LsdException Locked="false" Priority="71" Name="Colorful Shading Accent 6"/>
+  <w:LsdException Locked="false" Priority="72" Name="Colorful List Accent 6"/>
+  <w:LsdException Locked="false" Priority="73" Name="Colorful Grid Accent 6"/>
+  <w:LsdException Locked="false" Priority="19" QFormat="true"
+   Name="Subtle Emphasis"/>
+  <w:LsdException Locked="false" Priority="21" QFormat="true"
+   Name="Intense Emphasis"/>
+  <w:LsdException Locked="false" Priority="31" QFormat="true"
+   Name="Subtle Reference"/>
+  <w:LsdException Locked="false" Priority="32" QFormat="true"
+   Name="Intense Reference"/>
+  <w:LsdException Locked="false" Priority="33" QFormat="true" Name="Book Title"/>
+  <w:LsdException Locked="false" Priority="37" SemiHidden="true"
+   UnhideWhenUsed="true" Name="Bibliography"/>
+  <w:LsdException Locked="false" Priority="39" SemiHidden="true"
+   UnhideWhenUsed="true" QFormat="true" Name="TOC Heading"/>
+ </w:LatentStyles>
+</xml><![endif]-->
+
+<style>
+<!--
+ /* Font Definitions */
+ @font-face
+	{font-family:"Cambria Math";
+	panose-1:2 4 5 3 5 4 6 3 2 4;
+	mso-font-charset:1;
+	mso-generic-font-family:roman;
+	mso-font-format:other;
+	mso-font-pitch:variable;
+	mso-font-signature:0 0 0 0 0 0;}
+@font-face
+	{font-family:Calibri;
+	panose-1:2 15 5 2 2 2 4 3 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:-1610611985 1073750139 0 0 159 0;}
+@font-face
+	{font-family:Tahoma;
+	panose-1:2 11 6 4 3 5 4 4 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:1627400839 -2147483648 8 0 66047 0;}
+@font-face
+	{font-family:Verdana;
+	panose-1:2 11 6 4 3 5 4 4 2 4;
+	mso-font-charset:0;
+	mso-generic-font-family:swiss;
+	mso-font-pitch:variable;
+	mso-font-signature:536871559 0 0 0 415 0;}
+ /* Style Definitions */
+ p.MsoNormal, li.MsoNormal, div.MsoNormal
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-parent:"";
+	margin:0in;
+	margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:12.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";}
+h1
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 1 Char";
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	mso-outline-level:1;
+	font-size:24.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;}
+h2
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 2 Char";
+	mso-style-next:Normal;
+	margin-top:12.0pt;
+	margin-right:0in;
+	margin-bottom:3.0pt;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	page-break-after:avoid;
+	mso-outline-level:2;
+	font-size:14.0pt;
+	font-family:"Arial","sans-serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;
+	font-style:italic;}
+h3
+	{mso-style-unhide:no;
+	mso-style-qformat:yes;
+	mso-style-link:"Heading 3 Char";
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	mso-outline-level:3;
+	font-size:13.5pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:minor-fareast;
+	font-weight:bold;}
+a:link, span.MsoHyperlink
+	{mso-style-unhide:no;
+	color:blue;
+	text-decoration:underline;
+	text-underline:single;}
+a:visited, span.MsoHyperlinkFollowed
+	{mso-style-unhide:no;
+	color:blue;
+	text-decoration:underline;
+	text-underline:single;}
+p
+	{mso-style-unhide:no;
+	mso-margin-top-alt:auto;
+	margin-right:0in;
+	mso-margin-bottom-alt:auto;
+	margin-left:0in;
+	mso-pagination:widow-orphan;
+	font-size:12.0pt;
+	font-family:"Times New Roman","serif";
+	mso-fareast-font-family:"Times New Roman";}
+p.MsoAcetate, li.MsoAcetate, div.MsoAcetate
+	{mso-style-unhide:no;
+	mso-style-link:"Balloon Text Char";
+	margin:0in;
+	margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:8.0pt;
+	font-family:"Tahoma","sans-serif";
+	mso-fareast-font-family:"Times New Roman";}
+span.Heading1Char
+	{mso-style-name:"Heading 1 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 1";
+	mso-ansi-font-size:14.0pt;
+	mso-bidi-font-size:14.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#365F91;
+	mso-themecolor:accent1;
+	mso-themeshade:191;
+	font-weight:bold;}
+span.Heading2Char
+	{mso-style-name:"Heading 2 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 2";
+	mso-ansi-font-size:13.0pt;
+	mso-bidi-font-size:13.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#4F81BD;
+	mso-themecolor:accent1;
+	font-weight:bold;}
+span.Heading3Char
+	{mso-style-name:"Heading 3 Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Heading 3";
+	mso-ansi-font-size:12.0pt;
+	mso-bidi-font-size:12.0pt;
+	font-family:"Cambria","serif";
+	mso-ascii-font-family:Cambria;
+	mso-ascii-theme-font:major-latin;
+	mso-fareast-font-family:"Times New Roman";
+	mso-fareast-theme-font:major-fareast;
+	mso-hansi-font-family:Cambria;
+	mso-hansi-theme-font:major-latin;
+	mso-bidi-font-family:"Times New Roman";
+	mso-bidi-theme-font:major-bidi;
+	color:#4F81BD;
+	mso-themecolor:accent1;
+	font-weight:bold;}
+span.BalloonTextChar
+	{mso-style-name:"Balloon Text Char";
+	mso-style-unhide:no;
+	mso-style-locked:yes;
+	mso-style-link:"Balloon Text";
+	mso-ansi-font-size:8.0pt;
+	mso-bidi-font-size:8.0pt;
+	font-family:"Tahoma","sans-serif";
+	mso-ascii-font-family:Tahoma;
+	mso-hansi-font-family:Tahoma;
+	mso-bidi-font-family:Tahoma;}
+.MsoChpDefault
+	{mso-style-type:export-only;
+	mso-default-props:yes;
+	font-size:10.0pt;
+	mso-ansi-font-size:10.0pt;
+	mso-bidi-font-size:10.0pt;}
+@page WordSection1
+	{size:8.5in 11.0in;
+	margin:1.0in 1.25in 1.0in 1.25in;
+	mso-header-margin:.5in;
+	mso-footer-margin:.5in;
+	mso-paper-source:0;}
+div.WordSection1
+	{page:WordSection1;}
+ /* List Definitions */
+ @list l0
+	{mso-list-id:62067358;
+	mso-list-template-ids:-174943062;}
+@list l0:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l0:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l0:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1
+	{mso-list-id:128015942;
+	mso-list-template-ids:-90681214;}
+@list l1:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l1:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2
+	{mso-list-id:216556000;
+	mso-list-template-ids:925924412;}
+@list l2:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l2:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l2:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l2:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3
+	{mso-list-id:562446694;
+	mso-list-template-ids:913898366;}
+@list l3:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l3:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l3:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4
+	{mso-list-id:797802132;
+	mso-list-template-ids:-1971191336;}
+@list l4:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l4:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5
+	{mso-list-id:907304066;
+	mso-list-template-ids:1969781532;}
+@list l5:level1
+	{mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l5:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6
+	{mso-list-id:1050613616;
+	mso-list-template-ids:-1009886748;}
+@list l6:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l6:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l6:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l6:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7
+	{mso-list-id:1234970193;
+	mso-list-template-ids:2055904002;}
+@list l7:level1
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l7:level2
+	{mso-level-number-format:bullet;
+	mso-level-text:\F0B7;
+	mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;
+	mso-ansi-font-size:10.0pt;
+	font-family:Symbol;}
+@list l7:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l7:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8
+	{mso-list-id:1846092290;
+	mso-list-template-ids:-768590846;}
+@list l8:level1
+	{mso-level-start-at:2;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l8:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9
+	{mso-list-id:1894656566;
+	mso-list-template-ids:1199983812;}
+@list l9:level1
+	{mso-level-start-at:2;
+	mso-level-tab-stop:.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level2
+	{mso-level-tab-stop:1.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level3
+	{mso-level-tab-stop:1.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level4
+	{mso-level-tab-stop:2.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level5
+	{mso-level-tab-stop:2.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level6
+	{mso-level-tab-stop:3.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level7
+	{mso-level-tab-stop:3.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level8
+	{mso-level-tab-stop:4.0in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+@list l9:level9
+	{mso-level-tab-stop:4.5in;
+	mso-level-number-position:left;
+	text-indent:-.25in;}
+ol
+	{margin-bottom:0in;}
+ul
+	{margin-bottom:0in;}
+-->
+</style><!--[if gte mso 10]>
+<style>
+ /* Style Definitions */
+ table.MsoNormalTable
+	{mso-style-name:"Table Normal";
+	mso-tstyle-rowband-size:0;
+	mso-tstyle-colband-size:0;
+	mso-style-noshow:yes;
+	mso-style-priority:99;
+	mso-style-qformat:yes;
+	mso-style-parent:"";
+	mso-padding-alt:0in 5.4pt 0in 5.4pt;
+	mso-para-margin:0in;
+	mso-para-margin-bottom:.0001pt;
+	mso-pagination:widow-orphan;
+	font-size:10.0pt;
+	font-family:"Times New Roman","serif";}
+</style>
+<![endif]--><!--[if gte mso 9]><xml>
+ <o:shapedefaults v:ext="edit" spidmax="7170"/>
+</xml><![endif]--><!--[if gte mso 9]><xml>
+ <o:shapelayout v:ext="edit">
+  <o:idmap v:ext="edit" data="1"/>
+ </o:shapelayout></xml><![endif]--><meta content="MCD Application Team" name="author"></head>
+<body style="" link="blue" vlink="blue">
+
+<div class="WordSection1">
+
+<p class="MsoNormal"><span style="font-family: &quot;Arial&quot;,&quot;sans-serif&quot;;"><o:p>&nbsp;</o:p></span></p>
+
+<div align="center">
+
+<table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+ <tbody><tr style="">
+  <td style="padding: 0in;" valign="top">
+  <table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" cellspacing="0" width="900">
+   <tbody><tr style="">
+    <td style="padding: 0in 5.4pt;" valign="top">
+    <p class="MsoNormal"><span style="font-size: 8pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: blue;"><a href="../../Release_Notes.html">Back to Release page</a></span><span style="font-size: 10pt;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+   <tr style="">
+    <td style="padding: 1.5pt;">
+    <h1 style="margin-bottom: 0.25in; text-align: center;" align="center"><span style="font-size: 20pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: rgb(51, 102, 255);">Release Notes for STM32F105/7xx, STM32F2xx and STM32F4xx USB OTG Driver</span><span style="font-size: 20pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><o:p></o:p></span></h1>
+    <p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: black;">Copyright
+    2012 STMicroelectronics</span><span style="color: black;"><u1:p></u1:p><o:p></o:p></span></p>
+    <p class="MsoNormal" style="text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; color: black;"><img id="_x0000_i1026" src="../../_htmresc/logo.bmp" border="0" height="65" width="86"></span><span style="font-size: 10pt;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+  </tbody></table>
+  <p class="MsoNormal"><span style="font-family: &quot;Arial&quot;,&quot;sans-serif&quot;; display: none;"><o:p>&nbsp;</o:p></span></p>
+  <table class="MsoNormalTable" style="width: 675pt;" border="0" cellpadding="0" width="900">
+   <tbody><tr style="">
+    <td style="padding: 0in;" valign="top">
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><span style="font-size: 12pt; color: white;">Contents<o:p></o:p></span></h2>
+    <ol style="margin-top: 0in;" start="1" type="1">
+     <li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><a href="#History">Update History</a><o:p></o:p></span></li>
+     <li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><a href="#License">License</a><o:p></o:p></span></li>
+    </ol>
+    <h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="History"></a><span style="font-size: 12pt; color: white;">Update History</span></h2><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 200px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V2.1.0 / 19-March-2012<o:p></o:p></span></h3>
+            <p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+
+            <ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Official support of </span><span style="font-size: 10pt; font-family: Verdana;"><span style="font-weight: bold; font-style: italic;">STM32F4xx</span> devices</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">All source files: license disclaimer text update and add link to the License file on ST Internet</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Unmask Session request interrupt to handle the connect event during the core start-up</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Remove any reference to the USB HS external I2C PHY</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Update optimization pragma for AR Compiler</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Handle Correctly the Low Speed device connection in HS mode</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add a wrapper to isolate the library from the low level driver: connection done through ISR structure<br></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Miscellaneous bug fix</span></li></ul><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 171px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V2.0.0 / 22-July-2011 <o:p></o:p></span></h3><p class="MsoNormal" style="margin: 4.5pt 0cm 4.5pt 18pt;"><b style=""><u><span style="font-size: 10pt; font-family: Verdana; color: black;">Main
+Changes<o:p></o:p></span></u></b></p>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Second official version supporting <span style="font-weight: bold; font-style: italic;">STM32F105/7</span> and <span style="font-weight: bold; font-style: italic;">STM32F2xx</span> devices</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Rename the Library from "<span style="font-style: italic;">STM32_USB_HOST_Driver</span>" to "<span style="font-style: italic;">STM32_USB_OTG_Driver</span>"</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add support for <span style="font-weight: bold; font-style: italic;">STM32F2xx</span> devices</span><span style="font-size: 10pt; font-family: Verdana;"></span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add support for Device and OTG modes</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Change HCD layer to support High speed core</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Change the Low level driver to support multi core support for Host mode</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Add Stop mechanism for Host and Device modes</span></li><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Change VBUS enabling method, to use the external or the internal VBUS when using the ULPI</span></li></ul><span style="font-size: 10pt; font-family: Verdana;"></span><h3 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial; margin-right: 500pt; width: 171px;"><span style="font-size: 10pt; font-family: Arial; color: white;">V1.0.0&nbsp;- 11/29/2010<o:p></o:p></span></h3>
+<ul style="margin-top: 0cm;" type="square"><li class="MsoNormal" style="color: black; margin-top: 4.5pt; margin-bottom: 4.5pt;"><span style="font-size: 10pt; font-family: Verdana;">Created&nbsp;</span></li></ul><h2 style="background: rgb(51, 102, 255) none repeat scroll 0% 50%; -moz-background-clip: initial; -moz-background-origin: initial; -moz-background-inline-policy: initial;"><a name="License"></a><span style="font-size: 12pt; color: white;">License<o:p></o:p></span></h2>
+    <p class="MsoNormal"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); You may not use this&nbsp;</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">package</span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"> except in compliance with the License. You may obtain a copy of the License at:<br><br></span></p><div style="text-align: center;"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp; <a target="_blank" href="http://www.st.com/software_license_agreement_liberty_v2">http://www.st.com/software_license_agreement_liberty_v2</a></span><br><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"></span></div><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;"><br>Unless
+required by applicable law or agreed to in writing, software
+distributed under the License is distributed on an "AS IS" BASIS, <br>WITHOUT
+WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See
+the License for the specific language governing permissions and
+limitations under the License.</span>
+    <div class="MsoNormal" style="text-align: center;" align="center"><span style="color: black;">
+    <hr align="center" size="2" width="100%">
+    </span></div>
+    <p class="MsoNormal" style="margin: 4.5pt 0in 4.5pt 0.25in; text-align: center;" align="center"><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;; color: black;">For
+    complete documentation on </span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;">STM32<span style="color: black;">
+    Microcontrollers visit </span><u><span style="color: blue;"><a href="http://www.st.com/internet/mcu/family/141.jsp" target="_blank">www.st.com/STM32</a></span></u></span><span style="font-size: 10pt; font-family: &quot;Verdana&quot;,&quot;sans-serif&quot;;"><u><span style="color: blue;"><a href="http://www.st.com/stm32" target="_blank"></a></span></u></span><span style="color: black;"><o:p></o:p></span></p>
+    </td>
+   </tr>
+  </tbody></table>
+  <p class="MsoNormal"><span style="font-size: 10pt;"><o:p></o:p></span></p>
+  </td>
+ </tr>
+</tbody></table>
+
+</div>
+
+<p class="MsoNormal"><o:p>&nbsp;</o:p></p>
+
+</div>
+
+</body></html>
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_bsp.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_bsp.h
new file mode 100644
index 0000000000000000000000000000000000000000..29763a906eaa1799cb40702650a7d6a23c79d805
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_bsp.h
@@ -0,0 +1,103 @@
+/**
+  ******************************************************************************
+  * @file    usb_bsp.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Specific api's relative to the used hardware platform
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_BSP__H__
+#define __USB_BSP__H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_core.h"
+#include "usb_conf.h"
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_BSP
+  * @brief This file is the 
+  * @{
+  */ 
+
+
+/** @defgroup USB_BSP_Exported_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_BSP_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_BSP_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_BSP_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_BSP_Exported_FunctionsPrototype
+  * @{
+  */ 
+void BSP_Init(void);
+
+void USB_OTG_BSP_Init (USB_OTG_CORE_HANDLE *pdev);
+void USB_OTG_BSP_uDelay (const uint32_t usec);
+void USB_OTG_BSP_mDelay (const uint32_t msec);
+void USB_OTG_BSP_EnableInterrupt (USB_OTG_CORE_HANDLE *pdev);
+#ifdef USE_HOST_MODE
+void USB_OTG_BSP_ConfigVBUS(USB_OTG_CORE_HANDLE *pdev);
+void USB_OTG_BSP_DriveVBUS(USB_OTG_CORE_HANDLE *pdev,uint8_t state);
+#endif
+/**
+  * @}
+  */ 
+
+#endif //__USB_BSP__H__
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_conf_template.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_conf_template.h
new file mode 100644
index 0000000000000000000000000000000000000000..2e415e126512c0bbf6592a2b0de9d47509d2d76e
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_conf_template.h
@@ -0,0 +1,306 @@
+/**
+  ******************************************************************************
+  * @file    usb_conf.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   General low level driver configuration
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_CONF__H__
+#define __USB_CONF__H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_conf.h"
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_CONF
+  * @brief USB low level driver configuration file
+  * @{
+  */ 
+
+/** @defgroup USB_CONF_Exported_Defines
+  * @{
+  */ 
+
+/* USB Core and PHY interface configuration.
+   Tip: To avoid modifying these defines each time you need to change the USB
+        configuration, you can declare the needed define in your toolchain
+        compiler preprocessor.
+   */
+/****************** USB OTG FS PHY CONFIGURATION *******************************
+*  The USB OTG FS Core supports one on-chip Full Speed PHY.
+*  
+*  The USE_EMBEDDED_PHY symbol is defined in the project compiler preprocessor 
+*  when FS core is used.
+*******************************************************************************/
+#ifndef USE_USB_OTG_FS
+ //#define USE_USB_OTG_FS
+#endif /* USE_USB_OTG_FS */
+
+#ifdef USE_USB_OTG_FS 
+ #define USB_OTG_FS_CORE
+#endif
+
+/****************** USB OTG HS PHY CONFIGURATION *******************************
+*  The USB OTG HS Core supports two PHY interfaces:
+*   (i)  An ULPI interface for the external High Speed PHY: the USB HS Core will 
+*        operate in High speed mode
+*   (ii) An on-chip Full Speed PHY: the USB HS Core will operate in Full speed mode
+*
+*  You can select the PHY to be used using one of these two defines:
+*   (i)  USE_ULPI_PHY: if the USB OTG HS Core is to be used in High speed mode 
+*   (ii) USE_EMBEDDED_PHY: if the USB OTG HS Core is to be used in Full speed mode
+*
+*  Notes: 
+*   - The USE_ULPI_PHY symbol is defined in the project compiler preprocessor as 
+*     default PHY when HS core is used.
+*   - On STM322xG-EVAL and STM324xG-EVAL boards, only configuration(i) is available.
+*     Configuration (ii) need a different hardware, for more details refer to your
+*     STM32 device datasheet.
+*******************************************************************************/
+#ifndef USE_USB_OTG_HS
+ //#define USE_USB_OTG_HS
+#endif /* USE_USB_OTG_HS */
+
+#ifndef USE_ULPI_PHY
+ //#define USE_ULPI_PHY
+#endif /* USE_ULPI_PHY */
+
+#ifndef USE_EMBEDDED_PHY
+ //#define USE_EMBEDDED_PHY
+#endif /* USE_EMBEDDED_PHY */
+
+#ifdef USE_USB_OTG_HS 
+ #define USB_OTG_HS_CORE
+#endif
+
+/*******************************************************************************
+*                      FIFO Size Configuration in Device mode
+*  
+*  (i) Receive data FIFO size = RAM for setup packets + 
+*                   OUT endpoint control information +
+*                   data OUT packets + miscellaneous
+*      Space = ONE 32-bits words
+*     --> RAM for setup packets = 10 spaces
+*        (n is the nbr of CTRL EPs the device core supports) 
+*     --> OUT EP CTRL info      = 1 space
+*        (one space for status information written to the FIFO along with each 
+*        received packet)
+*     --> data OUT packets      = (Largest Packet Size / 4) + 1 spaces 
+*        (MINIMUM to receive packets)
+*     --> OR data OUT packets  = at least 2*(Largest Packet Size / 4) + 1 spaces 
+*        (if high-bandwidth EP is enabled or multiple isochronous EPs)
+*     --> miscellaneous = 1 space per OUT EP
+*        (one space for transfer complete status information also pushed to the 
+*        FIFO with each endpoint's last packet)
+*
+*  (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for 
+*       that particular IN EP. More space allocated in the IN EP Tx FIFO results
+*       in a better performance on the USB and can hide latencies on the AHB.
+*
+*  (iii) TXn min size = 16 words. (n  : Transmit FIFO index)
+*   (iv) When a TxFIFO is not used, the Configuration should be as follows: 
+*       case 1 :  n > m    and Txn is not used    (n,m  : Transmit FIFO indexes)
+*       --> Txm can use the space allocated for Txn.
+*       case2  :  n < m    and Txn is not used    (n,m  : Transmit FIFO indexes)
+*       --> Txn should be configured with the minimum space of 16 words
+*  (v) The FIFO is used optimally when used TxFIFOs are allocated in the top 
+*       of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
+*******************************************************************************/
+
+/*******************************************************************************
+*                     FIFO Size Configuration in Host mode
+*  
+*  (i) Receive data FIFO size = (Largest Packet Size / 4) + 1 or 
+*                             2x (Largest Packet Size / 4) + 1,  If a 
+*                             high-bandwidth channel or multiple isochronous 
+*                             channels are enabled
+*
+*  (ii) For the host nonperiodic Transmit FIFO is the largest maximum packet size 
+*      for all supported nonperiodic OUT channels. Typically, a space 
+*      corresponding to two Largest Packet Size is recommended.
+*
+*  (iii) The minimum amount of RAM required for Host periodic Transmit FIFO is 
+*        the largest maximum packet size for all supported periodic OUT channels.
+*        If there is at least one High Bandwidth Isochronous OUT endpoint, 
+*        then the space must be at least two times the maximum packet size for 
+*        that channel.
+*******************************************************************************/
+ 
+/****************** USB OTG HS CONFIGURATION **********************************/
+#ifdef USB_OTG_HS_CORE
+ #define RX_FIFO_HS_SIZE                          512
+ #define TX0_FIFO_HS_SIZE                         512
+ #define TX1_FIFO_HS_SIZE                         512
+ #define TX2_FIFO_HS_SIZE                          0
+ #define TX3_FIFO_HS_SIZE                          0
+ #define TX4_FIFO_HS_SIZE                          0
+ #define TX5_FIFO_HS_SIZE                          0
+ #define TXH_NP_HS_FIFOSIZ                         96
+ #define TXH_P_HS_FIFOSIZ                          96
+
+// #define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT
+// #define USB_OTG_HS_SOF_OUTPUT_ENABLED
+
+// #define USB_OTG_INTERNAL_VBUS_ENABLED
+ #define USB_OTG_EXTERNAL_VBUS_ENABLED
+
+ #ifdef USE_ULPI_PHY
+  #define USB_OTG_ULPI_PHY_ENABLED
+ #endif
+ #ifdef USE_EMBEDDED_PHY
+   #define USB_OTG_EMBEDDED_PHY_ENABLED
+ #endif
+ #define USB_OTG_HS_INTERNAL_DMA_ENABLED
+ #define USB_OTG_HS_DEDICATED_EP1_ENABLED
+#endif
+
+/****************** USB OTG FS CONFIGURATION **********************************/
+#ifdef USB_OTG_FS_CORE
+ #define RX_FIFO_FS_SIZE                          128
+ #define TX0_FIFO_FS_SIZE                          64
+ #define TX1_FIFO_FS_SIZE                         128
+ #define TX2_FIFO_FS_SIZE                          0
+ #define TX3_FIFO_FS_SIZE                          0
+ #define TXH_NP_HS_FIFOSIZ                         96
+ #define TXH_P_HS_FIFOSIZ                          96
+
+// #define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT
+// #define USB_OTG_FS_SOF_OUTPUT_ENABLED
+#endif
+
+/****************** USB OTG MISC CONFIGURATION ********************************/
+//#define VBUS_SENSING_ENABLED
+
+/****************** USB OTG MODE CONFIGURATION ********************************/
+//#define USE_HOST_MODE
+#define USE_DEVICE_MODE
+//#define USE_OTG_MODE
+
+#ifndef USB_OTG_FS_CORE
+ #ifndef USB_OTG_HS_CORE
+    #error  "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined"
+ #endif
+#endif
+
+#ifndef USE_DEVICE_MODE
+ #ifndef USE_HOST_MODE
+    #error  "USE_DEVICE_MODE or USE_HOST_MODE should be defined"
+ #endif
+#endif
+
+#ifndef USE_USB_OTG_HS
+ #ifndef USE_USB_OTG_FS
+    #error  "USE_USB_OTG_HS or USE_USB_OTG_FS should be defined"
+ #endif
+#else //USE_USB_OTG_HS
+ #ifndef USE_ULPI_PHY
+  #ifndef USE_EMBEDDED_PHY
+     #error  "USE_ULPI_PHY or USE_EMBEDDED_PHY should be defined"
+  #endif
+ #endif
+#endif
+
+/****************** C Compilers dependant keywords ****************************/
+/* In HS mode and when the DMA is used, all variables and data structures dealing
+   with the DMA during the transaction process should be 4-bytes aligned */    
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
+  #if defined   (__GNUC__)        /* GNU Compiler */
+    #define __ALIGN_END    __attribute__ ((aligned (4)))
+    #define __ALIGN_BEGIN         
+  #else                           
+    #define __ALIGN_END
+    #if defined   (__CC_ARM)      /* ARM Compiler */
+      #define __ALIGN_BEGIN    __align(4)  
+    #elif defined (__ICCARM__)    /* IAR Compiler */
+      #define __ALIGN_BEGIN 
+    #elif defined  (__TASKING__)  /* TASKING Compiler */
+      #define __ALIGN_BEGIN    __align(4) 
+    #endif /* __CC_ARM */  
+  #endif /* __GNUC__ */ 
+#else
+  #define __ALIGN_BEGIN
+  #define __ALIGN_END   
+#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
+
+/* __packed keyword used to decrease the data type alignment to 1-byte */
+#if defined (__CC_ARM)         /* ARM Compiler */
+  #define __packed    __packed
+#elif defined (__ICCARM__)     /* IAR Compiler */
+  #define __packed    __packed
+#elif defined   ( __GNUC__ )   /* GNU Compiler */                        
+  #define __packed    __attribute__ ((__packed__))
+#elif defined   (__TASKING__)  /* TASKING Compiler */
+  #define __packed    __unaligned
+#endif /* __CC_ARM */
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CONF_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CONF_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CONF_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+#endif //__USB_CONF__H__
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_core.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_core.h
new file mode 100644
index 0000000000000000000000000000000000000000..c574665c5c158b59bd6a15ebfa53c2c02d3a02d4
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_core.h
@@ -0,0 +1,417 @@
+/**
+  ******************************************************************************
+  * @file    usb_core.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Header of the Core Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_CORE_H__
+#define __USB_CORE_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_conf.h"
+#include "usb_regs.h"
+#include "usb_defines.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_CORE
+  * @brief usb otg driver core layer
+  * @{
+  */ 
+
+
+/** @defgroup USB_CORE_Exported_Defines
+  * @{
+  */ 
+
+#define USB_OTG_EP0_IDLE                          0
+#define USB_OTG_EP0_SETUP                         1
+#define USB_OTG_EP0_DATA_IN                       2
+#define USB_OTG_EP0_DATA_OUT                      3
+#define USB_OTG_EP0_STATUS_IN                     4
+#define USB_OTG_EP0_STATUS_OUT                    5
+#define USB_OTG_EP0_STALL                         6
+
+#define USB_OTG_EP_TX_DIS       0x0000
+#define USB_OTG_EP_TX_STALL     0x0010
+#define USB_OTG_EP_TX_NAK       0x0020
+#define USB_OTG_EP_TX_VALID     0x0030
+ 
+#define USB_OTG_EP_RX_DIS       0x0000
+#define USB_OTG_EP_RX_STALL     0x1000
+#define USB_OTG_EP_RX_NAK       0x2000
+#define USB_OTG_EP_RX_VALID     0x3000
+/**
+  * @}
+  */ 
+#define   MAX_DATA_LENGTH                        0x200
+
+/** @defgroup USB_CORE_Exported_Types
+  * @{
+  */ 
+
+
+typedef enum {
+  USB_OTG_OK = 0,
+  USB_OTG_FAIL
+}USB_OTG_STS;
+
+typedef enum {
+  HC_IDLE = 0,
+  HC_XFRC,
+  HC_HALTED,
+  HC_NAK,
+  HC_NYET,
+  HC_STALL,
+  HC_XACTERR,  
+  HC_BBLERR,   
+  HC_DATATGLERR,  
+}HC_STATUS;
+
+typedef enum {
+  URB_IDLE = 0,
+  URB_DONE,
+  URB_NOTREADY,
+  URB_ERROR,
+  URB_STALL
+}URB_STATE;
+
+typedef enum {
+  CTRL_START = 0,
+  CTRL_XFRC,
+  CTRL_HALTED,
+  CTRL_NAK,
+  CTRL_STALL,
+  CTRL_XACTERR,  
+  CTRL_BBLERR,   
+  CTRL_DATATGLERR,  
+  CTRL_FAIL
+}CTRL_STATUS;
+
+
+typedef struct USB_OTG_hc
+{
+  uint8_t       dev_addr ;
+  uint8_t       ep_num;
+  uint8_t       ep_is_in;
+  uint8_t       speed;
+  uint8_t       do_ping;  
+  uint8_t       ep_type;
+  uint16_t      max_packet;
+  uint8_t       data_pid;
+  uint8_t       *xfer_buff;
+  uint32_t      xfer_len;
+  uint32_t      xfer_count;  
+  uint8_t       toggle_in;
+  uint8_t       toggle_out;
+  uint32_t       dma_addr;  
+}
+USB_OTG_HC , *PUSB_OTG_HC;
+
+typedef struct USB_OTG_ep
+{
+  uint8_t        num;
+  uint8_t        is_in;
+  uint8_t        is_stall;  
+  uint8_t        type;
+  uint8_t        data_pid_start;
+  uint8_t        even_odd_frame;
+  uint16_t       tx_fifo_num;
+  uint32_t       maxpacket;
+  /* transaction level variables*/
+  uint8_t        *xfer_buff;
+  uint32_t       dma_addr;  
+  uint32_t       xfer_len;
+  uint32_t       xfer_count;
+  /* Transfer level variables*/  
+  uint32_t       rem_data_len;
+  uint32_t       total_data_len;
+  uint32_t       ctl_data_len;  
+
+}
+
+USB_OTG_EP , *PUSB_OTG_EP;
+
+
+
+typedef struct USB_OTG_core_cfg
+{
+  uint8_t       host_channels;
+  uint8_t       dev_endpoints;
+  uint8_t       speed;
+  uint8_t       dma_enable;
+  uint16_t      mps;
+  uint16_t      TotalFifoSize;
+  uint8_t       phy_itface;
+  uint8_t       Sof_output;
+  uint8_t       low_power;
+  uint8_t       coreID;
+ 
+}
+USB_OTG_CORE_CFGS, *PUSB_OTG_CORE_CFGS;
+
+
+
+typedef  struct  usb_setup_req {
+    
+    uint8_t   bmRequest;                      
+    uint8_t   bRequest;                           
+    uint16_t  wValue;                             
+    uint16_t  wIndex;                             
+    uint16_t  wLength;                            
+} USB_SETUP_REQ;
+
+typedef struct _Device_TypeDef
+{
+  uint8_t  *(*GetDeviceDescriptor)( uint8_t speed , uint16_t *length);  
+  uint8_t  *(*GetLangIDStrDescriptor)( uint8_t speed , uint16_t *length); 
+  uint8_t  *(*GetManufacturerStrDescriptor)( uint8_t speed , uint16_t *length);  
+  uint8_t  *(*GetProductStrDescriptor)( uint8_t speed , uint16_t *length);  
+  uint8_t  *(*GetSerialStrDescriptor)( uint8_t speed , uint16_t *length);  
+  uint8_t  *(*GetConfigurationStrDescriptor)( uint8_t speed , uint16_t *length);  
+  uint8_t  *(*GetInterfaceStrDescriptor)( uint8_t speed , uint16_t *length);   
+} USBD_DEVICE, *pUSBD_DEVICE;
+
+//typedef struct USB_OTG_hPort
+//{
+//  void (*Disconnect) (void *phost);
+//  void (*Connect) (void *phost); 
+//  uint8_t ConnStatus;
+//  uint8_t DisconnStatus;
+//  uint8_t ConnHandled;
+//  uint8_t DisconnHandled;
+//} USB_OTG_hPort_TypeDef;
+
+typedef struct _Device_cb
+{
+  uint8_t  (*Init)         (void *pdev , uint8_t cfgidx);
+  uint8_t  (*DeInit)       (void *pdev , uint8_t cfgidx);
+ /* Control Endpoints*/
+  uint8_t  (*Setup)        (void *pdev , USB_SETUP_REQ  *req);  
+  uint8_t  (*EP0_TxSent)   (void *pdev );    
+  uint8_t  (*EP0_RxReady)  (void *pdev );  
+  /* Class Specific Endpoints*/
+  uint8_t  (*DataIn)       (void *pdev , uint8_t epnum);   
+  uint8_t  (*DataOut)      (void *pdev , uint8_t epnum); 
+  uint8_t  (*SOF)          (void *pdev); 
+  uint8_t  (*IsoINIncomplete)  (void *pdev); 
+  uint8_t  (*IsoOUTIncomplete)  (void *pdev);   
+
+  uint8_t  *(*GetConfigDescriptor)( uint8_t speed , uint16_t *length); 
+#ifdef USB_OTG_HS_CORE 
+  uint8_t  *(*GetOtherConfigDescriptor)( uint8_t speed , uint16_t *length);   
+#endif
+
+#ifdef USB_SUPPORT_USER_STRING_DESC 
+  uint8_t  *(*GetUsrStrDescriptor)( uint8_t speed ,uint8_t index,  uint16_t *length);   
+#endif  
+  
+} USBD_Class_cb_TypeDef;
+
+
+
+typedef struct _USBD_USR_PROP
+{
+  void (*Init)(void);   
+  void (*DeviceReset)(uint8_t speed); 
+  void (*DeviceConfigured)(void);
+  void (*DeviceSuspended)(void);
+  void (*DeviceResumed)(void);  
+  
+  void (*DeviceConnected)(void);  
+  void (*DeviceDisconnected)(void);    
+  
+}
+USBD_Usr_cb_TypeDef;
+
+typedef struct _DCD
+{
+  uint8_t        device_config;
+  uint8_t        device_state;
+  uint8_t        device_status;
+  uint8_t        device_old_status;
+  uint8_t        device_address;
+  uint8_t        connection_status;  
+  uint8_t        test_mode;
+  uint32_t       DevRemoteWakeup;
+  USB_OTG_EP     in_ep   [USB_OTG_MAX_TX_FIFOS];
+  USB_OTG_EP     out_ep  [USB_OTG_MAX_TX_FIFOS];
+  uint8_t        setup_packet [8*3];
+  USBD_Class_cb_TypeDef         *class_cb;
+  USBD_Usr_cb_TypeDef           *usr_cb;
+  USBD_DEVICE                   *usr_device;  
+  uint8_t        *pConfig_descriptor;
+ }
+DCD_DEV , *DCD_PDEV;
+
+
+typedef struct _HCD
+{
+  uint8_t                  Rx_Buffer [MAX_DATA_LENGTH];  
+  __IO uint32_t            ConnSts;
+  __IO uint32_t            ErrCnt[USB_OTG_MAX_TX_FIFOS];
+  __IO uint32_t            XferCnt[USB_OTG_MAX_TX_FIFOS];
+  __IO HC_STATUS           HC_Status[USB_OTG_MAX_TX_FIFOS];  
+  __IO URB_STATE           URB_State[USB_OTG_MAX_TX_FIFOS];
+  USB_OTG_HC               hc [USB_OTG_MAX_TX_FIFOS];
+  uint16_t                 channel [USB_OTG_MAX_TX_FIFOS];
+//  USB_OTG_hPort_TypeDef    *port_cb;  
+}
+HCD_DEV , *USB_OTG_USBH_PDEV;
+
+
+typedef struct _OTG
+{
+  uint8_t    OTG_State;
+  uint8_t    OTG_PrevState;  
+  uint8_t    OTG_Mode;    
+}
+OTG_DEV , *USB_OTG_USBO_PDEV;
+
+typedef struct USB_OTG_handle
+{
+  USB_OTG_CORE_CFGS    cfg;
+  USB_OTG_CORE_REGS    regs;
+#ifdef USE_DEVICE_MODE
+  DCD_DEV     dev;
+#endif
+#ifdef USE_HOST_MODE
+  HCD_DEV     host;
+#endif
+#ifdef USE_OTG_MODE
+  OTG_DEV     otg;
+#endif
+}
+USB_OTG_CORE_HANDLE , *PUSB_OTG_CORE_HANDLE;
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_CORE_Exported_Macros
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CORE_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_CORE_Exported_FunctionsPrototype
+  * @{
+  */ 
+
+
+USB_OTG_STS  USB_OTG_CoreInit        (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_SelectCore      (USB_OTG_CORE_HANDLE *pdev, 
+                                      USB_OTG_CORE_ID_TypeDef coreID);
+USB_OTG_STS  USB_OTG_EnableGlobalInt (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_DisableGlobalInt(USB_OTG_CORE_HANDLE *pdev);
+void*           USB_OTG_ReadPacket   (USB_OTG_CORE_HANDLE *pdev ,
+    uint8_t *dest,
+    uint16_t len);
+USB_OTG_STS  USB_OTG_WritePacket     (USB_OTG_CORE_HANDLE *pdev ,
+    uint8_t *src,
+    uint8_t ch_ep_num,
+    uint16_t len);
+USB_OTG_STS  USB_OTG_FlushTxFifo     (USB_OTG_CORE_HANDLE *pdev , uint32_t num);
+USB_OTG_STS  USB_OTG_FlushRxFifo     (USB_OTG_CORE_HANDLE *pdev);
+
+uint32_t     USB_OTG_ReadCoreItr     (USB_OTG_CORE_HANDLE *pdev);
+uint32_t     USB_OTG_ReadOtgItr      (USB_OTG_CORE_HANDLE *pdev);
+uint8_t      USB_OTG_IsHostMode      (USB_OTG_CORE_HANDLE *pdev);
+uint8_t      USB_OTG_IsDeviceMode    (USB_OTG_CORE_HANDLE *pdev);
+uint32_t     USB_OTG_GetMode         (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_PhyInit         (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_SetCurrentMode  (USB_OTG_CORE_HANDLE *pdev,
+    uint8_t mode);
+
+/*********************** HOST APIs ********************************************/
+#ifdef USE_HOST_MODE
+USB_OTG_STS  USB_OTG_CoreInitHost    (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_EnableHostInt   (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_HC_Init         (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
+USB_OTG_STS  USB_OTG_HC_Halt         (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
+USB_OTG_STS  USB_OTG_HC_StartXfer    (USB_OTG_CORE_HANDLE *pdev, uint8_t hc_num);
+USB_OTG_STS  USB_OTG_HC_DoPing       (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num);
+uint32_t     USB_OTG_ReadHostAllChannels_intr    (USB_OTG_CORE_HANDLE *pdev);
+uint32_t     USB_OTG_ResetPort       (USB_OTG_CORE_HANDLE *pdev);
+uint32_t     USB_OTG_ReadHPRT0       (USB_OTG_CORE_HANDLE *pdev);
+void         USB_OTG_DriveVbus       (USB_OTG_CORE_HANDLE *pdev, uint8_t state);
+void         USB_OTG_InitFSLSPClkSel (USB_OTG_CORE_HANDLE *pdev ,uint8_t freq);
+uint8_t      USB_OTG_IsEvenFrame     (USB_OTG_CORE_HANDLE *pdev) ;
+void         USB_OTG_StopHost        (USB_OTG_CORE_HANDLE *pdev);
+#endif
+/********************* DEVICE APIs ********************************************/
+#ifdef USE_DEVICE_MODE
+USB_OTG_STS  USB_OTG_CoreInitDev         (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_EnableDevInt        (USB_OTG_CORE_HANDLE *pdev);
+uint32_t     USB_OTG_ReadDevAllInEPItr           (USB_OTG_CORE_HANDLE *pdev);
+enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_EP0Activate (USB_OTG_CORE_HANDLE *pdev);
+USB_OTG_STS  USB_OTG_EPActivate  (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
+USB_OTG_STS  USB_OTG_EPDeactivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
+USB_OTG_STS  USB_OTG_EPStartXfer (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
+USB_OTG_STS  USB_OTG_EP0StartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
+USB_OTG_STS  USB_OTG_EPSetStall          (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
+USB_OTG_STS  USB_OTG_EPClearStall        (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep);
+uint32_t     USB_OTG_ReadDevAllOutEp_itr (USB_OTG_CORE_HANDLE *pdev);
+uint32_t     USB_OTG_ReadDevOutEP_itr    (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
+uint32_t     USB_OTG_ReadDevAllInEPItr   (USB_OTG_CORE_HANDLE *pdev);
+void         USB_OTG_InitDevSpeed        (USB_OTG_CORE_HANDLE *pdev , uint8_t speed);
+uint8_t      USBH_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev);
+void         USB_OTG_EP0_OutStart(USB_OTG_CORE_HANDLE *pdev);
+void         USB_OTG_ActiveRemoteWakeup(USB_OTG_CORE_HANDLE *pdev);
+void         USB_OTG_UngateClock(USB_OTG_CORE_HANDLE *pdev);
+void         USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev);
+void         USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t Status);
+uint32_t     USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep);
+#endif
+/**
+  * @}
+  */ 
+
+#endif  /* __USB_CORE_H__ */
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_dcd.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_dcd.h
new file mode 100644
index 0000000000000000000000000000000000000000..6922782a7ed41cb16fdc63e8bd88d1bf4974d768
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_dcd.h
@@ -0,0 +1,164 @@
+/**
+  ******************************************************************************
+  * @file    usb_dcd.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Peripheral Driver Header file
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __DCD_H__
+#define __DCD_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_core.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+* @{
+*/
+
+/** @defgroup USB_DCD
+* @brief This file is the 
+* @{
+*/ 
+
+
+/** @defgroup USB_DCD_Exported_Defines
+* @{
+*/ 
+#define USB_OTG_EP_CONTROL                       0
+#define USB_OTG_EP_ISOC                          1
+#define USB_OTG_EP_BULK                          2
+#define USB_OTG_EP_INT                           3
+#define USB_OTG_EP_MASK                          3
+
+/*  Device Status */
+#define USB_OTG_DEFAULT                          1
+#define USB_OTG_ADDRESSED                        2
+#define USB_OTG_CONFIGURED                       3
+#define USB_OTG_SUSPENDED                        4
+
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_Exported_Types
+* @{
+*/ 
+/********************************************************************************
+Data structure type
+********************************************************************************/
+typedef struct
+{
+  uint8_t  bLength;
+  uint8_t  bDescriptorType;
+  uint8_t  bEndpointAddress;
+  uint8_t  bmAttributes;
+  uint16_t wMaxPacketSize;
+  uint8_t  bInterval;
+}
+EP_DESCRIPTOR , *PEP_DESCRIPTOR;
+
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_Exported_Macros
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+/** @defgroup USB_DCD_Exported_Variables
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+/** @defgroup USB_DCD_Exported_FunctionsPrototype
+* @{
+*/ 
+/********************************************************************************
+EXPORTED FUNCTION FROM THE USB-OTG LAYER
+********************************************************************************/
+void       DCD_Init(USB_OTG_CORE_HANDLE *pdev ,
+                    USB_OTG_CORE_ID_TypeDef coreID);
+
+void        DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev);
+void        DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev);
+void        DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev,
+                               uint8_t address);
+uint32_t    DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev , 
+                     uint8_t ep_addr,
+                     uint16_t ep_mps,
+                     uint8_t ep_type);
+
+uint32_t    DCD_EP_Close  (USB_OTG_CORE_HANDLE *pdev,
+                                uint8_t  ep_addr);
+
+
+uint32_t   DCD_EP_PrepareRx ( USB_OTG_CORE_HANDLE *pdev,
+                        uint8_t   ep_addr,                                  
+                        uint8_t *pbuf,                                  
+                        uint16_t  buf_len);
+  
+uint32_t    DCD_EP_Tx (USB_OTG_CORE_HANDLE *pdev,
+                               uint8_t  ep_addr,
+                               uint8_t  *pbuf,
+                               uint32_t   buf_len);
+uint32_t    DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev,
+                              uint8_t   epnum);
+uint32_t    DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev,
+                                  uint8_t epnum);
+uint32_t    DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev,
+                               uint8_t epnum);
+uint32_t    DCD_Handle_ISR(USB_OTG_CORE_HANDLE *pdev);
+
+uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,
+                         uint8_t epnum);
+
+void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , 
+                      uint8_t epnum , 
+                      uint32_t Status);
+
+/**
+* @}
+*/ 
+
+
+#endif //__DCD_H__
+
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_dcd_int.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_dcd_int.h
new file mode 100644
index 0000000000000000000000000000000000000000..e2369e5ddf8ad473365d912de3c7f688e86d530d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_dcd_int.h
@@ -0,0 +1,127 @@
+/**
+  ******************************************************************************
+  * @file    usb_dcd_int.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Peripheral Device Interface Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef USB_DCD_INT_H__
+#define USB_DCD_INT_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_dcd.h"
+
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_DCD_INT
+  * @brief This file is the 
+  * @{
+  */ 
+
+
+/** @defgroup USB_DCD_INT_Exported_Defines
+  * @{
+  */ 
+
+typedef struct _USBD_DCD_INT
+{
+  uint8_t (* DataOutStage) (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
+  uint8_t (* DataInStage)  (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum);
+  uint8_t (* SetupStage) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* SOF) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* Reset) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* Suspend) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* Resume) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* IsoINIncomplete) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* IsoOUTIncomplete) (USB_OTG_CORE_HANDLE *pdev);  
+  
+  uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev);   
+  
+}USBD_DCD_INT_cb_TypeDef;
+
+extern USBD_DCD_INT_cb_TypeDef *USBD_DCD_INT_fops;
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_DCD_INT_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_DCD_INT_Exported_Macros
+  * @{
+  */ 
+
+#define CLEAR_IN_EP_INTR(epnum,intr) \
+  diepint.d32=0; \
+  diepint.b.intr = 1; \
+  USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT,diepint.d32);
+
+#define CLEAR_OUT_EP_INTR(epnum,intr) \
+  doepint.d32=0; \
+  doepint.b.intr = 1; \
+  USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[epnum]->DOEPINT,doepint.d32);
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_DCD_INT_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_DCD_INT_Exported_FunctionsPrototype
+  * @{
+  */ 
+
+uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
+
+/**
+  * @}
+  */ 
+
+
+#endif // USB_DCD_INT_H__
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_defines.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_defines.h
new file mode 100644
index 0000000000000000000000000000000000000000..28e6d1687ca482daa4fab64f5d9c8087bcc55bee
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_defines.h
@@ -0,0 +1,249 @@
+/**
+  ******************************************************************************
+  * @file    usb_defines.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Header of the Core Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_DEF_H__
+#define __USB_DEF_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include  "usb_conf.h"
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_DEFINES
+  * @brief This file is the 
+  * @{
+  */ 
+
+
+/** @defgroup USB_DEFINES_Exported_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup _CORE_DEFINES_
+  * @{
+  */
+
+#define USB_OTG_SPEED_PARAM_HIGH 0
+#define USB_OTG_SPEED_PARAM_HIGH_IN_FULL 1
+#define USB_OTG_SPEED_PARAM_FULL 3
+
+#define USB_OTG_SPEED_HIGH      0
+#define USB_OTG_SPEED_FULL      1
+
+#define USB_OTG_ULPI_PHY      1
+#define USB_OTG_EMBEDDED_PHY  2
+
+/**
+  * @}
+  */
+
+
+/** @defgroup _GLOBAL_DEFINES_
+  * @{
+  */
+#define GAHBCFG_TXFEMPTYLVL_EMPTY              1
+#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY          0
+#define GAHBCFG_GLBINT_ENABLE                  1
+#define GAHBCFG_INT_DMA_BURST_SINGLE           0
+#define GAHBCFG_INT_DMA_BURST_INCR             1
+#define GAHBCFG_INT_DMA_BURST_INCR4            3
+#define GAHBCFG_INT_DMA_BURST_INCR8            5
+#define GAHBCFG_INT_DMA_BURST_INCR16           7
+#define GAHBCFG_DMAENABLE                      1
+#define GAHBCFG_TXFEMPTYLVL_EMPTY              1
+#define GAHBCFG_TXFEMPTYLVL_HALFEMPTY          0
+#define GRXSTS_PKTSTS_IN                       2
+#define GRXSTS_PKTSTS_IN_XFER_COMP             3
+#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR          5
+#define GRXSTS_PKTSTS_CH_HALTED                7
+/**
+  * @}
+  */
+
+
+/** @defgroup _OnTheGo_DEFINES_
+  * @{
+  */
+#define MODE_HNP_SRP_CAPABLE                   0
+#define MODE_SRP_ONLY_CAPABLE                  1
+#define MODE_NO_HNP_SRP_CAPABLE                2
+#define MODE_SRP_CAPABLE_DEVICE                3
+#define MODE_NO_SRP_CAPABLE_DEVICE             4
+#define MODE_SRP_CAPABLE_HOST                  5
+#define MODE_NO_SRP_CAPABLE_HOST               6
+#define A_HOST                                 1
+#define A_SUSPEND                              2
+#define A_PERIPHERAL                           3
+#define B_PERIPHERAL                           4
+#define B_HOST                                 5
+#define DEVICE_MODE                            0
+#define HOST_MODE                              1
+#define OTG_MODE                               2
+/**
+  * @}
+  */
+
+
+/** @defgroup __DEVICE_DEFINES_
+  * @{
+  */
+#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ     0
+#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ     1
+#define DSTS_ENUMSPD_LS_PHY_6MHZ               2
+#define DSTS_ENUMSPD_FS_PHY_48MHZ              3
+
+#define DCFG_FRAME_INTERVAL_80                 0
+#define DCFG_FRAME_INTERVAL_85                 1
+#define DCFG_FRAME_INTERVAL_90                 2
+#define DCFG_FRAME_INTERVAL_95                 3
+
+#define DEP0CTL_MPS_64                         0
+#define DEP0CTL_MPS_32                         1
+#define DEP0CTL_MPS_16                         2
+#define DEP0CTL_MPS_8                          3
+
+#define EP_SPEED_LOW                           0
+#define EP_SPEED_FULL                          1
+#define EP_SPEED_HIGH                          2
+
+#define EP_TYPE_CTRL                           0
+#define EP_TYPE_ISOC                           1
+#define EP_TYPE_BULK                           2
+#define EP_TYPE_INTR                           3
+#define EP_TYPE_MSK                            3
+
+#define STS_GOUT_NAK                           1
+#define STS_DATA_UPDT                          2
+#define STS_XFER_COMP                          3
+#define STS_SETUP_COMP                         4
+#define STS_SETUP_UPDT                         6
+/**
+  * @}
+  */
+
+
+/** @defgroup __HOST_DEFINES_
+  * @{
+  */
+#define HC_PID_DATA0                           0
+#define HC_PID_DATA2                           1
+#define HC_PID_DATA1                           2
+#define HC_PID_SETUP                           3
+
+#define HPRT0_PRTSPD_HIGH_SPEED                0
+#define HPRT0_PRTSPD_FULL_SPEED                1
+#define HPRT0_PRTSPD_LOW_SPEED                 2
+
+#define HCFG_30_60_MHZ                         0
+#define HCFG_48_MHZ                            1
+#define HCFG_6_MHZ                             2
+
+#define HCCHAR_CTRL                            0
+#define HCCHAR_ISOC                            1
+#define HCCHAR_BULK                            2
+#define HCCHAR_INTR                            3
+
+#define  MIN(a, b)      (((a) < (b)) ? (a) : (b))
+
+/**
+  * @}
+  */
+
+
+/** @defgroup USB_DEFINES_Exported_Types
+  * @{
+  */ 
+
+typedef enum
+{
+  USB_OTG_HS_CORE_ID = 0,
+  USB_OTG_FS_CORE_ID = 1
+}USB_OTG_CORE_ID_TypeDef;
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_DEFINES_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_DEFINES_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_DEFINES_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup Internal_Macro's
+  * @{
+  */
+#define USB_OTG_READ_REG32(reg)  (*(__IO uint32_t *)reg)
+#define USB_OTG_WRITE_REG32(reg,value) (*(__IO uint32_t *)reg = value)
+#define USB_OTG_MODIFY_REG32(reg,clear_mask,set_mask) \
+  USB_OTG_WRITE_REG32(reg, (((USB_OTG_READ_REG32(reg)) & ~clear_mask) | set_mask ) )
+
+/********************************************************************************
+                              ENUMERATION TYPE
+********************************************************************************/
+enum USB_OTG_SPEED {
+  USB_SPEED_UNKNOWN = 0,
+  USB_SPEED_LOW,
+  USB_SPEED_FULL,
+  USB_SPEED_HIGH
+};
+
+#endif //__USB_DEFINES__H__
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_hcd.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_hcd.h
new file mode 100644
index 0000000000000000000000000000000000000000..ca2ba3c374cb74f938e5fd57abfd26ba0c91a64c
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_hcd.h
@@ -0,0 +1,108 @@
+/**
+  ******************************************************************************
+  * @file    usb_hcd.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Host layer Header file
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_HCD_H__
+#define __USB_HCD_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_regs.h"
+#include "usb_core.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_HCD
+  * @brief This file is the 
+  * @{
+  */ 
+
+
+/** @defgroup USB_HCD_Exported_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_HCD_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_HCD_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_HCD_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_HCD_Exported_FunctionsPrototype
+  * @{
+  */ 
+uint32_t  HCD_Init                 (USB_OTG_CORE_HANDLE *pdev ,
+                                    USB_OTG_CORE_ID_TypeDef coreID);
+uint32_t  HCD_HC_Init              (USB_OTG_CORE_HANDLE *pdev , 
+                                    uint8_t hc_num); 
+uint32_t  HCD_SubmitRequest        (USB_OTG_CORE_HANDLE *pdev , 
+                                    uint8_t hc_num) ;
+uint32_t  HCD_GetCurrentSpeed      (USB_OTG_CORE_HANDLE *pdev);
+uint32_t  HCD_ResetPort            (USB_OTG_CORE_HANDLE *pdev);
+uint32_t  HCD_IsDeviceConnected    (USB_OTG_CORE_HANDLE *pdev);
+uint32_t  HCD_GetCurrentFrame      (USB_OTG_CORE_HANDLE *pdev) ;
+URB_STATE HCD_GetURB_State         (USB_OTG_CORE_HANDLE *pdev,  uint8_t ch_num); 
+uint32_t  HCD_GetXferCnt           (USB_OTG_CORE_HANDLE *pdev,  uint8_t ch_num); 
+HC_STATUS HCD_GetHCState           (USB_OTG_CORE_HANDLE *pdev,  uint8_t ch_num) ;
+/**
+  * @}
+  */ 
+
+#endif //__USB_HCD_H__
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_hcd_int.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_hcd_int.h
new file mode 100644
index 0000000000000000000000000000000000000000..5bc5b8a882a3fa0455070a04121f9368e168bd2d
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_hcd_int.h
@@ -0,0 +1,141 @@
+/**
+  ******************************************************************************
+  * @file    usb_hcd_int.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Peripheral Device Interface Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __HCD_INT_H__
+#define __HCD_INT_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_hcd.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_HCD_INT
+  * @brief This file is the 
+  * @{
+  */ 
+
+
+/** @defgroup USB_HCD_INT_Exported_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_HCD_INT_Exported_Types
+  * @{
+  */ 
+
+typedef struct _USBH_HCD_INT
+{
+  uint8_t (* SOF) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* DevConnected) (USB_OTG_CORE_HANDLE *pdev);
+  uint8_t (* DevDisconnected) (USB_OTG_CORE_HANDLE *pdev);   
+  
+}USBH_HCD_INT_cb_TypeDef;
+
+extern USBH_HCD_INT_cb_TypeDef *USBH_HCD_INT_fops;
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_HCD_INT_Exported_Macros
+  * @{
+  */ 
+
+#define CLEAR_HC_INT(HC_REGS, intr) \
+  {\
+  USB_OTG_HCINTn_TypeDef  hcint_clear; \
+  hcint_clear.d32 = 0; \
+  hcint_clear.b.intr = 1; \
+  USB_OTG_WRITE_REG32(&((HC_REGS)->HCINT), hcint_clear.d32);\
+  }\
+
+#define MASK_HOST_INT_CHH(hc_num) { USB_OTG_HCINTMSK_TypeDef  INTMSK; \
+    INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
+    INTMSK.b.chhltd = 0; \
+    USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);}
+
+#define UNMASK_HOST_INT_CHH(hc_num) { USB_OTG_HCINTMSK_TypeDef  INTMSK; \
+    INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
+    INTMSK.b.chhltd = 1; \
+    USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);}
+
+#define MASK_HOST_INT_ACK(hc_num) { USB_OTG_HCINTMSK_TypeDef  INTMSK; \
+    INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
+    INTMSK.b.ack = 0; \
+    USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, GINTMSK.d32);}
+
+#define UNMASK_HOST_INT_ACK(hc_num) { USB_OTG_HCGINTMSK_TypeDef  INTMSK; \
+    INTMSK.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK); \
+    INTMSK.b.ack = 1; \
+    USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, INTMSK.d32);}
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_HCD_INT_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_HCD_INT_Exported_FunctionsPrototype
+  * @{
+  */ 
+/* Callbacks handler */
+void ConnectCallback_Handler(USB_OTG_CORE_HANDLE *pdev);
+void Disconnect_Callback_Handler(USB_OTG_CORE_HANDLE *pdev);
+void Overcurrent_Callback_Handler(USB_OTG_CORE_HANDLE *pdev);
+uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev);
+
+/**
+  * @}
+  */ 
+
+
+
+#endif //__HCD_INT_H__
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_otg.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_otg.h
new file mode 100644
index 0000000000000000000000000000000000000000..54d35f9964d6dbbfe74af67d0b4f124131c41198
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_otg.h
@@ -0,0 +1,99 @@
+/**
+  ******************************************************************************
+  * @file    usb_otg.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   OTG Core Header
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_OTG__
+#define __USB_OTG__
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_OTG
+  * @brief This file is the 
+  * @{
+  */ 
+
+
+/** @defgroup USB_OTG_Exported_Defines
+  * @{
+  */ 
+
+
+void USB_OTG_InitiateSRP(void);
+void USB_OTG_InitiateHNP(uint8_t state , uint8_t mode);
+void USB_OTG_Switchback (USB_OTG_CORE_DEVICE *pdev);
+uint32_t  USB_OTG_GetCurrentState (USB_OTG_CORE_DEVICE *pdev);
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_OTG_Exported_Types
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_OTG_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_OTG_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_OTG_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+#endif //__USB_OTG__
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_regs.h b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_regs.h
new file mode 100644
index 0000000000000000000000000000000000000000..fab4e6f788c55053b9042a36863b18510d5ae774
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/inc/usb_regs.h
@@ -0,0 +1,1190 @@
+/**
+  ******************************************************************************
+  * @file    usb_regs.h
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   hardware registers
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __USB_OTG_REGS_H__
+#define __USB_OTG_REGS_H__
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_conf.h"
+#include "stm32f4xx.h"
+#include "core_cm4.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_REGS
+  * @brief This file is the 
+  * @{
+  */ 
+
+
+/** @defgroup USB_REGS_Exported_Defines
+  * @{
+  */ 
+
+#define USB_OTG_HS_BASE_ADDR                 0x40040000
+#define USB_OTG_FS_BASE_ADDR                 0x50000000
+
+#define USB_OTG_CORE_GLOBAL_REGS_OFFSET      0x000
+#define USB_OTG_DEV_GLOBAL_REG_OFFSET        0x800
+#define USB_OTG_DEV_IN_EP_REG_OFFSET         0x900
+#define USB_OTG_EP_REG_OFFSET                0x20
+#define USB_OTG_DEV_OUT_EP_REG_OFFSET        0xB00
+#define USB_OTG_HOST_GLOBAL_REG_OFFSET       0x400
+#define USB_OTG_HOST_PORT_REGS_OFFSET        0x440
+#define USB_OTG_HOST_CHAN_REGS_OFFSET        0x500
+#define USB_OTG_CHAN_REGS_OFFSET             0x20
+#define USB_OTG_PCGCCTL_OFFSET               0xE00
+#define USB_OTG_DATA_FIFO_OFFSET             0x1000
+#define USB_OTG_DATA_FIFO_SIZE               0x1000
+
+
+#define USB_OTG_MAX_TX_FIFOS                 15
+
+#define USB_OTG_HS_MAX_PACKET_SIZE           512
+#define USB_OTG_FS_MAX_PACKET_SIZE           64
+#define USB_OTG_MAX_EP0_SIZE                 64
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_REGS_Exported_Types
+  * @{
+  */ 
+
+/** @defgroup __USB_OTG_Core_register
+  * @{
+  */
+typedef struct _USB_OTG_GREGS  //000h
+{
+  __IO uint32_t GOTGCTL;      /* USB_OTG Control and Status Register    000h*/
+  __IO uint32_t GOTGINT;      /* USB_OTG Interrupt Register             004h*/
+  __IO uint32_t GAHBCFG;      /* Core AHB Configuration Register    008h*/
+  __IO uint32_t GUSBCFG;      /* Core USB Configuration Register    00Ch*/
+  __IO uint32_t GRSTCTL;      /* Core Reset Register                010h*/
+  __IO uint32_t GINTSTS;      /* Core Interrupt Register            014h*/
+  __IO uint32_t GINTMSK;      /* Core Interrupt Mask Register       018h*/
+  __IO uint32_t GRXSTSR;      /* Receive Sts Q Read Register        01Ch*/
+  __IO uint32_t GRXSTSP;      /* Receive Sts Q Read & POP Register  020h*/
+  __IO uint32_t GRXFSIZ;      /* Receive FIFO Size Register         024h*/
+  __IO uint32_t DIEPTXF0_HNPTXFSIZ;   /* EP0 / Non Periodic Tx FIFO Size Register 028h*/
+  __IO uint32_t HNPTXSTS;     /* Non Periodic Tx FIFO/Queue Sts reg 02Ch*/
+  uint32_t Reserved30[2];     /* Reserved                           030h*/
+  __IO uint32_t GCCFG;        /* General Purpose IO Register        038h*/
+  __IO uint32_t CID;          /* User ID Register                   03Ch*/
+  uint32_t  Reserved40[48];   /* Reserved                      040h-0FFh*/
+  __IO uint32_t HPTXFSIZ; /* Host Periodic Tx FIFO Size Reg     100h*/
+  __IO uint32_t DIEPTXF[USB_OTG_MAX_TX_FIFOS];/* dev Periodic Transmit FIFO */
+}
+USB_OTG_GREGS;
+/**
+  * @}
+  */
+
+
+/** @defgroup __device_Registers
+  * @{
+  */
+typedef struct _USB_OTG_DREGS // 800h
+{
+  __IO uint32_t DCFG;         /* dev Configuration Register   800h*/
+  __IO uint32_t DCTL;         /* dev Control Register         804h*/
+  __IO uint32_t DSTS;         /* dev Status Register (RO)     808h*/
+  uint32_t Reserved0C;           /* Reserved                     80Ch*/
+  __IO uint32_t DIEPMSK;   /* dev IN Endpoint Mask         810h*/
+  __IO uint32_t DOEPMSK;  /* dev OUT Endpoint Mask        814h*/
+  __IO uint32_t DAINT;     /* dev All Endpoints Itr Reg    818h*/
+  __IO uint32_t DAINTMSK; /* dev All Endpoints Itr Mask   81Ch*/
+  uint32_t  Reserved20;          /* Reserved                     820h*/
+  uint32_t Reserved9;       /* Reserved                     824h*/
+  __IO uint32_t DVBUSDIS;    /* dev VBUS discharge Register  828h*/
+  __IO uint32_t DVBUSPULSE;  /* dev VBUS Pulse Register      82Ch*/
+  __IO uint32_t DTHRCTL;     /* dev thr                      830h*/
+  __IO uint32_t DIEPEMPMSK; /* dev empty msk             834h*/
+  __IO uint32_t DEACHINT;    /* dedicated EP interrupt       838h*/
+  __IO uint32_t DEACHMSK;    /* dedicated EP msk             83Ch*/  
+  uint32_t Reserved40;      /* dedicated EP mask           840h*/
+  __IO uint32_t DINEP1MSK;  /* dedicated EP mask           844h*/
+  uint32_t  Reserved44[15];      /* Reserved                 844-87Ch*/
+  __IO uint32_t DOUTEP1MSK; /* dedicated EP msk            884h*/   
+}
+USB_OTG_DREGS;
+/**
+  * @}
+  */
+
+
+/** @defgroup __IN_Endpoint-Specific_Register
+  * @{
+  */
+typedef struct _USB_OTG_INEPREGS
+{
+  __IO uint32_t DIEPCTL; /* dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h*/
+  uint32_t Reserved04;             /* Reserved                       900h + (ep_num * 20h) + 04h*/
+  __IO uint32_t DIEPINT; /* dev IN Endpoint Itr Reg     900h + (ep_num * 20h) + 08h*/
+  uint32_t Reserved0C;             /* Reserved                       900h + (ep_num * 20h) + 0Ch*/
+  __IO uint32_t DIEPTSIZ; /* IN Endpoint Txfer Size   900h + (ep_num * 20h) + 10h*/
+  __IO uint32_t DIEPDMA; /* IN Endpoint DMA Address Reg    900h + (ep_num * 20h) + 14h*/
+  __IO uint32_t DTXFSTS;/*IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h*/
+  uint32_t Reserved18;             /* Reserved  900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch*/
+}
+USB_OTG_INEPREGS;
+/**
+  * @}
+  */
+
+
+/** @defgroup __OUT_Endpoint-Specific_Registers
+  * @{
+  */
+typedef struct _USB_OTG_OUTEPREGS
+{
+  __IO uint32_t DOEPCTL;       /* dev OUT Endpoint Control Reg  B00h + (ep_num * 20h) + 00h*/
+  uint32_t Reserved04;         /* Reserved                      B00h + (ep_num * 20h) + 04h*/
+  __IO uint32_t DOEPINT;       /* dev OUT Endpoint Itr Reg      B00h + (ep_num * 20h) + 08h*/
+  uint32_t Reserved0C;         /* Reserved                      B00h + (ep_num * 20h) + 0Ch*/
+  __IO uint32_t DOEPTSIZ;      /* dev OUT Endpoint Txfer Size   B00h + (ep_num * 20h) + 10h*/
+  __IO uint32_t DOEPDMA;       /* dev OUT Endpoint DMA Address  B00h + (ep_num * 20h) + 14h*/
+  uint32_t Reserved18[2];      /* Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch*/
+}
+USB_OTG_OUTEPREGS;
+/**
+  * @}
+  */
+
+
+/** @defgroup __Host_Mode_Register_Structures
+  * @{
+  */
+typedef struct _USB_OTG_HREGS
+{
+  __IO uint32_t HCFG;             /* Host Configuration Register    400h*/
+  __IO uint32_t HFIR;      /* Host Frame Interval Register   404h*/
+  __IO uint32_t HFNUM;         /* Host Frame Nbr/Frame Remaining 408h*/
+  uint32_t Reserved40C;                   /* Reserved                       40Ch*/
+  __IO uint32_t HPTXSTS;   /* Host Periodic Tx FIFO/ Queue Status 410h*/
+  __IO uint32_t HAINT;   /* Host All Channels Interrupt Register 414h*/
+  __IO uint32_t HAINTMSK;   /* Host All Channels Interrupt Mask 418h*/
+}
+USB_OTG_HREGS;
+/**
+  * @}
+  */
+
+
+/** @defgroup __Host_Channel_Specific_Registers
+  * @{
+  */
+typedef struct _USB_OTG_HC_REGS
+{
+  __IO uint32_t HCCHAR;
+  __IO uint32_t HCSPLT;
+  __IO uint32_t HCINT;
+  __IO uint32_t HCINTMSK;
+  __IO uint32_t HCTSIZ;
+  __IO uint32_t HCDMA;
+  uint32_t Reserved[2];
+}
+USB_OTG_HC_REGS;
+/**
+  * @}
+  */
+
+
+/** @defgroup __otg_Core_registers
+  * @{
+  */
+typedef struct USB_OTG_core_regs //000h
+{
+  USB_OTG_GREGS         *GREGS;
+  USB_OTG_DREGS         *DREGS;
+  USB_OTG_HREGS         *HREGS;
+  USB_OTG_INEPREGS      *INEP_REGS[USB_OTG_MAX_TX_FIFOS];
+  USB_OTG_OUTEPREGS     *OUTEP_REGS[USB_OTG_MAX_TX_FIFOS];
+  USB_OTG_HC_REGS       *HC_REGS[USB_OTG_MAX_TX_FIFOS];
+  __IO uint32_t         *HPRT0;
+  __IO uint32_t         *DFIFO[USB_OTG_MAX_TX_FIFOS];
+  __IO uint32_t         *PCGCCTL;
+}
+USB_OTG_CORE_REGS , *PUSB_OTG_CORE_REGS;
+typedef union _USB_OTG_GOTGCTL_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t sesreqscs :
+    1;
+uint32_t sesreq :
+    1;
+uint32_t Reserved2_7 :
+    6;
+uint32_t hstnegscs :
+    1;
+uint32_t hnpreq :
+    1;
+uint32_t hstsethnpen :
+    1;
+uint32_t devhnpen :
+    1;
+uint32_t Reserved12_15 :
+    4;
+uint32_t conidsts :
+    1;
+uint32_t dbct :
+    1;
+uint32_t asesvld :
+    1;
+uint32_t bsesvld :
+    1;
+uint32_t Reserved20_31 :
+    12;
+  }
+  b;
+} USB_OTG_GOTGCTL_TypeDef ;
+
+typedef union _USB_OTG_GOTGINT_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t Reserved0_1 :
+    2;
+uint32_t sesenddet :
+    1;
+uint32_t Reserved3_7 :
+    5;
+uint32_t sesreqsucstschng :
+    1;
+uint32_t hstnegsucstschng :
+    1;
+uint32_t reserver10_16 :
+    7;
+uint32_t hstnegdet :
+    1;
+uint32_t adevtoutchng :
+    1;
+uint32_t debdone :
+    1;
+uint32_t Reserved31_20 :
+    12;
+  }
+  b;
+} USB_OTG_GOTGINT_TypeDef ;
+typedef union _USB_OTG_GAHBCFG_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t glblintrmsk :
+    1;
+uint32_t hburstlen :
+    4;
+uint32_t dmaenable :
+    1;
+uint32_t Reserved :
+    1;
+uint32_t nptxfemplvl_txfemplvl :
+    1;
+uint32_t ptxfemplvl :
+    1;
+uint32_t Reserved9_31 :
+    23;
+  }
+  b;
+} USB_OTG_GAHBCFG_TypeDef ;
+typedef union _USB_OTG_GUSBCFG_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t toutcal :
+    3;
+uint32_t Reserved3_5 :
+    3;
+uint32_t physel :
+    1;
+uint32_t Reserved7 :
+    1;
+uint32_t srpcap :
+    1;
+uint32_t hnpcap :
+    1;
+uint32_t usbtrdtim :
+    4;
+uint32_t Reserved14 :
+    1;
+uint32_t phylpwrclksel :
+    1;
+uint32_t Reserved16 :
+    1;
+uint32_t ulpi_fsls :
+    1;
+uint32_t ulpi_auto_res :
+    1;
+uint32_t ulpi_clk_sus_m :
+    1;
+uint32_t ulpi_ext_vbus_drv :
+    1;
+uint32_t ulpi_int_vbus_ind :
+    1;
+uint32_t term_sel_dl_pulse :
+    1;
+uint32_t ulpi_ind_cpl :
+    1;
+uint32_t ulpi_passthrough :
+    1;       
+uint32_t ulpi_protect_disable :
+    1; 
+uint32_t Reserved26_28 :
+    3;     
+uint32_t force_host :
+    1;
+uint32_t force_dev :
+    1;
+uint32_t corrupt_tx :
+    1;
+  }
+  b;
+} USB_OTG_GUSBCFG_TypeDef ;
+typedef union _USB_OTG_GRSTCTL_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t csftrst :
+    1;
+uint32_t hsftrst :
+    1;
+uint32_t hstfrm :
+    1;
+uint32_t Reserved3 :
+    1;
+uint32_t rxfflsh :
+    1;
+uint32_t txfflsh :
+    1;
+uint32_t txfnum :
+    5;
+uint32_t Reserved11_29 :
+    19;
+uint32_t dmareq :
+    1;
+uint32_t ahbidle :
+    1;
+  }
+  b;
+} USB_OTG_GRSTCTL_TypeDef ;
+typedef union _USB_OTG_GINTMSK_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t Reserved0 :
+    1;
+uint32_t modemismatch :
+    1;
+uint32_t otgintr :
+    1;
+uint32_t sofintr :
+    1;
+uint32_t rxstsqlvl :
+    1;
+uint32_t nptxfempty :
+    1;
+uint32_t ginnakeff :
+    1;
+uint32_t goutnakeff :
+    1;
+uint32_t Reserved8_9 :
+    2;
+uint32_t erlysuspend :
+    1;
+uint32_t usbsuspend :
+    1;
+uint32_t usbreset :
+    1;
+uint32_t enumdone :
+    1;
+uint32_t isooutdrop :
+    1;
+uint32_t eopframe :
+    1;
+uint32_t Reserved16 :
+    1;
+uint32_t epmismatch :
+    1;
+uint32_t inepintr :
+    1;
+uint32_t outepintr :
+    1;
+uint32_t incomplisoin :
+    1;
+uint32_t incomplisoout :
+    1;
+uint32_t Reserved22_23 :
+    2;
+uint32_t portintr :
+    1;
+uint32_t hcintr :
+    1;
+uint32_t ptxfempty :
+    1;
+uint32_t Reserved27 :
+    1;
+uint32_t conidstschng :
+    1;
+uint32_t disconnect :
+    1;
+uint32_t sessreqintr :
+    1;
+uint32_t wkupintr :
+    1;
+  }
+  b;
+} USB_OTG_GINTMSK_TypeDef ;
+typedef union _USB_OTG_GINTSTS_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t curmode :
+    1;
+uint32_t modemismatch :
+    1;
+uint32_t otgintr :
+    1;
+uint32_t sofintr :
+    1;
+uint32_t rxstsqlvl :
+    1;
+uint32_t nptxfempty :
+    1;
+uint32_t ginnakeff :
+    1;
+uint32_t goutnakeff :
+    1;
+uint32_t Reserved8_9 :
+    2;
+uint32_t erlysuspend :
+    1;
+uint32_t usbsuspend :
+    1;
+uint32_t usbreset :
+    1;
+uint32_t enumdone :
+    1;
+uint32_t isooutdrop :
+    1;
+uint32_t eopframe :
+    1;
+uint32_t Reserved16_17 :
+    2;
+uint32_t inepint:
+    1;
+uint32_t outepintr :
+    1;
+uint32_t incomplisoin :
+    1;
+uint32_t incomplisoout :
+    1;
+uint32_t Reserved22_23 :
+    2;
+uint32_t portintr :
+    1;
+uint32_t hcintr :
+    1;
+uint32_t ptxfempty :
+    1;
+uint32_t Reserved27 :
+    1;
+uint32_t conidstschng :
+    1;
+uint32_t disconnect :
+    1;
+uint32_t sessreqintr :
+    1;
+uint32_t wkupintr :
+    1;
+  }
+  b;
+} USB_OTG_GINTSTS_TypeDef ;
+typedef union _USB_OTG_DRXSTS_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t epnum :
+    4;
+uint32_t bcnt :
+    11;
+uint32_t dpid :
+    2;
+uint32_t pktsts :
+    4;
+uint32_t fn :
+    4;
+uint32_t Reserved :
+    7;
+  }
+  b;
+} USB_OTG_DRXSTS_TypeDef ;
+typedef union _USB_OTG_GRXSTS_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t chnum :
+    4;
+uint32_t bcnt :
+    11;
+uint32_t dpid :
+    2;
+uint32_t pktsts :
+    4;
+uint32_t Reserved :
+    11;
+  }
+  b;
+} USB_OTG_GRXFSTS_TypeDef ;
+typedef union _USB_OTG_FSIZ_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t startaddr :
+    16;
+uint32_t depth :
+    16;
+  }
+  b;
+} USB_OTG_FSIZ_TypeDef ;
+typedef union _USB_OTG_HNPTXSTS_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+    uint32_t nptxfspcavail :
+      16;
+    uint32_t nptxqspcavail :
+      8;
+      struct
+        {
+          uint32_t terminate :
+            1;
+          uint32_t token :
+            2;
+          uint32_t chnum :
+            4; 
+         } nptxqtop;
+     uint32_t Reserved :
+        1;
+  }
+  b;
+} USB_OTG_HNPTXSTS_TypeDef ;
+typedef union _USB_OTG_DTXFSTSn_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t txfspcavail :
+    16;
+uint32_t Reserved :
+    16;
+  }
+  b;
+} USB_OTG_DTXFSTSn_TypeDef ;
+
+typedef union _USB_OTG_GCCFG_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t Reserved_in :
+    16;
+uint32_t pwdn :
+    1;
+uint32_t Reserved_17 :
+    1;
+uint32_t vbussensingA :
+    1;
+uint32_t vbussensingB :
+    1;
+uint32_t sofouten :
+    1;
+uint32_t disablevbussensing :
+    1;
+uint32_t Reserved_out :
+    10;
+  }
+  b;
+} USB_OTG_GCCFG_TypeDef ;
+
+typedef union _USB_OTG_DCFG_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t devspd :
+    2;
+uint32_t nzstsouthshk :
+    1;
+uint32_t Reserved3 :
+    1;
+uint32_t devaddr :
+    7;
+uint32_t perfrint :
+    2;
+uint32_t Reserved12_31 :
+    19;
+  }
+  b;
+} USB_OTG_DCFG_TypeDef ;
+typedef union _USB_OTG_DCTL_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t rmtwkupsig :
+    1;
+uint32_t sftdiscon :
+    1;
+uint32_t gnpinnaksts :
+    1;
+uint32_t goutnaksts :
+    1;
+uint32_t tstctl :
+    3;
+uint32_t sgnpinnak :
+    1;
+uint32_t cgnpinnak :
+    1;
+uint32_t sgoutnak :
+    1;
+uint32_t cgoutnak :
+    1;
+uint32_t poprg_done :
+    1;    
+uint32_t Reserved :
+    20;
+  }
+  b;
+} USB_OTG_DCTL_TypeDef ;
+typedef union _USB_OTG_DSTS_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t suspsts :
+    1;
+uint32_t enumspd :
+    2;
+uint32_t errticerr :
+    1;
+uint32_t Reserved4_7:
+    4;
+uint32_t soffn :
+    14;
+uint32_t Reserved22_31 :
+    10;
+  }
+  b;
+} USB_OTG_DSTS_TypeDef ;
+typedef union _USB_OTG_DIEPINTn_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t xfercompl :
+    1;
+uint32_t epdisabled :
+    1;
+uint32_t Reserved2 :
+    1;
+uint32_t timeout :
+    1;
+uint32_t intktxfemp :
+    1;
+uint32_t Reserved5 :
+    1;
+uint32_t inepnakeff :
+    1;
+uint32_t emptyintr :
+    1;
+uint32_t txfifoundrn :
+    1;
+uint32_t Reserved14_31 :
+    23;
+  }
+  b;
+} USB_OTG_DIEPINTn_TypeDef ;
+typedef union _USB_OTG_DIEPINTn_TypeDef   USB_OTG_DIEPMSK_TypeDef ;
+typedef union _USB_OTG_DOEPINTn_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t xfercompl :
+    1;
+uint32_t epdisabled :
+    1;
+uint32_t Reserved2 :
+    1;
+uint32_t setup :
+    1;
+uint32_t Reserved04_31 :
+    28;
+  }
+  b;
+} USB_OTG_DOEPINTn_TypeDef ;
+typedef union _USB_OTG_DOEPINTn_TypeDef   USB_OTG_DOEPMSK_TypeDef ;
+
+typedef union _USB_OTG_DAINT_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t in :
+    16;
+uint32_t out :
+    16;
+  }
+  ep;
+} USB_OTG_DAINT_TypeDef ;
+
+typedef union _USB_OTG_DTHRCTL_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t non_iso_thr_en :
+    1;
+uint32_t iso_thr_en :
+    1;
+uint32_t tx_thr_len :
+    9;
+uint32_t Reserved11_15 :
+    5;
+uint32_t rx_thr_en :
+    1;
+uint32_t rx_thr_len :
+    9;
+uint32_t Reserved26 : 
+    1;
+uint32_t arp_en :  
+    1;
+uint32_t Reserved28_31 :
+    4;   
+  }
+  b;
+} USB_OTG_DTHRCTL_TypeDef ;
+typedef union _USB_OTG_DEPCTL_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t mps :
+    11;
+uint32_t reserved :
+    4;
+uint32_t usbactep :
+    1;
+uint32_t dpid :
+    1;
+uint32_t naksts :
+    1;
+uint32_t eptype :
+    2;
+uint32_t snp :
+    1;
+uint32_t stall :
+    1;
+uint32_t txfnum :
+    4;
+uint32_t cnak :
+    1;
+uint32_t snak :
+    1;
+uint32_t setd0pid :
+    1;
+uint32_t setd1pid :
+    1;
+uint32_t epdis :
+    1;
+uint32_t epena :
+    1;
+  }
+  b;
+} USB_OTG_DEPCTL_TypeDef ;
+typedef union _USB_OTG_DEPXFRSIZ_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t xfersize :
+    19;
+uint32_t pktcnt :
+    10;
+uint32_t mc :
+    2;
+uint32_t Reserved :
+    1;
+  }
+  b;
+} USB_OTG_DEPXFRSIZ_TypeDef ;
+typedef union _USB_OTG_DEP0XFRSIZ_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t xfersize :
+    7;
+uint32_t Reserved7_18 :
+    12;
+uint32_t pktcnt :
+    2;
+uint32_t Reserved20_28 :
+    9;
+uint32_t supcnt :
+    2;
+    uint32_t Reserved31;
+  }
+  b;
+} USB_OTG_DEP0XFRSIZ_TypeDef ;
+typedef union _USB_OTG_HCFG_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t fslspclksel :
+    2;
+uint32_t fslssupp :
+    1;
+  }
+  b;
+} USB_OTG_HCFG_TypeDef ;
+typedef union _USB_OTG_HFRMINTRVL_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t frint :
+    16;
+uint32_t Reserved :
+    16;
+  }
+  b;
+} USB_OTG_HFRMINTRVL_TypeDef ;
+
+typedef union _USB_OTG_HFNUM_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t frnum :
+    16;
+uint32_t frrem :
+    16;
+  }
+  b;
+} USB_OTG_HFNUM_TypeDef ;
+typedef union _USB_OTG_HPTXSTS_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t ptxfspcavail :
+    16;
+uint32_t ptxqspcavail :
+    8;
+      struct
+        {
+          uint32_t terminate :
+            1;
+          uint32_t token :
+            2;
+          uint32_t chnum :
+            4; 
+          uint32_t odd_even :
+            1;            
+         } ptxqtop;    
+  }
+  b;
+} USB_OTG_HPTXSTS_TypeDef ;
+typedef union _USB_OTG_HPRT0_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t prtconnsts :
+    1;
+uint32_t prtconndet :
+    1;
+uint32_t prtena :
+    1;
+uint32_t prtenchng :
+    1;
+uint32_t prtovrcurract :
+    1;
+uint32_t prtovrcurrchng :
+    1;
+uint32_t prtres :
+    1;
+uint32_t prtsusp :
+    1;
+uint32_t prtrst :
+    1;
+uint32_t Reserved9 :
+    1;
+uint32_t prtlnsts :
+    2;
+uint32_t prtpwr :
+    1;
+uint32_t prttstctl :
+    4;
+uint32_t prtspd :
+    2;
+uint32_t Reserved19_31 :
+    13;
+  }
+  b;
+} USB_OTG_HPRT0_TypeDef ;
+typedef union _USB_OTG_HAINT_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t chint :
+    16;
+uint32_t Reserved :
+    16;
+  }
+  b;
+} USB_OTG_HAINT_TypeDef ;
+typedef union _USB_OTG_HAINTMSK_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t chint :
+    16;
+uint32_t Reserved :
+    16;
+  }
+  b;
+} USB_OTG_HAINTMSK_TypeDef ;
+typedef union _USB_OTG_HCCHAR_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t mps :
+    11;
+uint32_t epnum :
+    4;
+uint32_t epdir :
+    1;
+uint32_t Reserved :
+    1;
+uint32_t lspddev :
+    1;
+uint32_t eptype :
+    2;
+uint32_t multicnt :
+    2;
+uint32_t devaddr :
+    7;
+uint32_t oddfrm :
+    1;
+uint32_t chdis :
+    1;
+uint32_t chen :
+    1;
+  }
+  b;
+} USB_OTG_HCCHAR_TypeDef ;
+typedef union _USB_OTG_HCSPLT_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t prtaddr :
+    7;
+uint32_t hubaddr :
+    7;
+uint32_t xactpos :
+    2;
+uint32_t compsplt :
+    1;
+uint32_t Reserved :
+    14;
+uint32_t spltena :
+    1;
+  }
+  b;
+} USB_OTG_HCSPLT_TypeDef ;
+typedef union _USB_OTG_HCINTn_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t xfercompl :
+    1;
+uint32_t chhltd :
+    1;
+uint32_t ahberr :
+    1;
+uint32_t stall :
+    1;
+uint32_t nak :
+    1;
+uint32_t ack :
+    1;
+uint32_t nyet :
+    1;
+uint32_t xacterr :
+    1;
+uint32_t bblerr :
+    1;
+uint32_t frmovrun :
+    1;
+uint32_t datatglerr :
+    1;
+uint32_t Reserved :
+    21;
+  }
+  b;
+} USB_OTG_HCINTn_TypeDef ;
+typedef union _USB_OTG_HCTSIZn_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t xfersize :
+    19;
+uint32_t pktcnt :
+    10;
+uint32_t pid :
+    2;
+uint32_t dopng :
+    1;
+  }
+  b;
+} USB_OTG_HCTSIZn_TypeDef ;
+typedef union _USB_OTG_HCINTMSK_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t xfercompl :
+    1;
+uint32_t chhltd :
+    1;
+uint32_t ahberr :
+    1;
+uint32_t stall :
+    1;
+uint32_t nak :
+    1;
+uint32_t ack :
+    1;
+uint32_t nyet :
+    1;
+uint32_t xacterr :
+    1;
+uint32_t bblerr :
+    1;
+uint32_t frmovrun :
+    1;
+uint32_t datatglerr :
+    1;
+uint32_t Reserved :
+    21;
+  }
+  b;
+} USB_OTG_HCINTMSK_TypeDef ;
+
+typedef union _USB_OTG_PCGCCTL_TypeDef 
+{
+  uint32_t d32;
+  struct
+  {
+uint32_t stoppclk :
+    1;
+uint32_t gatehclk :
+    1;
+uint32_t Reserved2_3 :
+    2;
+uint32_t phy_susp :
+    1;    
+uint32_t Reserved5_31 :
+    27;
+  }
+  b;
+} USB_OTG_PCGCCTL_TypeDef ;
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_REGS_Exported_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_REGS_Exported_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_REGS_Exported_FunctionsPrototype
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+#endif //__USB_OTG_REGS_H__
+
+
+/**
+  * @}
+  */ 
+
+/**
+  * @}
+  */ 
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_bsp_template.c b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_bsp_template.c
new file mode 100644
index 0000000000000000000000000000000000000000..27066cd95c3292b95dd13ffebd82663b742329f9
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_bsp_template.c
@@ -0,0 +1,206 @@
+/**
+  ******************************************************************************
+  * @file    usb_bsp.c
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   This file is responsible to offer board support package and is
+  *          configurable by user.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */ 
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_bsp.h"
+
+/** @addtogroup USB_OTG_DRIVER
+* @{
+*/
+
+/** @defgroup USB_BSP
+  * @brief This file is responsible to offer board support package
+  * @{
+  */ 
+
+/** @defgroup USB_BSP_Private_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_BSP_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+
+
+
+/** @defgroup USB_BSP_Private_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USBH_BSP_Private_Variables
+  * @{
+  */ 
+
+/**
+  * @}
+  */ 
+
+/** @defgroup USBH_BSP_Private_FunctionPrototypes
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+/** @defgroup USB_BSP_Private_Functions
+  * @{
+  */ 
+
+
+/**
+  * @brief  USB_OTG_BSP_Init
+  *         Initilizes BSP configurations
+  * @param  None
+  * @retval None
+  */
+
+void USB_OTG_BSP_Init(void)
+{
+
+}
+/**
+  * @brief  USB_OTG_BSP_EnableInterrupt
+  *         Enabele USB Global interrupt
+  * @param  None
+  * @retval None
+  */
+void USB_OTG_BSP_EnableInterrupt(void)
+{
+
+}
+
+/**
+  * @brief  BSP_Drive_VBUS
+  *         Drives the Vbus signal through IO
+  * @param  speed : Full, Low 
+  * @param  state : VBUS states
+  * @retval None
+  */
+
+void USB_OTG_BSP_DriveVBUS(uint32_t speed, uint8_t state)
+{
+
+}
+
+/**
+  * @brief  USB_OTG_BSP_ConfigVBUS
+  *         Configures the IO for the Vbus and OverCurrent
+  * @param  Speed : Full, Low 
+  * @retval None
+  */
+
+void  USB_OTG_BSP_ConfigVBUS(uint32_t speed)
+{
+
+}
+
+/**
+  * @brief  USB_OTG_BSP_TimeInit
+  *         Initialises delay unit Systick timer /Timer2
+  * @param  None
+  * @retval None
+  */
+void USB_OTG_BSP_TimeInit ( void )
+{
+
+}
+
+/**
+  * @brief  USB_OTG_BSP_uDelay
+  *         This function provides delay time in micro sec
+  * @param  usec : Value of delay required in micro sec
+  * @retval None
+  */
+void USB_OTG_BSP_uDelay (const uint32_t usec)
+{
+
+  uint32_t count = 0;
+  const uint32_t utime = (120 * usec / 7);
+  do
+  {
+    if ( ++count > utime )
+    {
+      return ;
+    }
+  }
+  while (1); 
+  
+}
+
+
+/**
+  * @brief  USB_OTG_BSP_mDelay
+  *          This function provides delay time in milli sec
+  * @param  msec : Value of delay required in milli sec
+  * @retval None
+  */
+void USB_OTG_BSP_mDelay (const uint32_t msec)
+{
+
+    USB_OTG_BSP_uDelay(msec * 1000);    
+
+}
+
+
+/**
+  * @brief  USB_OTG_BSP_TimerIRQ
+  *         Time base IRQ
+  * @param  None
+  * @retval None
+  */
+
+void USB_OTG_BSP_TimerIRQ (void)
+{
+
+} 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_core.c b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_core.c
new file mode 100644
index 0000000000000000000000000000000000000000..e257e73dc4c0166c9acc32c8b3349d0a0cf5afcc
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_core.c
@@ -0,0 +1,2162 @@
+/**
+  ******************************************************************************
+  * @file    usb_core.c
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   USB-OTG Core Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_core.h"
+#include "usb_bsp.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+* @{
+*/
+
+/** @defgroup USB_CORE 
+* @brief This file includes the USB-OTG Core Layer
+* @{
+*/
+
+
+/** @defgroup USB_CORE_Private_Defines
+* @{
+*/ 
+
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_CORE_Private_TypesDefinitions
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+
+/** @defgroup USB_CORE_Private_Macros
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_CORE_Private_Variables
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_CORE_Private_FunctionPrototypes
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_CORE_Private_Functions
+* @{
+*/ 
+
+/**
+* @brief  USB_OTG_EnableCommonInt
+*         Initializes the commmon interrupts, used in both device and modes
+* @param  pdev : Selected device
+* @retval None
+*/
+static void USB_OTG_EnableCommonInt(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTMSK_TypeDef  int_mask;
+  
+  int_mask.d32 = 0;
+  /* Clear any pending USB_OTG Interrupts */
+#ifndef USE_OTG_MODE
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GOTGINT, 0xFFFFFFFF);
+#endif
+  /* Clear any pending interrupts */
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xBFFFFFFF);
+  /* Enable the interrupts in the INTMSK */
+  int_mask.b.wkupintr = 1;
+  int_mask.b.usbsuspend = 1; 
+  
+#ifdef USE_OTG_MODE
+  int_mask.b.otgintr = 1;
+  int_mask.b.sessreqintr = 1;
+  int_mask.b.conidstschng = 1;
+#endif
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTMSK, int_mask.d32);
+}
+
+/**
+* @brief  USB_OTG_CoreReset : Soft reset of the core
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+static USB_OTG_STS USB_OTG_CoreReset(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  __IO USB_OTG_GRSTCTL_TypeDef  greset;
+  uint32_t count = 0;
+  
+  greset.d32 = 0;
+  /* Wait for AHB master IDLE state. */
+  do
+  {
+    USB_OTG_BSP_uDelay(3);
+    greset.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRSTCTL);
+    if (++count > 200000)
+    {
+      return USB_OTG_OK;
+    }
+  }
+  while (greset.b.ahbidle == 0);
+  /* Core Soft Reset */
+  count = 0;
+  greset.b.csftrst = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRSTCTL, greset.d32 );
+  do
+  {
+    greset.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRSTCTL);
+    if (++count > 200000)
+    {
+      break;
+    }
+  }
+  while (greset.b.csftrst == 1);
+  /* Wait for 3 PHY Clocks*/
+  USB_OTG_BSP_uDelay(3);
+  return status;
+}
+
+/**
+* @brief  USB_OTG_WritePacket : Writes a packet into the Tx FIFO associated 
+*         with the EP
+* @param  pdev : Selected device
+* @param  src : source pointer
+* @param  ch_ep_num : end point number
+* @param  bytes : No. of bytes
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_WritePacket(USB_OTG_CORE_HANDLE *pdev, 
+                                uint8_t             *src, 
+                                uint8_t             ch_ep_num, 
+                                uint16_t            len)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  if (pdev->cfg.dma_enable == 0)
+  {
+    uint32_t count32b= 0 , i= 0;
+    __IO uint32_t *fifo;
+    
+    count32b =  (len + 3) / 4;
+    fifo = pdev->regs.DFIFO[ch_ep_num];
+    for (i = 0; i < count32b; i++, src+=4)
+    {
+      USB_OTG_WRITE_REG32( fifo, *((__packed uint32_t *)src) );
+    }
+  }
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_ReadPacket : Reads a packet from the Rx FIFO
+* @param  pdev : Selected device
+* @param  dest : Destination Pointer
+* @param  bytes : No. of bytes
+* @retval None
+*/
+void *USB_OTG_ReadPacket(USB_OTG_CORE_HANDLE *pdev, 
+                         uint8_t *dest, 
+                         uint16_t len)
+{
+  uint32_t i=0;
+  uint32_t count32b = (len + 3) / 4;
+  
+  __IO uint32_t *fifo = pdev->regs.DFIFO[0];
+  
+  for ( i = 0; i < count32b; i++, dest += 4 )
+  {
+    *(__packed uint32_t *)dest = USB_OTG_READ_REG32(fifo);
+    
+  }
+  return ((void *)dest);
+}
+
+/**
+* @brief  USB_OTG_SelectCore 
+*         Initialize core registers address.
+* @param  pdev : Selected device
+* @param  coreID : USB OTG Core ID
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_SelectCore(USB_OTG_CORE_HANDLE *pdev, 
+                               USB_OTG_CORE_ID_TypeDef coreID)
+{
+  uint32_t i , baseAddress = 0;
+  USB_OTG_STS status = USB_OTG_OK;
+  
+  pdev->cfg.dma_enable       = 0;
+  
+  /* at startup the core is in FS mode */
+  pdev->cfg.speed            = USB_OTG_SPEED_FULL;
+  pdev->cfg.mps              = USB_OTG_FS_MAX_PACKET_SIZE ;    
+  
+  /* initialize device cfg following its address */
+  if (coreID == USB_OTG_FS_CORE_ID)
+  {
+    baseAddress                = USB_OTG_FS_BASE_ADDR;
+    pdev->cfg.coreID           = USB_OTG_FS_CORE_ID;
+    pdev->cfg.host_channels    = 8 ;
+    pdev->cfg.dev_endpoints    = 4 ;
+    pdev->cfg.TotalFifoSize    = 320; /* in 32-bits */
+    pdev->cfg.phy_itface       = USB_OTG_EMBEDDED_PHY;     
+    
+#ifdef USB_OTG_FS_SOF_OUTPUT_ENABLED    
+    pdev->cfg.Sof_output       = 1;    
+#endif 
+    
+#ifdef USB_OTG_FS_LOW_PWR_MGMT_SUPPORT    
+    pdev->cfg.low_power        = 1;    
+#endif     
+  }
+  else if (coreID == USB_OTG_HS_CORE_ID)
+  {
+    baseAddress                = USB_OTG_HS_BASE_ADDR;
+    pdev->cfg.coreID           = USB_OTG_HS_CORE_ID;    
+    pdev->cfg.host_channels    = 12 ;
+    pdev->cfg.dev_endpoints    = 6 ;
+    pdev->cfg.TotalFifoSize    = 1280;/* in 32-bits */
+    
+#ifdef USB_OTG_ULPI_PHY_ENABLED
+    pdev->cfg.phy_itface       = USB_OTG_ULPI_PHY;
+#else    
+#ifdef USB_OTG_EMBEDDED_PHY_ENABLED
+    pdev->cfg.phy_itface       = USB_OTG_EMBEDDED_PHY;
+#endif  
+#endif      
+    
+#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED    
+    pdev->cfg.dma_enable       = 1;    
+#endif
+    
+#ifdef USB_OTG_HS_SOF_OUTPUT_ENABLED    
+    pdev->cfg.Sof_output       = 1;    
+#endif 
+    
+#ifdef USB_OTG_HS_LOW_PWR_MGMT_SUPPORT    
+    pdev->cfg.low_power        = 1;    
+#endif 
+    
+  }
+  
+  pdev->regs.GREGS = (USB_OTG_GREGS *)(baseAddress + \
+    USB_OTG_CORE_GLOBAL_REGS_OFFSET);
+  pdev->regs.DREGS =  (USB_OTG_DREGS  *)  (baseAddress + \
+    USB_OTG_DEV_GLOBAL_REG_OFFSET);
+  
+  for (i = 0; i < pdev->cfg.dev_endpoints; i++)
+  {
+    pdev->regs.INEP_REGS[i]  = (USB_OTG_INEPREGS *)  \
+      (baseAddress + USB_OTG_DEV_IN_EP_REG_OFFSET + \
+        (i * USB_OTG_EP_REG_OFFSET));
+    pdev->regs.OUTEP_REGS[i] = (USB_OTG_OUTEPREGS *) \
+      (baseAddress + USB_OTG_DEV_OUT_EP_REG_OFFSET + \
+        (i * USB_OTG_EP_REG_OFFSET));
+  }
+  pdev->regs.HREGS = (USB_OTG_HREGS *)(baseAddress + \
+    USB_OTG_HOST_GLOBAL_REG_OFFSET);
+  pdev->regs.HPRT0 = (uint32_t *)(baseAddress + USB_OTG_HOST_PORT_REGS_OFFSET);
+  
+  for (i = 0; i < pdev->cfg.host_channels; i++)
+  {
+    pdev->regs.HC_REGS[i] = (USB_OTG_HC_REGS *)(baseAddress + \
+      USB_OTG_HOST_CHAN_REGS_OFFSET + \
+        (i * USB_OTG_CHAN_REGS_OFFSET));
+  }
+  for (i = 0; i < pdev->cfg.host_channels; i++)
+  {
+    pdev->regs.DFIFO[i] = (uint32_t *)(baseAddress + USB_OTG_DATA_FIFO_OFFSET +\
+      (i * USB_OTG_DATA_FIFO_SIZE));
+  }
+  pdev->regs.PCGCCTL = (uint32_t *)(baseAddress + USB_OTG_PCGCCTL_OFFSET);
+  
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_CoreInit
+*         Initializes the USB_OTG controller registers and prepares the core
+*         device mode or host mode operation.
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_CoreInit(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_GUSBCFG_TypeDef  usbcfg;
+  USB_OTG_GCCFG_TypeDef    gccfg;
+  USB_OTG_GAHBCFG_TypeDef  ahbcfg;
+  
+  usbcfg.d32 = 0;
+  gccfg.d32 = 0;
+  ahbcfg.d32 = 0;
+  
+  
+  
+  if (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY)
+  {
+    gccfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GCCFG);
+    gccfg.b.pwdn = 0;
+    
+    if (pdev->cfg.Sof_output)
+    {
+      gccfg.b.sofouten = 1;   
+    }
+    USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GCCFG, gccfg.d32);
+    
+    /* Init The ULPI Interface */
+    usbcfg.d32 = 0;
+    usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
+    
+    usbcfg.b.physel            = 0; /* HS Interface */
+#ifdef USB_OTG_INTERNAL_VBUS_ENABLED
+    usbcfg.b.ulpi_ext_vbus_drv = 0; /* Use internal VBUS */
+#else
+#ifdef USB_OTG_EXTERNAL_VBUS_ENABLED    
+    usbcfg.b.ulpi_ext_vbus_drv = 1; /* Use external VBUS */
+#endif
+#endif 
+    usbcfg.b.term_sel_dl_pulse = 0; /* Data line pulsing using utmi_txvalid */    
+    
+    usbcfg.b.ulpi_fsls = 0;
+    usbcfg.b.ulpi_clk_sus_m = 0;
+    USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
+    
+    /* Reset after a PHY select  */
+    USB_OTG_CoreReset(pdev);
+    
+    if(pdev->cfg.dma_enable == 1)
+    {
+      
+      ahbcfg.b.hburstlen = 5; /* 64 x 32-bits*/
+      ahbcfg.b.dmaenable = 1;
+      USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GAHBCFG, ahbcfg.d32);
+      
+    }    
+  }
+  else /* FS interface (embedded Phy) */
+  {
+    
+    usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);;
+    usbcfg.b.physel  = 1; /* FS Interface */
+    USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
+    /* Reset after a PHY select and set Host mode */
+    USB_OTG_CoreReset(pdev);
+    /* Deactivate the power down*/
+    gccfg.d32 = 0;
+    gccfg.b.pwdn = 1;
+    
+    gccfg.b.vbussensingA = 1 ;
+    gccfg.b.vbussensingB = 1 ;     
+#ifndef VBUS_SENSING_ENABLED
+    gccfg.b.disablevbussensing = 1; 
+#endif    
+    
+    if(pdev->cfg.Sof_output)
+    {
+      gccfg.b.sofouten = 1;  
+    }
+    
+    USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GCCFG, gccfg.d32);
+    USB_OTG_BSP_mDelay(20);
+  }
+  /* case the HS core is working in FS mode */
+  if(pdev->cfg.dma_enable == 1)
+  {
+    
+    ahbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GAHBCFG);
+    ahbcfg.b.hburstlen = 5; /* 64 x 32-bits*/
+    ahbcfg.b.dmaenable = 1;
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GAHBCFG, ahbcfg.d32);
+    
+  }
+  /* initialize OTG features */
+#ifdef  USE_OTG_MODE
+  usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
+  usbcfg.b.hnpcap = 1;
+  usbcfg.b.srpcap = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
+  USB_OTG_EnableCommonInt(pdev);
+#endif
+  return status;
+}
+/**
+* @brief  USB_OTG_EnableGlobalInt
+*         Enables the controller's Global Int in the AHB Config reg
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EnableGlobalInt(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_GAHBCFG_TypeDef  ahbcfg;
+  
+  ahbcfg.d32 = 0;
+  ahbcfg.b.glblintrmsk = 1; /* Enable interrupts */
+  USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GAHBCFG, 0, ahbcfg.d32);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_DisableGlobalInt
+*         Enables the controller's Global Int in the AHB Config reg
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_DisableGlobalInt(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_GAHBCFG_TypeDef  ahbcfg;
+  ahbcfg.d32 = 0;
+  ahbcfg.b.glblintrmsk = 1; /* Enable interrupts */
+  USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GAHBCFG, ahbcfg.d32, 0);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_FlushTxFifo : Flush a Tx FIFO
+* @param  pdev : Selected device
+* @param  num : FO num
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_FlushTxFifo (USB_OTG_CORE_HANDLE *pdev , uint32_t num )
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  __IO USB_OTG_GRSTCTL_TypeDef  greset;
+  
+  uint32_t count = 0;
+  greset.d32 = 0;
+  greset.b.txfflsh = 1;
+  greset.b.txfnum  = num;
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GRSTCTL, greset.d32 );
+  do
+  {
+    greset.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRSTCTL);
+    if (++count > 200000)
+    {
+      break;
+    }
+  }
+  while (greset.b.txfflsh == 1);
+  /* Wait for 3 PHY Clocks*/
+  USB_OTG_BSP_uDelay(3);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_FlushRxFifo : Flush a Rx FIFO
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_FlushRxFifo( USB_OTG_CORE_HANDLE *pdev )
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  __IO USB_OTG_GRSTCTL_TypeDef  greset;
+  uint32_t count = 0;
+  
+  greset.d32 = 0;
+  greset.b.rxfflsh = 1;
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GRSTCTL, greset.d32 );
+  do
+  {
+    greset.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRSTCTL);
+    if (++count > 200000)
+    {
+      break;
+    }
+  }
+  while (greset.b.rxfflsh == 1);
+  /* Wait for 3 PHY Clocks*/
+  USB_OTG_BSP_uDelay(3);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_SetCurrentMode : Set ID line
+* @param  pdev : Selected device
+* @param  mode :  (Host/device)
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_SetCurrentMode(USB_OTG_CORE_HANDLE *pdev , uint8_t mode)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_GUSBCFG_TypeDef  usbcfg;
+  
+  usbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
+  
+  usbcfg.b.force_host = 0;
+  usbcfg.b.force_dev = 0;
+  
+  if ( mode == HOST_MODE)
+  {
+    usbcfg.b.force_host = 1;
+  }
+  else if ( mode == DEVICE_MODE)
+  {
+    usbcfg.b.force_dev = 1;
+  }
+  
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, usbcfg.d32);
+  USB_OTG_BSP_mDelay(50);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_GetMode : Get current mode
+* @param  pdev : Selected device
+* @retval current mode
+*/
+uint32_t USB_OTG_GetMode(USB_OTG_CORE_HANDLE *pdev)
+{
+  return (USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS ) & 0x1);
+}
+
+
+/**
+* @brief  USB_OTG_IsDeviceMode : Check if it is device mode
+* @param  pdev : Selected device
+* @retval num_in_ep
+*/
+uint8_t USB_OTG_IsDeviceMode(USB_OTG_CORE_HANDLE *pdev)
+{
+  return (USB_OTG_GetMode(pdev) != HOST_MODE);
+}
+
+
+/**
+* @brief  USB_OTG_IsHostMode : Check if it is host mode
+* @param  pdev : Selected device
+* @retval num_in_ep
+*/
+uint8_t USB_OTG_IsHostMode(USB_OTG_CORE_HANDLE *pdev)
+{
+  return (USB_OTG_GetMode(pdev) == HOST_MODE);
+}
+
+
+/**
+* @brief  USB_OTG_ReadCoreItr : returns the Core Interrupt register
+* @param  pdev : Selected device
+* @retval Status
+*/
+uint32_t USB_OTG_ReadCoreItr(USB_OTG_CORE_HANDLE *pdev)
+{
+  uint32_t v = 0;
+  v = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS);
+  v &= USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTMSK);
+  return v;
+}
+
+
+/**
+* @brief  USB_OTG_ReadOtgItr : returns the USB_OTG Interrupt register
+* @param  pdev : Selected device
+* @retval Status
+*/
+uint32_t USB_OTG_ReadOtgItr (USB_OTG_CORE_HANDLE *pdev)
+{
+  return (USB_OTG_READ_REG32 (&pdev->regs.GREGS->GOTGINT));
+}
+
+#ifdef USE_HOST_MODE
+/**
+* @brief  USB_OTG_CoreInitHost : Initializes USB_OTG controller for host mode
+* @param  pdev : Selected device
+* @retval status
+*/
+USB_OTG_STS USB_OTG_CoreInitHost(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS                     status = USB_OTG_OK;
+  USB_OTG_FSIZ_TypeDef            nptxfifosize;
+  USB_OTG_FSIZ_TypeDef            ptxfifosize;  
+  USB_OTG_HCFG_TypeDef            hcfg;
+  
+#ifdef USE_OTG_MODE
+  USB_OTG_OTGCTL_TypeDef          gotgctl;
+#endif
+  
+  uint32_t                        i = 0;
+  
+  nptxfifosize.d32 = 0;  
+  ptxfifosize.d32 = 0;
+#ifdef USE_OTG_MODE
+  gotgctl.d32 = 0;
+#endif
+  hcfg.d32 = 0;
+  
+  
+  /* configure charge pump IO */
+  USB_OTG_BSP_ConfigVBUS(pdev);
+  
+  /* Restart the Phy Clock */
+  USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, 0);
+  
+  /* Initialize Host Configuration Register */
+  if (pdev->cfg.phy_itface == USB_OTG_ULPI_PHY)
+  {
+    USB_OTG_InitFSLSPClkSel(pdev , HCFG_30_60_MHZ); 
+  }
+  else
+  {
+    USB_OTG_InitFSLSPClkSel(pdev , HCFG_48_MHZ); 
+  }
+  USB_OTG_ResetPort(pdev);
+  
+  hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG);
+  hcfg.b.fslssupp = 0;
+  USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HCFG, hcfg.d32);
+  
+  /* Configure data FIFO sizes */
+  /* Rx FIFO */
+#ifdef USB_OTG_FS_CORE
+  if(pdev->cfg.coreID == USB_OTG_FS_CORE_ID)
+  {
+    /* set Rx FIFO size */
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_FS_SIZE);
+    nptxfifosize.b.startaddr = RX_FIFO_FS_SIZE;   
+    nptxfifosize.b.depth = TXH_NP_FS_FIFOSIZ;  
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32);
+    
+    ptxfifosize.b.startaddr = RX_FIFO_FS_SIZE + TXH_NP_FS_FIFOSIZ;
+    ptxfifosize.b.depth     = TXH_P_FS_FIFOSIZ;
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->HPTXFSIZ, ptxfifosize.d32);      
+  }
+#endif
+#ifdef USB_OTG_HS_CORE  
+  if (pdev->cfg.coreID == USB_OTG_HS_CORE_ID)
+  {
+    /* set Rx FIFO size */
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_HS_SIZE);
+    nptxfifosize.b.startaddr = RX_FIFO_HS_SIZE;   
+    nptxfifosize.b.depth = TXH_NP_HS_FIFOSIZ;  
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32);
+    
+    ptxfifosize.b.startaddr = RX_FIFO_HS_SIZE + TXH_NP_HS_FIFOSIZ;
+    ptxfifosize.b.depth     = TXH_P_HS_FIFOSIZ;
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->HPTXFSIZ, ptxfifosize.d32);      
+  }
+#endif  
+  
+#ifdef USE_OTG_MODE
+  /* Clear Host Set HNP Enable in the USB_OTG Control Register */
+  gotgctl.b.hstsethnpen = 1;
+  USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GOTGCTL, gotgctl.d32, 0);
+#endif
+  
+  /* Make sure the FIFOs are flushed. */
+  USB_OTG_FlushTxFifo(pdev, 0x10 );         /* all Tx FIFOs */
+  USB_OTG_FlushRxFifo(pdev);
+  
+  
+  /* Clear all pending HC Interrupts */
+  for (i = 0; i < pdev->cfg.host_channels; i++)
+  {
+    USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCINT, 0xFFFFFFFF );
+    USB_OTG_WRITE_REG32( &pdev->regs.HC_REGS[i]->HCINTMSK, 0 );
+  }
+#ifndef USE_OTG_MODE
+  USB_OTG_DriveVbus(pdev, 1);
+#endif
+  
+  USB_OTG_EnableHostInt(pdev);
+  return status;
+}
+
+/**
+* @brief  USB_OTG_IsEvenFrame 
+*         This function returns the frame number for sof packet
+* @param  pdev : Selected device
+* @retval Frame number
+*/
+uint8_t USB_OTG_IsEvenFrame (USB_OTG_CORE_HANDLE *pdev) 
+{
+  return !(USB_OTG_READ_REG32(&pdev->regs.HREGS->HFNUM) & 0x1);
+}
+
+/**
+* @brief  USB_OTG_DriveVbus : set/reset vbus
+* @param  pdev : Selected device
+* @param  state : VBUS state
+* @retval None
+*/
+void USB_OTG_DriveVbus (USB_OTG_CORE_HANDLE *pdev, uint8_t state)
+{
+  USB_OTG_HPRT0_TypeDef     hprt0;
+  
+  hprt0.d32 = 0;
+  
+  /* enable disable the external charge pump */
+  USB_OTG_BSP_DriveVBUS(pdev, state);
+  
+  /* Turn on the Host port power. */
+  hprt0.d32 = USB_OTG_ReadHPRT0(pdev);
+  if ((hprt0.b.prtpwr == 0 ) && (state == 1 ))
+  {
+    hprt0.b.prtpwr = 1;
+    USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
+  }
+  if ((hprt0.b.prtpwr == 1 ) && (state == 0 ))
+  {
+    hprt0.b.prtpwr = 0;
+    USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
+  }
+  
+  USB_OTG_BSP_mDelay(200);
+}
+/**
+* @brief  USB_OTG_EnableHostInt: Enables the Host mode interrupts
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EnableHostInt(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS       status = USB_OTG_OK;
+  USB_OTG_GINTMSK_TypeDef  intmsk;
+  intmsk.d32 = 0;
+  /* Disable all interrupts. */
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTMSK, 0);
+  
+  /* Clear any pending interrupts. */
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, 0xFFFFFFFF);
+  
+  /* Enable the common interrupts */
+  USB_OTG_EnableCommonInt(pdev);
+  
+  if (pdev->cfg.dma_enable == 0)
+  {  
+    intmsk.b.rxstsqlvl  = 1;
+  }  
+  intmsk.b.portintr   = 1;
+  intmsk.b.hcintr     = 1;
+  intmsk.b.disconnect = 1;  
+  intmsk.b.sofintr    = 1;  
+  intmsk.b.incomplisoout  = 1; 
+  USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32);
+  return status;
+}
+
+/**
+* @brief  USB_OTG_InitFSLSPClkSel : Initializes the FSLSPClkSel field of the 
+*         HCFG register on the PHY type
+* @param  pdev : Selected device
+* @param  freq : clock frequency
+* @retval None
+*/
+void USB_OTG_InitFSLSPClkSel(USB_OTG_CORE_HANDLE *pdev , uint8_t freq)
+{
+  USB_OTG_HCFG_TypeDef   hcfg;
+  
+  hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG);
+  hcfg.b.fslspclksel = freq;
+  USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HCFG, hcfg.d32);
+}
+
+
+/**
+* @brief  USB_OTG_ReadHPRT0 : Reads HPRT0 to modify later
+* @param  pdev : Selected device
+* @retval HPRT0 value
+*/
+uint32_t USB_OTG_ReadHPRT0(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_HPRT0_TypeDef  hprt0;
+  
+  hprt0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
+  hprt0.b.prtena = 0;
+  hprt0.b.prtconndet = 0;
+  hprt0.b.prtenchng = 0;
+  hprt0.b.prtovrcurrchng = 0;
+  return hprt0.d32;
+}
+
+
+/**
+* @brief  USB_OTG_ReadHostAllChannels_intr : Register PCD Callbacks
+* @param  pdev : Selected device
+* @retval Status
+*/
+uint32_t USB_OTG_ReadHostAllChannels_intr (USB_OTG_CORE_HANDLE *pdev)
+{
+  return (USB_OTG_READ_REG32 (&pdev->regs.HREGS->HAINT));
+}
+
+
+/**
+* @brief  USB_OTG_ResetPort : Reset Host Port
+* @param  pdev : Selected device
+* @retval status
+* @note : (1)The application must wait at least 10 ms (+ 10 ms security)
+*   before clearing the reset bit.
+*/
+uint32_t USB_OTG_ResetPort(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_HPRT0_TypeDef  hprt0;
+  
+  hprt0.d32 = USB_OTG_ReadHPRT0(pdev);
+  hprt0.b.prtrst = 1;
+  USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
+  USB_OTG_BSP_mDelay (10);                                /* See Note #1 */
+  hprt0.b.prtrst = 0;
+  USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
+  USB_OTG_BSP_mDelay (20);   
+  return 1;
+}
+
+
+/**
+* @brief  USB_OTG_HC_Init : Prepares a host channel for transferring packets
+* @param  pdev : Selected device
+* @param  hc_num : channel number
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_HC_Init(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  uint32_t intr_enable = 0;
+  USB_OTG_HCINTMSK_TypeDef  hcintmsk;
+  USB_OTG_GINTMSK_TypeDef    gintmsk;
+  USB_OTG_HCCHAR_TypeDef     hcchar;
+  USB_OTG_HCINTn_TypeDef     hcint;
+  
+  
+  gintmsk.d32 = 0;
+  hcintmsk.d32 = 0;
+  hcchar.d32 = 0;
+  
+  /* Clear old interrupt conditions for this host channel. */
+  hcint.d32 = 0xFFFFFFFF;
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINT, hcint.d32);
+  
+  /* Enable channel interrupts required for this transfer. */
+  hcintmsk.d32 = 0;
+  
+  if (pdev->cfg.dma_enable == 1)
+  {
+    hcintmsk.b.ahberr = 1;
+  }
+  
+  switch (pdev->host.hc[hc_num].ep_type) 
+  {
+  case EP_TYPE_CTRL:
+  case EP_TYPE_BULK:
+    hcintmsk.b.xfercompl = 1;
+    hcintmsk.b.stall = 1;
+    hcintmsk.b.xacterr = 1;
+    hcintmsk.b.datatglerr = 1;
+    hcintmsk.b.nak = 1;  
+    if (pdev->host.hc[hc_num].ep_is_in) 
+    {
+      hcintmsk.b.bblerr = 1;
+    } 
+    else 
+    {
+      hcintmsk.b.nyet = 1;
+      if (pdev->host.hc[hc_num].do_ping) 
+      {
+        hcintmsk.b.ack = 1;
+      }
+    }
+    break;
+  case EP_TYPE_INTR:
+    hcintmsk.b.xfercompl = 1;
+    hcintmsk.b.nak = 1;
+    hcintmsk.b.stall = 1;
+    hcintmsk.b.xacterr = 1;
+    hcintmsk.b.datatglerr = 1;
+    hcintmsk.b.frmovrun = 1;
+    
+    if (pdev->host.hc[hc_num].ep_is_in) 
+    {
+      hcintmsk.b.bblerr = 1;
+    }
+    
+    break;
+  case EP_TYPE_ISOC:
+    hcintmsk.b.xfercompl = 1;
+    hcintmsk.b.frmovrun = 1;
+    hcintmsk.b.ack = 1;
+    
+    if (pdev->host.hc[hc_num].ep_is_in) 
+    {
+      hcintmsk.b.xacterr = 1;
+      hcintmsk.b.bblerr = 1;
+    }
+    break;
+  }
+  
+  
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCINTMSK, hcintmsk.d32);
+  
+  
+  /* Enable the top level host channel interrupt. */
+  intr_enable = (1 << hc_num);
+  USB_OTG_MODIFY_REG32(&pdev->regs.HREGS->HAINTMSK, 0, intr_enable);
+  
+  /* Make sure host channel interrupts are enabled. */
+  gintmsk.b.hcintr = 1;
+  USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, 0, gintmsk.d32);
+  
+  /* Program the HCCHAR register */
+  hcchar.d32 = 0;
+  hcchar.b.devaddr = pdev->host.hc[hc_num].dev_addr;
+  hcchar.b.epnum   = pdev->host.hc[hc_num].ep_num;
+  hcchar.b.epdir   = pdev->host.hc[hc_num].ep_is_in;
+  hcchar.b.lspddev = (pdev->host.hc[hc_num].speed == HPRT0_PRTSPD_LOW_SPEED);
+  hcchar.b.eptype  = pdev->host.hc[hc_num].ep_type;
+  hcchar.b.mps     = pdev->host.hc[hc_num].max_packet;
+  if (pdev->host.hc[hc_num].ep_type == HCCHAR_INTR)
+  {
+    hcchar.b.oddfrm  = 1;
+  }
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_HC_StartXfer : Start transfer
+* @param  pdev : Selected device
+* @param  hc_num : channel number
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_HC_StartXfer(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_HCCHAR_TypeDef   hcchar;
+  USB_OTG_HCTSIZn_TypeDef  hctsiz;
+  USB_OTG_HNPTXSTS_TypeDef hnptxsts; 
+  USB_OTG_HPTXSTS_TypeDef  hptxsts; 
+  USB_OTG_GINTMSK_TypeDef  intmsk;
+  uint16_t                 len_words = 0;   
+  
+  uint16_t num_packets;
+  uint16_t max_hc_pkt_count;
+  
+  max_hc_pkt_count = 256;
+  hctsiz.d32 = 0;
+  hcchar.d32 = 0;
+  intmsk.d32 = 0;
+  
+  /* Compute the expected number of packets associated to the transfer */
+  if (pdev->host.hc[hc_num].xfer_len > 0)
+  {
+    num_packets = (pdev->host.hc[hc_num].xfer_len + \
+      pdev->host.hc[hc_num].max_packet - 1) / pdev->host.hc[hc_num].max_packet;
+    
+    if (num_packets > max_hc_pkt_count)
+    {
+      num_packets = max_hc_pkt_count;
+      pdev->host.hc[hc_num].xfer_len = num_packets * \
+        pdev->host.hc[hc_num].max_packet;
+    }
+  }
+  else
+  {
+    num_packets = 1;
+  }
+  if (pdev->host.hc[hc_num].ep_is_in)
+  {
+    pdev->host.hc[hc_num].xfer_len = num_packets * \
+      pdev->host.hc[hc_num].max_packet;
+  }
+  /* Initialize the HCTSIZn register */
+  hctsiz.b.xfersize = pdev->host.hc[hc_num].xfer_len;
+  hctsiz.b.pktcnt = num_packets;
+  hctsiz.b.pid = pdev->host.hc[hc_num].data_pid;
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCTSIZ, hctsiz.d32);
+  
+  if (pdev->cfg.dma_enable == 1)
+  {
+    USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCDMA, (unsigned int)pdev->host.hc[hc_num].xfer_buff);
+  }
+  
+  
+  hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR);
+  hcchar.b.oddfrm = USB_OTG_IsEvenFrame(pdev);
+  
+  /* Set host channel enable */
+  hcchar.b.chen = 1;
+  hcchar.b.chdis = 0;
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
+  
+  if (pdev->cfg.dma_enable == 0) /* Slave mode */
+  {  
+    if((pdev->host.hc[hc_num].ep_is_in == 0) && 
+       (pdev->host.hc[hc_num].xfer_len > 0))
+    {
+      switch(pdev->host.hc[hc_num].ep_type) 
+      {
+        /* Non periodic transfer */
+      case EP_TYPE_CTRL:
+      case EP_TYPE_BULK:
+        
+        hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
+        len_words = (pdev->host.hc[hc_num].xfer_len + 3) / 4;
+        
+        /* check if there is enough space in FIFO space */
+        if(len_words > hnptxsts.b.nptxfspcavail)
+        {
+          /* need to process data in nptxfempty interrupt */
+          intmsk.b.nptxfempty = 1;
+          USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, intmsk.d32);  
+        }
+        
+        break;
+        /* Periodic transfer */
+      case EP_TYPE_INTR:
+      case EP_TYPE_ISOC:
+        hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
+        len_words = (pdev->host.hc[hc_num].xfer_len + 3) / 4;
+        /* check if there is enough space in FIFO space */
+        if(len_words > hptxsts.b.ptxfspcavail) /* split the transfer */
+        {
+          /* need to process data in ptxfempty interrupt */
+          intmsk.b.ptxfempty = 1;
+          USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, intmsk.d32);  
+        }
+        break;
+        
+      default:
+        break;
+      }
+      
+      /* Write packet into the Tx FIFO. */
+      USB_OTG_WritePacket(pdev, 
+                          pdev->host.hc[hc_num].xfer_buff , 
+                          hc_num, pdev->host.hc[hc_num].xfer_len);
+    }
+  }
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_HC_Halt : Halt channel
+* @param  pdev : Selected device
+* @param  hc_num : channel number
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_HC_Halt(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_HNPTXSTS_TypeDef            nptxsts;
+  USB_OTG_HPTXSTS_TypeDef             hptxsts;
+  USB_OTG_HCCHAR_TypeDef              hcchar;
+  
+  nptxsts.d32 = 0;
+  hptxsts.d32 = 0;
+  hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR);
+  hcchar.b.chen = 1;
+  hcchar.b.chdis = 1;
+  
+  /* Check for space in the request queue to issue the halt. */
+  if (hcchar.b.eptype == HCCHAR_CTRL || hcchar.b.eptype == HCCHAR_BULK)
+  {
+    nptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
+    if (nptxsts.b.nptxqspcavail == 0)
+    {
+      hcchar.b.chen = 0;
+    }
+  }
+  else
+  {
+    hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
+    if (hptxsts.b.ptxqspcavail == 0)
+    {
+      hcchar.b.chen = 0;
+    }
+  }
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
+  return status;
+}
+
+/**
+* @brief  Issue a ping token
+* @param  None
+* @retval : None
+*/
+USB_OTG_STS USB_OTG_HC_DoPing(USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num)
+{
+  USB_OTG_STS               status = USB_OTG_OK;
+  USB_OTG_HCCHAR_TypeDef    hcchar;
+  USB_OTG_HCTSIZn_TypeDef   hctsiz;  
+  
+  hctsiz.d32 = 0;
+  hctsiz.b.dopng = 1;
+  hctsiz.b.pktcnt = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCTSIZ, hctsiz.d32);
+  
+  hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR);
+  hcchar.b.chen = 1;
+  hcchar.b.chdis = 0;
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[hc_num]->HCCHAR, hcchar.d32);
+  return status;  
+}
+
+/**
+* @brief  Stop the device and clean up fifo's
+* @param  None
+* @retval : None
+*/
+void USB_OTG_StopHost(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_HCCHAR_TypeDef  hcchar;
+  uint32_t                i;
+  
+  USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HAINTMSK , 0);
+  USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HAINT,      0xFFFFFFFF);
+  /* Flush out any leftover queued requests. */
+  
+  for (i = 0; i < pdev->cfg.host_channels; i++)
+  {
+    hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[i]->HCCHAR);
+    hcchar.b.chen = 0;
+    hcchar.b.chdis = 1;
+    hcchar.b.epdir = 0;
+    USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[i]->HCCHAR, hcchar.d32);
+  }
+  
+  /* Flush the FIFO */
+  USB_OTG_FlushRxFifo(pdev);
+  USB_OTG_FlushTxFifo(pdev ,  0x10 );  
+}
+#endif
+#ifdef USE_DEVICE_MODE
+/*         PCD Core Layer       */
+
+/**
+* @brief  USB_OTG_InitDevSpeed :Initializes the DevSpd field of DCFG register 
+*         depending the PHY type and the enumeration speed of the device.
+* @param  pdev : Selected device
+* @retval : None
+*/
+void USB_OTG_InitDevSpeed(USB_OTG_CORE_HANDLE *pdev , uint8_t speed)
+{
+  USB_OTG_DCFG_TypeDef   dcfg;
+  
+  dcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCFG);
+  dcfg.b.devspd = speed;
+  USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCFG, dcfg.d32);
+}
+
+
+/**
+* @brief  USB_OTG_CoreInitDev : Initializes the USB_OTG controller registers 
+*         for device mode
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_CoreInitDev (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS             status       = USB_OTG_OK;
+  USB_OTG_DEPCTL_TypeDef  depctl;
+  uint32_t i;
+  USB_OTG_DCFG_TypeDef    dcfg;
+  USB_OTG_FSIZ_TypeDef    nptxfifosize;
+  USB_OTG_FSIZ_TypeDef    txfifosize;
+  USB_OTG_DIEPMSK_TypeDef msk;
+  USB_OTG_DTHRCTL_TypeDef dthrctl;  
+  
+  depctl.d32 = 0;
+  dcfg.d32 = 0;
+  nptxfifosize.d32 = 0;
+  txfifosize.d32 = 0;
+  msk.d32 = 0;
+  
+  /* Restart the Phy Clock */
+  USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, 0);
+  /* Device configuration register */
+  dcfg.d32 = USB_OTG_READ_REG32( &pdev->regs.DREGS->DCFG);
+  dcfg.b.perfrint = DCFG_FRAME_INTERVAL_80;
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DCFG, dcfg.d32 );
+  
+#ifdef USB_OTG_FS_CORE
+  if(pdev->cfg.coreID == USB_OTG_FS_CORE_ID  )
+  {  
+    
+    /* Set Full speed phy */
+    USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_FULL);
+    
+    /* set Rx FIFO size */
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_FS_SIZE);
+    
+    /* EP0 TX*/
+    nptxfifosize.b.depth     = TX0_FIFO_FS_SIZE;
+    nptxfifosize.b.startaddr = RX_FIFO_FS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32 );
+    
+    
+    /* EP1 TX*/
+    txfifosize.b.startaddr = nptxfifosize.b.startaddr + nptxfifosize.b.depth;
+    txfifosize.b.depth = TX1_FIFO_FS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[0], txfifosize.d32 );
+    
+    
+    /* EP2 TX*/
+    txfifosize.b.startaddr += txfifosize.b.depth;
+    txfifosize.b.depth = TX2_FIFO_FS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[1], txfifosize.d32 );
+    
+    
+    /* EP3 TX*/  
+    txfifosize.b.startaddr += txfifosize.b.depth;
+    txfifosize.b.depth = TX3_FIFO_FS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[2], txfifosize.d32 );
+  }
+#endif
+#ifdef USB_OTG_HS_CORE
+  if(pdev->cfg.coreID == USB_OTG_HS_CORE_ID  )
+  {
+    
+    /* Set High speed phy */
+    
+    if(pdev->cfg.phy_itface  == USB_OTG_ULPI_PHY)
+    {
+      USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH);
+    }
+    else /* set High speed phy in Full speed mode */
+    {
+      USB_OTG_InitDevSpeed (pdev , USB_OTG_SPEED_PARAM_HIGH_IN_FULL);
+    }
+    
+    /* set Rx FIFO size */
+    USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GRXFSIZ, RX_FIFO_HS_SIZE);
+    
+    /* EP0 TX*/
+    nptxfifosize.b.depth     = TX0_FIFO_HS_SIZE;
+    nptxfifosize.b.startaddr = RX_FIFO_HS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF0_HNPTXFSIZ, nptxfifosize.d32 );
+    
+    
+    /* EP1 TX*/
+    txfifosize.b.startaddr = nptxfifosize.b.startaddr + nptxfifosize.b.depth;
+    txfifosize.b.depth = TX1_FIFO_HS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[0], txfifosize.d32 );
+    
+    
+    /* EP2 TX*/
+    txfifosize.b.startaddr += txfifosize.b.depth;
+    txfifosize.b.depth = TX2_FIFO_HS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[1], txfifosize.d32 );
+    
+    
+    /* EP3 TX*/  
+    txfifosize.b.startaddr += txfifosize.b.depth;
+    txfifosize.b.depth = TX3_FIFO_HS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[2], txfifosize.d32 );
+    
+    /* EP4 TX*/
+    txfifosize.b.startaddr += txfifosize.b.depth;
+    txfifosize.b.depth = TX4_FIFO_HS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[3], txfifosize.d32 );
+    
+    
+    /* EP5 TX*/  
+    txfifosize.b.startaddr += txfifosize.b.depth;
+    txfifosize.b.depth = TX5_FIFO_HS_SIZE;
+    USB_OTG_WRITE_REG32( &pdev->regs.GREGS->DIEPTXF[4], txfifosize.d32 );
+  }
+#endif  
+  /* Flush the FIFOs */
+  USB_OTG_FlushTxFifo(pdev , 0x10); /* all Tx FIFOs */
+  USB_OTG_FlushRxFifo(pdev);
+  /* Clear all pending Device Interrupts */
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, 0 );
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, 0 );
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF );
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, 0 );
+  
+  for (i = 0; i < pdev->cfg.dev_endpoints; i++)
+  {
+    depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[i]->DIEPCTL);
+    if (depctl.b.epena)
+    {
+      depctl.d32 = 0;
+      depctl.b.epdis = 1;
+      depctl.b.snak = 1;
+    }
+    else
+    {
+      depctl.d32 = 0;
+    }
+    USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPCTL, depctl.d32);
+    USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPTSIZ, 0);
+    USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF);
+  }
+  for (i = 0; i <  pdev->cfg.dev_endpoints; i++)
+  {
+    USB_OTG_DEPCTL_TypeDef  depctl;
+    depctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[i]->DOEPCTL);
+    if (depctl.b.epena)
+    {
+      depctl.d32 = 0;
+      depctl.b.epdis = 1;
+      depctl.b.snak = 1;
+    }
+    else
+    {
+      depctl.d32 = 0;
+    }
+    USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPCTL, depctl.d32);
+    USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPTSIZ, 0);
+    USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF);
+  }
+  msk.d32 = 0;
+  msk.b.txfifoundrn = 1;
+  USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPMSK, msk.d32, msk.d32);
+  
+  if (pdev->cfg.dma_enable == 1)
+  {
+    dthrctl.d32 = 0;
+    dthrctl.b.non_iso_thr_en = 1;
+    dthrctl.b.iso_thr_en = 1;
+    dthrctl.b.tx_thr_len = 64;
+    dthrctl.b.rx_thr_en = 1;
+    dthrctl.b.rx_thr_len = 64;
+    USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DTHRCTL, dthrctl.d32);  
+  }
+  USB_OTG_EnableDevInt(pdev);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_EnableDevInt : Enables the Device mode interrupts
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EnableDevInt(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_GINTMSK_TypeDef  intmsk;
+  
+  intmsk.d32 = 0;
+  
+  /* Disable all interrupts. */
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTMSK, 0);
+  /* Clear any pending interrupts */
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, 0xBFFFFFFF);
+  /* Enable the common interrupts */
+  USB_OTG_EnableCommonInt(pdev);
+  
+  if (pdev->cfg.dma_enable == 0)
+  {
+    intmsk.b.rxstsqlvl = 1;
+  }
+  
+  /* Enable interrupts matching to the Device mode ONLY */
+  intmsk.b.usbsuspend = 1;
+  intmsk.b.usbreset   = 1;
+  intmsk.b.enumdone   = 1;
+  intmsk.b.inepintr   = 1;
+  intmsk.b.outepintr  = 1;
+  intmsk.b.sofintr    = 1; 
+  
+  intmsk.b.incomplisoin    = 1; 
+  intmsk.b.incomplisoout    = 1;   
+#ifdef VBUS_SENSING_ENABLED
+  intmsk.b.sessreqintr    = 1; 
+  intmsk.b.otgintr    = 1;    
+#endif  
+  USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, intmsk.d32);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_GetDeviceSpeed
+*         Get the device speed from the device status register
+* @param  None
+* @retval status
+*/
+enum USB_OTG_SPEED USB_OTG_GetDeviceSpeed (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_DSTS_TypeDef  dsts;
+  enum USB_OTG_SPEED speed = USB_SPEED_UNKNOWN;
+  
+  
+  dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
+  
+  switch (dsts.b.enumspd)
+  {
+  case DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ:
+    speed = USB_SPEED_HIGH;
+    break;
+  case DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ:
+  case DSTS_ENUMSPD_FS_PHY_48MHZ:
+    speed = USB_SPEED_FULL;
+    break;
+    
+  case DSTS_ENUMSPD_LS_PHY_6MHZ:
+    speed = USB_SPEED_LOW;
+    break;
+  }
+  
+  return speed;
+}
+/**
+* @brief  enables EP0 OUT to receive SETUP packets and configures EP0
+*   for transmitting packets
+* @param  None
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS  USB_OTG_EP0Activate(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_STS             status = USB_OTG_OK;
+  USB_OTG_DSTS_TypeDef    dsts;
+  USB_OTG_DEPCTL_TypeDef  diepctl;
+  USB_OTG_DCTL_TypeDef    dctl;
+  
+  dctl.d32 = 0;
+  /* Read the Device Status and Endpoint 0 Control registers */
+  dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
+  diepctl.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[0]->DIEPCTL);
+  /* Set the MPS of the IN EP based on the enumeration speed */
+  switch (dsts.b.enumspd)
+  {
+  case DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ:
+  case DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ:
+  case DSTS_ENUMSPD_FS_PHY_48MHZ:
+    diepctl.b.mps = DEP0CTL_MPS_64;
+    break;
+  case DSTS_ENUMSPD_LS_PHY_6MHZ:
+    diepctl.b.mps = DEP0CTL_MPS_8;
+    break;
+  }
+  USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[0]->DIEPCTL, diepctl.d32);
+  dctl.b.cgnpinnak = 1;
+  USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, dctl.d32);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_EPActivate : Activates an EP
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EPActivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_DEPCTL_TypeDef  depctl;
+  USB_OTG_DAINT_TypeDef  daintmsk;
+  __IO uint32_t *addr;
+  
+  
+  depctl.d32 = 0;
+  daintmsk.d32 = 0;
+  /* Read DEPCTLn register */
+  if (ep->is_in == 1)
+  {
+    addr = &pdev->regs.INEP_REGS[ep->num]->DIEPCTL;
+    daintmsk.ep.in = 1 << ep->num;
+  }
+  else
+  {
+    addr = &pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL;
+    daintmsk.ep.out = 1 << ep->num;
+  }
+  /* If the EP is already active don't change the EP Control
+  * register. */
+  depctl.d32 = USB_OTG_READ_REG32(addr);
+  if (!depctl.b.usbactep)
+  {
+    depctl.b.mps    = ep->maxpacket;
+    depctl.b.eptype = ep->type;
+    depctl.b.txfnum = ep->tx_fifo_num;
+    depctl.b.setd0pid = 1;
+    depctl.b.usbactep = 1;
+    USB_OTG_WRITE_REG32(addr, depctl.d32);
+  }
+  /* Enable the Interrupt for this EP */
+#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
+  if((ep->num == 1)&&(pdev->cfg.coreID == USB_OTG_HS_CORE_ID))
+  {
+    USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DEACHMSK, 0, daintmsk.d32);
+  }
+  else
+#endif   
+    USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DAINTMSK, 0, daintmsk.d32);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_EPDeactivate : Deactivates an EP
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EPDeactivate(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_DEPCTL_TypeDef  depctl;
+  USB_OTG_DAINT_TypeDef  daintmsk;
+  __IO uint32_t *addr;
+  
+  depctl.d32 = 0;
+  daintmsk.d32 = 0;  
+  /* Read DEPCTLn register */
+  if (ep->is_in == 1)
+  {
+    addr = &pdev->regs.INEP_REGS[ep->num]->DIEPCTL;
+    daintmsk.ep.in = 1 << ep->num;
+  }
+  else
+  {
+    addr = &pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL;
+    daintmsk.ep.out = 1 << ep->num;
+  }
+  depctl.b.usbactep = 0;
+  USB_OTG_WRITE_REG32(addr, depctl.d32);
+  /* Disable the Interrupt for this EP */
+  
+#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED
+  if((ep->num == 1)&&(pdev->cfg.coreID == USB_OTG_HS_CORE_ID))
+  {
+    USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DEACHMSK, daintmsk.d32, 0);
+  }
+  else
+#endif    
+    USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DAINTMSK, daintmsk.d32, 0);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_EPStartXfer : Handle the setup for data xfer for an EP and 
+*         starts the xfer
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EPStartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_DEPCTL_TypeDef     depctl;
+  USB_OTG_DEPXFRSIZ_TypeDef  deptsiz;
+  USB_OTG_DSTS_TypeDef       dsts;    
+  uint32_t fifoemptymsk = 0;  
+  
+  depctl.d32 = 0;
+  deptsiz.d32 = 0;
+  /* IN endpoint */
+  if (ep->is_in == 1)
+  {
+    depctl.d32  = USB_OTG_READ_REG32(&(pdev->regs.INEP_REGS[ep->num]->DIEPCTL));
+    deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.INEP_REGS[ep->num]->DIEPTSIZ));
+    /* Zero Length Packet? */
+    if (ep->xfer_len == 0)
+    {
+      deptsiz.b.xfersize = 0;
+      deptsiz.b.pktcnt = 1;
+    }
+    else
+    {
+      /* Program the transfer size and packet count
+      * as follows: xfersize = N * maxpacket +
+      * short_packet pktcnt = N + (short_packet
+      * exist ? 1 : 0)
+      */
+      deptsiz.b.xfersize = ep->xfer_len;
+      deptsiz.b.pktcnt = (ep->xfer_len - 1 + ep->maxpacket) / ep->maxpacket;
+      
+      if (ep->type == EP_TYPE_ISOC)
+      {
+        deptsiz.b.mc = 1;
+      }       
+    }
+    USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPTSIZ, deptsiz.d32);
+    
+    if (pdev->cfg.dma_enable == 1)
+    {
+      USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPDMA, ep->dma_addr);
+    }
+    else
+    {
+      if (ep->type != EP_TYPE_ISOC)
+      {
+        /* Enable the Tx FIFO Empty Interrupt for this EP */
+        if (ep->xfer_len > 0)
+        {
+          fifoemptymsk = 1 << ep->num;
+          USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, 0, fifoemptymsk);
+        }
+      }
+    }
+    
+    
+    if (ep->type == EP_TYPE_ISOC)
+    {
+      dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
+      
+      if (((dsts.b.soffn)&0x1) == 0)
+      {
+        depctl.b.setd1pid = 1;
+      }
+      else
+      {
+        depctl.b.setd0pid = 1;
+      }
+    } 
+    
+    /* EP enable, IN data in FIFO */
+    depctl.b.cnak = 1;
+    depctl.b.epena = 1;
+    USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPCTL, depctl.d32);
+    
+    if (ep->type == EP_TYPE_ISOC)
+    {
+      USB_OTG_WritePacket(pdev, ep->xfer_buff, ep->num, ep->xfer_len);   
+    }    
+  }
+  else
+  {
+    /* OUT endpoint */
+    depctl.d32  = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL));
+    deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ));
+    /* Program the transfer size and packet count as follows:
+    * pktcnt = N
+    * xfersize = N * maxpacket
+    */
+    if (ep->xfer_len == 0)
+    {
+      deptsiz.b.xfersize = ep->maxpacket;
+      deptsiz.b.pktcnt = 1;
+    }
+    else
+    {
+      deptsiz.b.pktcnt = (ep->xfer_len + (ep->maxpacket - 1)) / ep->maxpacket;
+      deptsiz.b.xfersize = deptsiz.b.pktcnt * ep->maxpacket;
+    }
+    USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ, deptsiz.d32);
+    
+    if (pdev->cfg.dma_enable == 1)
+    {
+      USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPDMA, ep->dma_addr);
+    }
+    
+    if (ep->type == EP_TYPE_ISOC)
+    {
+      if (ep->even_odd_frame)
+      {
+        depctl.b.setd1pid = 1;
+      }
+      else
+      {
+        depctl.b.setd0pid = 1;
+      }
+    }
+    /* EP enable */
+    depctl.b.cnak = 1;
+    depctl.b.epena = 1;
+    USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL, depctl.d32);
+  }
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_EP0StartXfer : Handle the setup for a data xfer for EP0 and 
+*         starts the xfer
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EP0StartXfer(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
+{
+  USB_OTG_STS                 status = USB_OTG_OK;
+  USB_OTG_DEPCTL_TypeDef      depctl;
+  USB_OTG_DEP0XFRSIZ_TypeDef  deptsiz;
+  USB_OTG_INEPREGS          *in_regs;
+  uint32_t fifoemptymsk = 0;
+  
+  depctl.d32   = 0;
+  deptsiz.d32  = 0;
+  /* IN endpoint */
+  if (ep->is_in == 1)
+  {
+    in_regs = pdev->regs.INEP_REGS[0];
+    depctl.d32  = USB_OTG_READ_REG32(&in_regs->DIEPCTL);
+    deptsiz.d32 = USB_OTG_READ_REG32(&in_regs->DIEPTSIZ);
+    /* Zero Length Packet? */
+    if (ep->xfer_len == 0)
+    {
+      deptsiz.b.xfersize = 0;
+      deptsiz.b.pktcnt = 1;
+      
+    }
+    else
+    {
+      if (ep->xfer_len > ep->maxpacket)
+      {
+        ep->xfer_len = ep->maxpacket;
+        deptsiz.b.xfersize = ep->maxpacket;
+      }
+      else
+      {
+        deptsiz.b.xfersize = ep->xfer_len;
+      }
+      deptsiz.b.pktcnt = 1;
+    }
+    USB_OTG_WRITE_REG32(&in_regs->DIEPTSIZ, deptsiz.d32);
+    
+    if (pdev->cfg.dma_enable == 1)
+    {
+      USB_OTG_WRITE_REG32(&pdev->regs.INEP_REGS[ep->num]->DIEPDMA, ep->dma_addr);  
+    }
+    
+    /* EP enable, IN data in FIFO */
+    depctl.b.cnak = 1;
+    depctl.b.epena = 1;
+    USB_OTG_WRITE_REG32(&in_regs->DIEPCTL, depctl.d32);
+    
+    
+    
+    if (pdev->cfg.dma_enable == 0)
+    {
+      /* Enable the Tx FIFO Empty Interrupt for this EP */
+      if (ep->xfer_len > 0)
+      {
+        {
+          fifoemptymsk |= 1 << ep->num;
+          USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, 0, fifoemptymsk);
+        }
+      }
+    }
+  }
+  else
+  {
+    /* OUT endpoint */
+    depctl.d32  = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL);
+    deptsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ);
+    /* Program the transfer size and packet count as follows:
+    * xfersize = N * (maxpacket + 4 - (maxpacket % 4))
+    * pktcnt = N           */
+    if (ep->xfer_len == 0)
+    {
+      deptsiz.b.xfersize = ep->maxpacket;
+      deptsiz.b.pktcnt = 1;
+    }
+    else
+    {
+      ep->xfer_len = ep->maxpacket;
+      deptsiz.b.xfersize = ep->maxpacket;
+      deptsiz.b.pktcnt = 1;
+    }
+    USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPTSIZ, deptsiz.d32);
+    if (pdev->cfg.dma_enable == 1)
+    {
+      USB_OTG_WRITE_REG32(&pdev->regs.OUTEP_REGS[ep->num]->DOEPDMA, ep->dma_addr);
+    }
+    /* EP enable */
+    depctl.b.cnak = 1;
+    depctl.b.epena = 1;
+    USB_OTG_WRITE_REG32 (&(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL), depctl.d32);
+    
+  }
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_EPSetStall : Set the EP STALL
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EPSetStall(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_DEPCTL_TypeDef  depctl;
+  __IO uint32_t *depctl_addr;
+  
+  depctl.d32 = 0;
+  if (ep->is_in == 1)
+  {
+    depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL);
+    depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
+    /* set the disable and stall bits */
+    if (depctl.b.epena)
+    {
+      depctl.b.epdis = 1;
+    }
+    depctl.b.stall = 1;
+    USB_OTG_WRITE_REG32(depctl_addr, depctl.d32);
+  }
+  else
+  {
+    depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL);
+    depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
+    /* set the stall bit */
+    depctl.b.stall = 1;
+    USB_OTG_WRITE_REG32(depctl_addr, depctl.d32);
+  }
+  return status;
+}
+
+
+/**
+* @brief  Clear the EP STALL
+* @param  pdev : Selected device
+* @retval USB_OTG_STS : status
+*/
+USB_OTG_STS USB_OTG_EPClearStall(USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep)
+{
+  USB_OTG_STS status = USB_OTG_OK;
+  USB_OTG_DEPCTL_TypeDef  depctl;
+  __IO uint32_t *depctl_addr;
+  
+  depctl.d32 = 0;
+  
+  if (ep->is_in == 1)
+  {
+    depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL);
+  }
+  else
+  {
+    depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL);
+  }
+  depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
+  /* clear the stall bits */
+  depctl.b.stall = 0;
+  if (ep->type == EP_TYPE_INTR || ep->type == EP_TYPE_BULK)
+  {
+    depctl.b.setd0pid = 1; /* DATA0 */
+  }
+  USB_OTG_WRITE_REG32(depctl_addr, depctl.d32);
+  return status;
+}
+
+
+/**
+* @brief  USB_OTG_ReadDevAllOutEp_itr : returns OUT endpoint interrupt bits
+* @param  pdev : Selected device
+* @retval OUT endpoint interrupt bits
+*/
+uint32_t USB_OTG_ReadDevAllOutEp_itr(USB_OTG_CORE_HANDLE *pdev)
+{
+  uint32_t v;
+  v  = USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINT);
+  v &= USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINTMSK);
+  return ((v & 0xffff0000) >> 16);
+}
+
+
+/**
+* @brief  USB_OTG_ReadDevOutEP_itr : returns Device OUT EP Interrupt register
+* @param  pdev : Selected device
+* @param  ep : end point number
+* @retval Device OUT EP Interrupt register
+*/
+uint32_t USB_OTG_ReadDevOutEP_itr(USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
+{
+  uint32_t v;
+  v  = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[epnum]->DOEPINT);
+  v &= USB_OTG_READ_REG32(&pdev->regs.DREGS->DOEPMSK);
+  return v;
+}
+
+
+/**
+* @brief  USB_OTG_ReadDevAllInEPItr : Get int status register
+* @param  pdev : Selected device
+* @retval int status register
+*/
+uint32_t USB_OTG_ReadDevAllInEPItr(USB_OTG_CORE_HANDLE *pdev)
+{
+  uint32_t v;
+  v = USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINT);
+  v &= USB_OTG_READ_REG32(&pdev->regs.DREGS->DAINTMSK);
+  return (v & 0xffff);
+}
+
+/**
+* @brief  configures EPO to receive SETUP packets
+* @param  None
+* @retval : None
+*/
+void USB_OTG_EP0_OutStart(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_DEP0XFRSIZ_TypeDef  doeptsize0;
+  doeptsize0.d32 = 0;
+  doeptsize0.b.supcnt = 3;
+  doeptsize0.b.pktcnt = 1;
+  doeptsize0.b.xfersize = 8 * 3;
+  USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[0]->DOEPTSIZ, doeptsize0.d32 );
+  
+  if (pdev->cfg.dma_enable == 1)
+  {
+    USB_OTG_DEPCTL_TypeDef  doepctl;
+    doepctl.d32 = 0;
+    USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[0]->DOEPDMA, 
+                        (uint32_t)&pdev->dev.setup_packet);
+    
+    /* EP enable */
+    doepctl.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[0]->DOEPCTL);
+    doepctl.b.epena = 1;
+    doepctl.d32 = 0x80008000;
+    USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[0]->DOEPCTL, doepctl.d32);
+  }
+}
+
+/**
+* @brief  USB_OTG_RemoteWakeup : active remote wakeup signalling
+* @param  None
+* @retval : None
+*/
+void USB_OTG_ActiveRemoteWakeup(USB_OTG_CORE_HANDLE *pdev)
+{
+  
+  USB_OTG_DCTL_TypeDef     dctl;
+  USB_OTG_DSTS_TypeDef     dsts;
+  USB_OTG_PCGCCTL_TypeDef  power;  
+  
+  if (pdev->dev.DevRemoteWakeup) 
+  {
+    dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
+    if(dsts.b.suspsts == 1)
+    {
+      if(pdev->cfg.low_power)
+      {
+        /* un-gate USB Core clock */
+        power.d32 = USB_OTG_READ_REG32(&pdev->regs.PCGCCTL);
+        power.b.gatehclk = 0;
+        power.b.stoppclk = 0;
+        USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32);
+      }   
+      /* active Remote wakeup signaling */
+      dctl.d32 = 0;
+      dctl.b.rmtwkupsig = 1;
+      USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, 0, dctl.d32);
+      USB_OTG_BSP_mDelay(5);
+      USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, 0 );
+    }
+  }
+}
+
+
+/**
+* @brief  USB_OTG_UngateClock : active USB Core clock
+* @param  None
+* @retval : None
+*/
+void USB_OTG_UngateClock(USB_OTG_CORE_HANDLE *pdev)
+{
+  if(pdev->cfg.low_power)
+  {
+    
+    USB_OTG_DSTS_TypeDef     dsts;
+    USB_OTG_PCGCCTL_TypeDef  power; 
+    
+    dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
+    
+    if(dsts.b.suspsts == 1)
+    {
+      /* un-gate USB Core clock */
+      power.d32 = USB_OTG_READ_REG32(&pdev->regs.PCGCCTL);
+      power.b.gatehclk = 0;
+      power.b.stoppclk = 0;
+      USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32);
+      
+    }
+  }
+}
+
+/**
+* @brief  Stop the device and clean up fifo's
+* @param  None
+* @retval : None
+*/
+void USB_OTG_StopDevice(USB_OTG_CORE_HANDLE *pdev)
+{
+  uint32_t i;
+  
+  pdev->dev.device_status = 1;
+  
+  for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
+  {
+    USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF);
+    USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF);
+  }
+  
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, 0 );
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, 0 );
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, 0 );
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF );  
+  
+  /* Flush the FIFO */
+  USB_OTG_FlushRxFifo(pdev);
+  USB_OTG_FlushTxFifo(pdev ,  0x10 );  
+}
+
+/**
+* @brief  returns the EP Status
+* @param  pdev : Selected device
+*         ep : endpoint structure
+* @retval : EP status
+*/
+
+uint32_t USB_OTG_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,USB_OTG_EP *ep)
+{
+  USB_OTG_DEPCTL_TypeDef  depctl;
+  __IO uint32_t *depctl_addr;
+  uint32_t Status = 0;  
+  
+  depctl.d32 = 0;
+  if (ep->is_in == 1)
+  {
+    depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL);
+    depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
+    
+    if (depctl.b.stall == 1)  
+      Status = USB_OTG_EP_TX_STALL;
+    else if (depctl.b.naksts == 1)
+      Status = USB_OTG_EP_TX_NAK;
+    else 
+      Status = USB_OTG_EP_TX_VALID;     
+    
+  }
+  else
+  {
+    depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL);
+    depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
+    if (depctl.b.stall == 1)  
+      Status = USB_OTG_EP_RX_STALL;
+    else if (depctl.b.naksts == 1)
+      Status = USB_OTG_EP_RX_NAK;
+    else 
+      Status = USB_OTG_EP_RX_VALID; 
+  } 
+  
+  /* Return the current status */
+  return Status;
+}
+
+/**
+* @brief  Set the EP Status
+* @param  pdev : Selected device
+*         Status : new Status
+*         ep : EP structure
+* @retval : None
+*/
+void USB_OTG_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , USB_OTG_EP *ep , uint32_t Status)
+{
+  USB_OTG_DEPCTL_TypeDef  depctl;
+  __IO uint32_t *depctl_addr;
+  
+  depctl.d32 = 0;
+  
+  /* Process for IN endpoint */
+  if (ep->is_in == 1)
+  {
+    depctl_addr = &(pdev->regs.INEP_REGS[ep->num]->DIEPCTL);
+    depctl.d32 = USB_OTG_READ_REG32(depctl_addr);
+    
+    if (Status == USB_OTG_EP_TX_STALL)  
+    {
+      USB_OTG_EPSetStall(pdev, ep); return;
+    }
+    else if (Status == USB_OTG_EP_TX_NAK)
+      depctl.b.snak = 1;
+    else if (Status == USB_OTG_EP_TX_VALID)
+    {
+      if (depctl.b.stall == 1)
+      {  
+        ep->even_odd_frame = 0;
+        USB_OTG_EPClearStall(pdev, ep);
+        return;
+      }      
+      depctl.b.cnak = 1;
+      depctl.b.usbactep = 1; 
+      depctl.b.epena = 1;
+    }
+    else if (Status == USB_OTG_EP_TX_DIS)
+      depctl.b.usbactep = 0;
+  } 
+  else /* Process for OUT endpoint */
+  {
+    depctl_addr = &(pdev->regs.OUTEP_REGS[ep->num]->DOEPCTL);
+    depctl.d32 = USB_OTG_READ_REG32(depctl_addr);    
+    
+    if (Status == USB_OTG_EP_RX_STALL)  {
+      depctl.b.stall = 1;
+    }
+    else if (Status == USB_OTG_EP_RX_NAK)
+      depctl.b.snak = 1;
+    else if (Status == USB_OTG_EP_RX_VALID)
+    {
+      if (depctl.b.stall == 1)
+      {  
+        ep->even_odd_frame = 0;
+        USB_OTG_EPClearStall(pdev, ep);
+        return;
+      }  
+      depctl.b.cnak = 1;
+      depctl.b.usbactep = 1;    
+      depctl.b.epena = 1;
+    }
+    else if (Status == USB_OTG_EP_RX_DIS)
+    {
+      depctl.b.usbactep = 0;    
+    }
+  }
+  
+  USB_OTG_WRITE_REG32(depctl_addr, depctl.d32); 
+}
+
+#endif
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_dcd.c b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_dcd.c
new file mode 100644
index 0000000000000000000000000000000000000000..eac8c337126c05fa42c7fed08170cbcbbfffce76
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_dcd.c
@@ -0,0 +1,478 @@
+/**
+  ******************************************************************************
+  * @file    usb_dcd.c
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Peripheral Device Interface Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_dcd.h"
+#include "usb_bsp.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+* @{
+*/
+
+/** @defgroup USB_DCD 
+* @brief This file is the interface between EFSL ans Host mass-storage class
+* @{
+*/
+
+
+/** @defgroup USB_DCD_Private_Defines
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_Private_TypesDefinitions
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+
+/** @defgroup USB_DCD_Private_Macros
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_Private_Variables
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_Private_FunctionPrototypes
+* @{
+*/ 
+
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_Private_Functions
+* @{
+*/ 
+
+
+
+void DCD_Init(USB_OTG_CORE_HANDLE *pdev , 
+              USB_OTG_CORE_ID_TypeDef coreID)
+{
+  uint32_t i;
+  USB_OTG_EP *ep;
+  
+  USB_OTG_SelectCore (pdev , coreID);
+  
+  pdev->dev.device_status = USB_OTG_DEFAULT;
+  pdev->dev.device_address = 0;
+  
+  /* Init ep structure */
+  for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
+  {
+    ep = &pdev->dev.in_ep[i];
+    /* Init ep structure */
+    ep->is_in = 1;
+    ep->num = i;
+    ep->tx_fifo_num = i;
+    /* Control until ep is actvated */
+    ep->type = EP_TYPE_CTRL;
+    ep->maxpacket =  USB_OTG_MAX_EP0_SIZE;
+    ep->xfer_buff = 0;
+    ep->xfer_len = 0;
+  }
+  
+  for (i = 0; i < pdev->cfg.dev_endpoints; i++)
+  {
+    ep = &pdev->dev.out_ep[i];
+    /* Init ep structure */
+    ep->is_in = 0;
+    ep->num = i;
+    ep->tx_fifo_num = i;
+    /* Control until ep is activated */
+    ep->type = EP_TYPE_CTRL;
+    ep->maxpacket = USB_OTG_MAX_EP0_SIZE;
+    ep->xfer_buff = 0;
+    ep->xfer_len = 0;
+  }
+  
+  USB_OTG_DisableGlobalInt(pdev);
+  
+  /*Init the Core (common init.) */
+  USB_OTG_CoreInit(pdev);
+
+
+  /* Force Device Mode*/
+  USB_OTG_SetCurrentMode(pdev, DEVICE_MODE);
+  
+  /* Init Device */
+  USB_OTG_CoreInitDev(pdev);
+  
+  
+  /* Enable USB Global interrupt */
+  USB_OTG_EnableGlobalInt(pdev);
+}
+
+
+/**
+* @brief  Configure an EP
+* @param pdev : Device instance
+* @param epdesc : Endpoint Descriptor
+* @retval : status
+*/
+uint32_t DCD_EP_Open(USB_OTG_CORE_HANDLE *pdev , 
+                     uint8_t ep_addr,
+                     uint16_t ep_mps,
+                     uint8_t ep_type)
+{
+  USB_OTG_EP *ep;
+  
+  if ((ep_addr & 0x80) == 0x80)
+  {
+    ep = &pdev->dev.in_ep[ep_addr & 0x7F];
+  }
+  else
+  {
+    ep = &pdev->dev.out_ep[ep_addr & 0x7F];
+  }
+  ep->num   = ep_addr & 0x7F;
+  
+  ep->is_in = (0x80 & ep_addr) != 0;
+  ep->maxpacket = ep_mps;
+  ep->type = ep_type;
+  if (ep->is_in)
+  {
+    /* Assign a Tx FIFO */
+    ep->tx_fifo_num = ep->num;
+  }
+  /* Set initial data PID. */
+  if (ep_type == USB_OTG_EP_BULK )
+  {
+    ep->data_pid_start = 0;
+  }
+  USB_OTG_EPActivate(pdev , ep );
+  return 0;
+}
+/**
+* @brief  called when an EP is disabled
+* @param pdev: device instance
+* @param ep_addr: endpoint address
+* @retval : status
+*/
+uint32_t DCD_EP_Close(USB_OTG_CORE_HANDLE *pdev , uint8_t  ep_addr)
+{
+  USB_OTG_EP *ep;
+  
+  if ((ep_addr&0x80) == 0x80)
+  {
+    ep = &pdev->dev.in_ep[ep_addr & 0x7F];
+  }
+  else
+  {
+    ep = &pdev->dev.out_ep[ep_addr & 0x7F];
+  }
+  ep->num   = ep_addr & 0x7F;
+  ep->is_in = (0x80 & ep_addr) != 0;
+  USB_OTG_EPDeactivate(pdev , ep );
+  return 0;
+}
+
+
+/**
+* @brief  DCD_EP_PrepareRx
+* @param pdev: device instance
+* @param ep_addr: endpoint address
+* @param pbuf: pointer to Rx buffer
+* @param buf_len: data length
+* @retval : status
+*/
+uint32_t   DCD_EP_PrepareRx( USB_OTG_CORE_HANDLE *pdev,
+                            uint8_t   ep_addr,
+                            uint8_t *pbuf,                        
+                            uint16_t  buf_len)
+{
+  USB_OTG_EP *ep;
+  
+  ep = &pdev->dev.out_ep[ep_addr & 0x7F];
+  
+  /*setup and start the Xfer */
+  ep->xfer_buff = pbuf;  
+  ep->xfer_len = buf_len;
+  ep->xfer_count = 0;
+  ep->is_in = 0;
+  ep->num = ep_addr & 0x7F;
+  
+  if (pdev->cfg.dma_enable == 1)
+  {
+    ep->dma_addr = (uint32_t)pbuf;  
+  }
+  
+  if ( ep->num == 0 )
+  {
+    USB_OTG_EP0StartXfer(pdev , ep);
+  }
+  else
+  {
+    USB_OTG_EPStartXfer(pdev, ep );
+  }
+  return 0;
+}
+
+/**
+* @brief  Transmit data over USB
+* @param pdev: device instance
+* @param ep_addr: endpoint address
+* @param pbuf: pointer to Tx buffer
+* @param buf_len: data length
+* @retval : status
+*/
+uint32_t  DCD_EP_Tx ( USB_OTG_CORE_HANDLE *pdev,
+                     uint8_t   ep_addr,
+                     uint8_t   *pbuf,
+                     uint32_t   buf_len)
+{
+  USB_OTG_EP *ep;
+  
+  ep = &pdev->dev.in_ep[ep_addr & 0x7F];
+  
+  /* Setup and start the Transfer */
+  ep->is_in = 1;
+  ep->num = ep_addr & 0x7F;  
+  ep->xfer_buff = pbuf;
+  ep->dma_addr = (uint32_t)pbuf;  
+  ep->xfer_count = 0;
+  ep->xfer_len  = buf_len;
+  
+  if ( ep->num == 0 )
+  {
+    USB_OTG_EP0StartXfer(pdev , ep);
+  }
+  else
+  {
+    USB_OTG_EPStartXfer(pdev, ep );
+  }
+  return 0;
+}
+
+
+/**
+* @brief  Stall an endpoint.
+* @param pdev: device instance
+* @param epnum: endpoint address
+* @retval : status
+*/
+uint32_t  DCD_EP_Stall (USB_OTG_CORE_HANDLE *pdev, uint8_t   epnum)
+{
+  USB_OTG_EP *ep;
+  if ((0x80 & epnum) == 0x80)
+  {
+    ep = &pdev->dev.in_ep[epnum & 0x7F];
+  }
+  else
+  {
+    ep = &pdev->dev.out_ep[epnum];
+  }
+
+  ep->is_stall = 1;
+  ep->num   = epnum & 0x7F;
+  ep->is_in = ((epnum & 0x80) == 0x80);
+  
+  USB_OTG_EPSetStall(pdev , ep);
+  return (0);
+}
+
+
+/**
+* @brief  Clear stall condition on endpoints.
+* @param pdev: device instance
+* @param epnum: endpoint address
+* @retval : status
+*/
+uint32_t  DCD_EP_ClrStall (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
+{
+  USB_OTG_EP *ep;
+  if ((0x80 & epnum) == 0x80)
+  {
+    ep = &pdev->dev.in_ep[epnum & 0x7F];    
+  }
+  else
+  {
+    ep = &pdev->dev.out_ep[epnum];
+  }
+  
+  ep->is_stall = 0;  
+  ep->num   = epnum & 0x7F;
+  ep->is_in = ((epnum & 0x80) == 0x80);
+  
+  USB_OTG_EPClearStall(pdev , ep);
+  return (0);
+}
+
+
+/**
+* @brief  This Function flushes the FIFOs.
+* @param pdev: device instance
+* @param epnum: endpoint address
+* @retval : status
+*/
+uint32_t  DCD_EP_Flush (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum)
+{
+
+  if ((epnum & 0x80) == 0x80)
+  {
+    USB_OTG_FlushTxFifo(pdev, epnum & 0x7F);
+  }
+  else
+  {
+    USB_OTG_FlushRxFifo(pdev);
+  }
+
+  return (0);
+}
+
+
+/**
+* @brief  This Function set USB device address
+* @param pdev: device instance
+* @param address: new device address
+* @retval : status
+*/
+void  DCD_EP_SetAddress (USB_OTG_CORE_HANDLE *pdev, uint8_t address)
+{
+  USB_OTG_DCFG_TypeDef  dcfg;
+  dcfg.d32 = 0;
+  dcfg.b.devaddr = address;
+  USB_OTG_MODIFY_REG32( &pdev->regs.DREGS->DCFG, 0, dcfg.d32);
+}
+
+/**
+* @brief  Connect device (enable internal pull-up)
+* @param pdev: device instance
+* @retval : None
+*/
+void  DCD_DevConnect (USB_OTG_CORE_HANDLE *pdev)
+{
+#ifndef USE_OTG_MODE
+  USB_OTG_DCTL_TypeDef  dctl;
+  dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
+  /* Connect device */
+  dctl.b.sftdiscon  = 0;
+  USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
+  USB_OTG_BSP_mDelay(3);
+#endif
+}
+
+
+/**
+* @brief  Disconnect device (disable internal pull-up)
+* @param pdev: device instance
+* @retval : None
+*/
+void  DCD_DevDisconnect (USB_OTG_CORE_HANDLE *pdev)
+{
+#ifndef USE_OTG_MODE
+  USB_OTG_DCTL_TypeDef  dctl;
+  dctl.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DCTL);
+  /* Disconnect device for 3ms */
+  dctl.b.sftdiscon  = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.DREGS->DCTL, dctl.d32);
+  USB_OTG_BSP_mDelay(3);
+#endif
+}
+
+
+/**
+* @brief  returns the EP Status
+* @param  pdev : Selected device
+*         epnum : endpoint address
+* @retval : EP status
+*/
+
+uint32_t DCD_GetEPStatus(USB_OTG_CORE_HANDLE *pdev ,uint8_t epnum)
+{
+  USB_OTG_EP *ep;
+  uint32_t Status = 0;  
+  
+  if ((0x80 & epnum) == 0x80)
+  {
+    ep = &pdev->dev.in_ep[epnum & 0x7F];    
+  }
+  else
+  {
+    ep = &pdev->dev.out_ep[epnum];
+  }
+  
+  Status = USB_OTG_GetEPStatus(pdev ,ep);
+
+  /* Return the current status */
+  return Status;
+}
+
+/**
+* @brief  Set the EP Status
+* @param  pdev : Selected device
+*         Status : new Status
+*         epnum : EP address
+* @retval : None
+*/
+void DCD_SetEPStatus (USB_OTG_CORE_HANDLE *pdev , uint8_t epnum , uint32_t Status)
+{
+  USB_OTG_EP *ep;
+  
+  if ((0x80 & epnum) == 0x80)
+  {
+    ep = &pdev->dev.in_ep[epnum & 0x7F];    
+  }
+  else
+  {
+    ep = &pdev->dev.out_ep[epnum];
+  }
+  
+   USB_OTG_SetEPStatus(pdev ,ep , Status);
+}
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_dcd_int.c b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_dcd_int.c
new file mode 100644
index 0000000000000000000000000000000000000000..c6bd80b41cdb6983b1ec43fe65ac2a492699f1b0
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_dcd_int.c
@@ -0,0 +1,877 @@
+/**
+  ******************************************************************************
+  * @file    usb_dcd_int.c
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Peripheral Device interrupt subroutines
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_dcd_int.h"
+/** @addtogroup USB_OTG_DRIVER
+* @{
+*/
+
+/** @defgroup USB_DCD_INT 
+* @brief This file contains the interrupt subroutines for the Device mode.
+* @{
+*/
+
+
+/** @defgroup USB_DCD_INT_Private_Defines
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_INT_Private_TypesDefinitions
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+
+/** @defgroup USB_DCD_INT_Private_Macros
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_INT_Private_Variables
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_INT_Private_FunctionPrototypes
+* @{
+*/ 
+/* static functions */
+static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum);
+
+/* Interrupt Handlers */
+static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev);
+
+static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev , uint32_t epnum);
+
+static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev);
+
+static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev);
+#ifdef VBUS_SENSING_ENABLED
+static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev);
+#endif
+
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_DCD_INT_Private_Functions
+* @{
+*/ 
+
+
+#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED  
+/**
+* @brief  USBD_OTG_EP1OUT_ISR_Handler
+*         handles all USB Interrupts
+* @param  pdev: device instance
+* @retval status
+*/
+uint32_t USBD_OTG_EP1OUT_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
+{
+  
+  USB_OTG_DOEPINTn_TypeDef  doepint;
+  USB_OTG_DEPXFRSIZ_TypeDef  deptsiz;  
+  
+  doepint.d32 = USB_OTG_READ_REG32(&pdev->regs.OUTEP_REGS[1]->DOEPINT);
+  doepint.d32&= USB_OTG_READ_REG32(&pdev->regs.DREGS->DOUTEP1MSK);
+  
+  /* Transfer complete */
+  if ( doepint.b.xfercompl )
+  {
+    /* Clear the bit in DOEPINTn for this interrupt */
+    CLEAR_OUT_EP_INTR(1, xfercompl);
+    if (pdev->cfg.dma_enable == 1)
+    {
+      deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[1]->DOEPTSIZ));
+      /*ToDo : handle more than one single MPS size packet */
+      pdev->dev.out_ep[1].xfer_count = pdev->dev.out_ep[1].maxpacket - \
+        deptsiz.b.xfersize;
+    }    
+    /* Inform upper layer: data ready */
+    /* RX COMPLETE */
+    USBD_DCD_INT_fops->DataOutStage(pdev , 1);
+    
+  }
+  
+  /* Endpoint disable  */
+  if ( doepint.b.epdisabled )
+  {
+    /* Clear the bit in DOEPINTn for this interrupt */
+    CLEAR_OUT_EP_INTR(1, epdisabled);
+  }
+
+  return 1;
+}
+
+/**
+* @brief  USBD_OTG_EP1IN_ISR_Handler
+*         handles all USB Interrupts
+* @param  pdev: device instance
+* @retval status
+*/
+uint32_t USBD_OTG_EP1IN_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
+{
+  
+  USB_OTG_DIEPINTn_TypeDef  diepint;
+  uint32_t fifoemptymsk, msk, emp;
+  
+  msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DINEP1MSK);
+  emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
+  msk |= ((emp >> 1 ) & 0x1) << 7;
+  diepint.d32  = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[1]->DIEPINT) & msk;  
+  
+  if ( diepint.b.xfercompl )
+  {
+    fifoemptymsk = 0x1 << 1;
+    USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
+    CLEAR_IN_EP_INTR(1, xfercompl);
+    /* TX COMPLETE */
+    USBD_DCD_INT_fops->DataInStage(pdev , 1);
+  }
+  if ( diepint.b.epdisabled )
+  {
+    CLEAR_IN_EP_INTR(1, epdisabled);
+  }  
+  if ( diepint.b.timeout )
+  {
+    CLEAR_IN_EP_INTR(1, timeout);
+  }
+  if (diepint.b.intktxfemp)
+  {
+    CLEAR_IN_EP_INTR(1, intktxfemp);
+  }
+  if (diepint.b.inepnakeff)
+  {
+    CLEAR_IN_EP_INTR(1, inepnakeff);
+  }
+  if (diepint.b.emptyintr)
+  {
+    DCD_WriteEmptyTxFifo(pdev , 1);
+    CLEAR_IN_EP_INTR(1, emptyintr);
+  }
+  return 1;
+}
+#endif
+
+/**
+* @brief  STM32_USBF_OTG_ISR_Handler
+*         handles all USB Interrupts
+* @param  pdev: device instance
+* @retval status
+*/
+
+void  __attribute__((used)) OTG_FS_IRQHandler(void)
+{
+  extern USB_OTG_CORE_HANDLE USB_OTG_dev;
+
+  USBD_OTG_ISR_Handler (&USB_OTG_dev);
+}
+
+uint32_t USBD_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintr_status;
+  uint32_t retval = 0;
+  
+  if (USB_OTG_IsDeviceMode(pdev)) /* ensure that we are in device mode */
+  {
+    gintr_status.d32 = USB_OTG_ReadCoreItr(pdev);
+    if (!gintr_status.d32) /* avoid spurious interrupt */
+    {
+      return 0;
+    }
+    
+    if (gintr_status.b.outepintr)
+    {
+      retval |= DCD_HandleOutEP_ISR(pdev);
+    }    
+    
+    if (gintr_status.b.inepint)
+    {
+      retval |= DCD_HandleInEP_ISR(pdev);
+    }
+    
+    if (gintr_status.b.modemismatch)
+    {
+      USB_OTG_GINTSTS_TypeDef  gintsts;
+      
+      /* Clear interrupt */
+      gintsts.d32 = 0;
+      gintsts.b.modemismatch = 1;
+      USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+    }
+    
+    if (gintr_status.b.wkupintr)
+    {
+      retval |= DCD_HandleResume_ISR(pdev);
+    }
+    
+    if (gintr_status.b.usbsuspend)
+    {
+      retval |= DCD_HandleUSBSuspend_ISR(pdev);
+    }
+    if (gintr_status.b.sofintr)
+    {
+      retval |= DCD_HandleSof_ISR(pdev);
+      
+    }
+    
+    if (gintr_status.b.rxstsqlvl)
+    {
+      retval |= DCD_HandleRxStatusQueueLevel_ISR(pdev);
+      
+    }
+    
+    if (gintr_status.b.usbreset)
+    {
+      retval |= DCD_HandleUsbReset_ISR(pdev);
+      
+    }
+    if (gintr_status.b.enumdone)
+    {
+      retval |= DCD_HandleEnumDone_ISR(pdev);
+    }
+    
+    if (gintr_status.b.incomplisoin)
+    {
+      retval |= DCD_IsoINIncomplete_ISR(pdev);
+    }
+
+    if (gintr_status.b.incomplisoout)
+    {
+      retval |= DCD_IsoOUTIncomplete_ISR(pdev);
+    }    
+#ifdef VBUS_SENSING_ENABLED
+    if (gintr_status.b.sessreqintr)
+    {
+      retval |= DCD_SessionRequest_ISR(pdev);
+    }
+
+    if (gintr_status.b.otgintr)
+    {
+      retval |= DCD_OTG_ISR(pdev);
+    }   
+#endif    
+  }
+  return retval;
+}
+
+#ifdef VBUS_SENSING_ENABLED
+/**
+* @brief  DCD_SessionRequest_ISR
+*         Indicates that the USB_OTG controller has detected a connection
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_SessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintsts;  
+  USBD_DCD_INT_fops->DevConnected (pdev);
+
+  /* Clear interrupt */
+  gintsts.d32 = 0;
+  gintsts.b.sessreqintr = 1;
+  USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);   
+  return 1;
+}
+
+/**
+* @brief  DCD_OTG_ISR
+*         Indicates that the USB_OTG controller has detected an OTG event:
+*                 used to detect the end of session i.e. disconnection
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_OTG_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+
+  USB_OTG_GOTGINT_TypeDef  gotgint;
+
+  gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT);
+  
+  if (gotgint.b.sesenddet)
+  {
+    USBD_DCD_INT_fops->DevDisconnected (pdev);
+  }
+  /* Clear OTG interrupt */
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32); 
+  return 1;
+}
+#endif
+/**
+* @brief  DCD_HandleResume_ISR
+*         Indicates that the USB_OTG controller has detected a resume or
+*                 remote Wake-up sequence
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleResume_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  USB_OTG_DCTL_TypeDef     devctl;
+  USB_OTG_PCGCCTL_TypeDef  power;
+  
+  if(pdev->cfg.low_power)
+  {
+    /* un-gate USB Core clock */
+    power.d32 = USB_OTG_READ_REG32(&pdev->regs.PCGCCTL);
+    power.b.gatehclk = 0;
+    power.b.stoppclk = 0;
+    USB_OTG_WRITE_REG32(pdev->regs.PCGCCTL, power.d32);
+  }
+  
+  /* Clear the Remote Wake-up Signaling */
+  devctl.d32 = 0;
+  devctl.b.rmtwkupsig = 1;
+  USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, devctl.d32, 0);
+  
+  /* Inform upper layer by the Resume Event */
+  USBD_DCD_INT_fops->Resume (pdev);
+  
+  /* Clear interrupt */
+  gintsts.d32 = 0;
+  gintsts.b.wkupintr = 1;
+  USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  return 1;
+}
+
+/**
+* @brief  USB_OTG_HandleUSBSuspend_ISR
+*         Indicates that SUSPEND state has been detected on the USB
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleUSBSuspend_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  USB_OTG_PCGCCTL_TypeDef  power;
+  USB_OTG_DSTS_TypeDef     dsts;
+  __IO uint8_t prev_status = 0;
+  
+  prev_status = pdev->dev.device_status;
+  USBD_DCD_INT_fops->Suspend (pdev);      
+  
+  dsts.d32 = USB_OTG_READ_REG32(&pdev->regs.DREGS->DSTS);
+    
+  /* Clear interrupt */
+  gintsts.d32 = 0;
+  gintsts.b.usbsuspend = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  
+  if((pdev->cfg.low_power) && (dsts.b.suspsts == 1)  && 
+    (pdev->dev.connection_status == 1) && 
+    (prev_status  == USB_OTG_CONFIGURED))
+  {
+	/*  switch-off the clocks */
+    power.d32 = 0;
+    power.b.stoppclk = 1;
+    USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);  
+    
+    power.b.gatehclk = 1;
+    USB_OTG_MODIFY_REG32(pdev->regs.PCGCCTL, 0, power.d32);
+    
+    /* Request to enter Sleep mode after exit from current ISR */
+    SCB->SCR |= (SCB_SCR_SLEEPDEEP_Msk | SCB_SCR_SLEEPONEXIT_Msk);
+  }
+  return 1;
+}
+
+/**
+* @brief  DCD_HandleInEP_ISR
+*         Indicates that an IN EP has a pending Interrupt
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleInEP_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_DIEPINTn_TypeDef  diepint;
+  
+  uint32_t ep_intr;
+  uint32_t epnum = 0;
+  uint32_t fifoemptymsk;
+  diepint.d32 = 0;
+  ep_intr = USB_OTG_ReadDevAllInEPItr(pdev);
+  
+  while ( ep_intr )
+  {
+    if (ep_intr&0x1) /* In ITR */
+    {
+      diepint.d32 = DCD_ReadDevInEP(pdev , epnum); /* Get In ITR status */
+      if ( diepint.b.xfercompl )
+      {
+        fifoemptymsk = 0x1 << epnum;
+        USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DIEPEMPMSK, fifoemptymsk, 0);
+        CLEAR_IN_EP_INTR(epnum, xfercompl);
+        /* TX COMPLETE */
+        USBD_DCD_INT_fops->DataInStage(pdev , epnum);
+        
+        if (pdev->cfg.dma_enable == 1)
+        {
+          if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_IN))
+          {
+            /* prepare to rx more setup packets */
+            USB_OTG_EP0_OutStart(pdev);
+          }
+        }           
+      }
+      if ( diepint.b.timeout )
+      {
+        CLEAR_IN_EP_INTR(epnum, timeout);
+      }
+      if (diepint.b.intktxfemp)
+      {
+        CLEAR_IN_EP_INTR(epnum, intktxfemp);
+      }
+      if (diepint.b.inepnakeff)
+      {
+        CLEAR_IN_EP_INTR(epnum, inepnakeff);
+      }
+      if ( diepint.b.epdisabled )
+      {
+        CLEAR_IN_EP_INTR(epnum, epdisabled);
+      }       
+      if (diepint.b.emptyintr)
+      {
+        
+        DCD_WriteEmptyTxFifo(pdev , epnum);
+        
+        CLEAR_IN_EP_INTR(epnum, emptyintr);
+      }
+    }
+    epnum++;
+    ep_intr >>= 1;
+  }
+  
+  return 1;
+}
+
+/**
+* @brief  DCD_HandleOutEP_ISR
+*         Indicates that an OUT EP has a pending Interrupt
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleOutEP_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  uint32_t ep_intr;
+  USB_OTG_DOEPINTn_TypeDef  doepint;
+  USB_OTG_DEPXFRSIZ_TypeDef  deptsiz;
+  uint32_t epnum = 0;
+  
+  doepint.d32 = 0;
+  
+  /* Read in the device interrupt bits */
+  ep_intr = USB_OTG_ReadDevAllOutEp_itr(pdev);
+  
+  while ( ep_intr )
+  {
+    if (ep_intr&0x1)
+    {
+      
+      doepint.d32 = USB_OTG_ReadDevOutEP_itr(pdev, epnum);
+      
+      /* Transfer complete */
+      if ( doepint.b.xfercompl )
+      {
+        /* Clear the bit in DOEPINTn for this interrupt */
+        CLEAR_OUT_EP_INTR(epnum, xfercompl);
+        if (pdev->cfg.dma_enable == 1)
+        {
+          deptsiz.d32 = USB_OTG_READ_REG32(&(pdev->regs.OUTEP_REGS[epnum]->DOEPTSIZ));
+          /*ToDo : handle more than one single MPS size packet */
+          pdev->dev.out_ep[epnum].xfer_count = pdev->dev.out_ep[epnum].maxpacket - \
+            deptsiz.b.xfersize;
+        }
+        /* Inform upper layer: data ready */
+        /* RX COMPLETE */
+        USBD_DCD_INT_fops->DataOutStage(pdev , epnum);
+        
+        if (pdev->cfg.dma_enable == 1)
+        {
+          if((epnum == 0) && (pdev->dev.device_state == USB_OTG_EP0_STATUS_OUT))
+          {
+            /* prepare to rx more setup packets */
+            USB_OTG_EP0_OutStart(pdev);
+          }
+        }        
+      }
+      /* Endpoint disable  */
+      if ( doepint.b.epdisabled )
+      {
+        /* Clear the bit in DOEPINTn for this interrupt */
+        CLEAR_OUT_EP_INTR(epnum, epdisabled);
+      }
+      /* Setup Phase Done (control EPs) */
+      if ( doepint.b.setup )
+      {
+        
+        /* inform the upper layer that a setup packet is available */
+        /* SETUP COMPLETE */
+        USBD_DCD_INT_fops->SetupStage(pdev);
+        CLEAR_OUT_EP_INTR(epnum, setup);
+      }
+    }
+    epnum++;
+    ep_intr >>= 1;
+  }
+  return 1;
+}
+
+/**
+* @brief  DCD_HandleSof_ISR
+*         Handles the SOF Interrupts
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleSof_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  GINTSTS;
+  
+  
+  USBD_DCD_INT_fops->SOF(pdev);
+  
+  /* Clear interrupt */
+  GINTSTS.d32 = 0;
+  GINTSTS.b.sofintr = 1;
+  USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, GINTSTS.d32);
+  
+  return 1;
+}
+
+/**
+* @brief  DCD_HandleRxStatusQueueLevel_ISR
+*         Handles the Rx Status Queue Level Interrupt
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleRxStatusQueueLevel_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTMSK_TypeDef  int_mask;
+  USB_OTG_DRXSTS_TypeDef   status;
+  USB_OTG_EP *ep;
+  
+  /* Disable the Rx Status Queue Level interrupt */
+  int_mask.d32 = 0;
+  int_mask.b.rxstsqlvl = 1;
+  USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, int_mask.d32, 0);
+  
+  /* Get the Status from the top of the FIFO */
+  status.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GRXSTSP );
+  
+  ep = &pdev->dev.out_ep[status.b.epnum];
+  
+  switch (status.b.pktsts)
+  {
+  case STS_GOUT_NAK:
+    break;
+  case STS_DATA_UPDT:
+    if (status.b.bcnt)
+    {
+      USB_OTG_ReadPacket(pdev,ep->xfer_buff, status.b.bcnt);
+      ep->xfer_buff += status.b.bcnt;
+      ep->xfer_count += status.b.bcnt;
+    }
+    break;
+  case STS_XFER_COMP:
+    break;
+  case STS_SETUP_COMP:
+    break;
+  case STS_SETUP_UPDT:
+    /* Copy the setup packet received in FIFO into the setup buffer in RAM */
+    USB_OTG_ReadPacket(pdev , pdev->dev.setup_packet, 8);
+    ep->xfer_count += status.b.bcnt;
+    break;
+  default:
+    break;
+  }
+  
+  /* Enable the Rx Status Queue Level interrupt */
+  USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, 0, int_mask.d32);
+  
+  return 1;
+}
+
+/**
+* @brief  DCD_WriteEmptyTxFifo
+*         check FIFO for the next packet to be loaded
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_WriteEmptyTxFifo(USB_OTG_CORE_HANDLE *pdev, uint32_t epnum)
+{
+  USB_OTG_DTXFSTSn_TypeDef  txstatus;
+  USB_OTG_EP *ep;
+  uint32_t len = 0;
+  uint32_t len32b;
+  txstatus.d32 = 0;
+  
+  ep = &pdev->dev.in_ep[epnum];    
+  
+  len = ep->xfer_len - ep->xfer_count;
+  
+  if (len > ep->maxpacket)
+  {
+    len = ep->maxpacket;
+  }
+  
+  len32b = (len + 3) / 4;
+  txstatus.d32 = USB_OTG_READ_REG32( &pdev->regs.INEP_REGS[epnum]->DTXFSTS);
+  
+  
+  
+  while  (txstatus.b.txfspcavail > len32b &&
+          ep->xfer_count < ep->xfer_len &&
+            ep->xfer_len != 0)
+  {
+    /* Write the FIFO */
+    len = ep->xfer_len - ep->xfer_count;
+    
+    if (len > ep->maxpacket)
+    {
+      len = ep->maxpacket;
+    }
+    len32b = (len + 3) / 4;
+    
+    USB_OTG_WritePacket (pdev , ep->xfer_buff, epnum, len);
+    
+    ep->xfer_buff  += len;
+    ep->xfer_count += len;
+    
+    txstatus.d32 = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DTXFSTS);
+  }
+  
+  return 1;
+}
+
+/**
+* @brief  DCD_HandleUsbReset_ISR
+*         This interrupt occurs when a USB Reset is detected
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleUsbReset_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_DAINT_TypeDef    daintmsk;
+  USB_OTG_DOEPMSK_TypeDef  doepmsk;
+  USB_OTG_DIEPMSK_TypeDef  diepmsk;
+  USB_OTG_DCFG_TypeDef     dcfg;
+  USB_OTG_DCTL_TypeDef     dctl;
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  uint32_t i;
+  
+  dctl.d32 = 0;
+  daintmsk.d32 = 0;
+  doepmsk.d32 = 0;
+  diepmsk.d32 = 0;
+  dcfg.d32 = 0;
+  gintsts.d32 = 0;
+  
+  /* Clear the Remote Wake-up Signaling */
+  dctl.b.rmtwkupsig = 1;
+  USB_OTG_MODIFY_REG32(&pdev->regs.DREGS->DCTL, dctl.d32, 0 );
+  
+  /* Flush the Tx FIFO */
+  USB_OTG_FlushTxFifo(pdev ,  0 );
+  
+  for (i = 0; i < pdev->cfg.dev_endpoints ; i++)
+  {
+    USB_OTG_WRITE_REG32( &pdev->regs.INEP_REGS[i]->DIEPINT, 0xFF);
+    USB_OTG_WRITE_REG32( &pdev->regs.OUTEP_REGS[i]->DOEPINT, 0xFF);
+  }
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINT, 0xFFFFFFFF );
+  
+  daintmsk.ep.in = 1;
+  daintmsk.ep.out = 1;
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DAINTMSK, daintmsk.d32 );
+  
+  doepmsk.b.setup = 1;
+  doepmsk.b.xfercompl = 1;
+  doepmsk.b.epdisabled = 1;
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOEPMSK, doepmsk.d32 );
+#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED   
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DOUTEP1MSK, doepmsk.d32 );
+#endif
+  diepmsk.b.xfercompl = 1;
+  diepmsk.b.timeout = 1;
+  diepmsk.b.epdisabled = 1;
+
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DIEPMSK, diepmsk.d32 );
+#ifdef USB_OTG_HS_DEDICATED_EP1_ENABLED  
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DINEP1MSK, diepmsk.d32 );
+#endif
+  /* Reset Device Address */
+  dcfg.d32 = USB_OTG_READ_REG32( &pdev->regs.DREGS->DCFG);
+  dcfg.b.devaddr = 0;
+  USB_OTG_WRITE_REG32( &pdev->regs.DREGS->DCFG, dcfg.d32);
+  
+  
+  /* setup EP0 to receive SETUP packets */
+  USB_OTG_EP0_OutStart(pdev);
+  
+  /* Clear interrupt */
+  gintsts.d32 = 0;
+  gintsts.b.usbreset = 1;
+  USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  
+  /*Reset internal state machine */
+  USBD_DCD_INT_fops->Reset(pdev);
+  return 1;
+}
+
+/**
+* @brief  DCD_HandleEnumDone_ISR
+*         Read the device status register and set the device speed
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_HandleEnumDone_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  USB_OTG_GUSBCFG_TypeDef  gusbcfg;
+  
+  USB_OTG_EP0Activate(pdev);
+  
+  /* Set USB turn-around time based on device speed and PHY interface. */
+  gusbcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GUSBCFG);
+  
+  /* Full or High speed */
+  if ( USB_OTG_GetDeviceSpeed(pdev) == USB_SPEED_HIGH)
+  {
+    pdev->cfg.speed            = USB_OTG_SPEED_HIGH;
+    pdev->cfg.mps              = USB_OTG_HS_MAX_PACKET_SIZE ;    
+    gusbcfg.b.usbtrdtim = 9;
+  }
+  else
+  {
+    pdev->cfg.speed            = USB_OTG_SPEED_FULL;
+    pdev->cfg.mps              = USB_OTG_FS_MAX_PACKET_SIZE ;  
+    gusbcfg.b.usbtrdtim = 5;
+  }
+  
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GUSBCFG, gusbcfg.d32);
+  
+  /* Clear interrupt */
+  gintsts.d32 = 0;
+  gintsts.b.enumdone = 1;
+  USB_OTG_WRITE_REG32( &pdev->regs.GREGS->GINTSTS, gintsts.d32 );
+  return 1;
+}
+
+
+/**
+* @brief  DCD_IsoINIncomplete_ISR
+*         handle the ISO IN incomplete interrupt
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_IsoINIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef gintsts;  
+  
+  gintsts.d32 = 0;
+
+  USBD_DCD_INT_fops->IsoINIncomplete (pdev); 
+  
+  /* Clear interrupt */
+  gintsts.b.incomplisoin = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  
+  return 1;
+}
+
+/**
+* @brief  DCD_IsoOUTIncomplete_ISR
+*         handle the ISO OUT incomplete interrupt
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_IsoOUTIncomplete_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef gintsts;  
+  
+  gintsts.d32 = 0;
+
+  USBD_DCD_INT_fops->IsoOUTIncomplete (pdev); 
+  
+  /* Clear interrupt */
+  gintsts.b.incomplisoout = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  return 1;
+}
+/**
+* @brief  DCD_ReadDevInEP
+*         Reads ep flags
+* @param  pdev: device instance
+* @retval status
+*/
+static uint32_t DCD_ReadDevInEP (USB_OTG_CORE_HANDLE *pdev, uint8_t epnum)
+{
+  uint32_t v, msk, emp;
+  msk = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPMSK);
+  emp = USB_OTG_READ_REG32(&pdev->regs.DREGS->DIEPEMPMSK);
+  msk |= ((emp >> epnum) & 0x1) << 7;
+  v = USB_OTG_READ_REG32(&pdev->regs.INEP_REGS[epnum]->DIEPINT) & msk;
+  return v;
+}
+
+
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_hcd.c b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_hcd.c
new file mode 100644
index 0000000000000000000000000000000000000000..56e2244181a65bdd35d6e50007adc0d977f86cbe
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_hcd.c
@@ -0,0 +1,262 @@
+/**
+  ******************************************************************************
+  * @file    usb_hcd.c
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Host Interface Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_core.h"
+#include "usb_hcd.h"
+#include "usb_conf.h"
+#include "usb_bsp.h"
+
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_HCD 
+  * @brief This file is the interface between EFSL ans Host mass-storage class
+  * @{
+  */
+
+
+/** @defgroup USB_HCD_Private_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+ 
+
+/** @defgroup USB_HCD_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USB_HCD_Private_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_HCD_Private_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_HCD_Private_FunctionPrototypes
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_HCD_Private_Functions
+  * @{
+  */ 
+
+/**
+  * @brief  HCD_Init 
+  *         Initialize the HOST portion of the driver.
+  * @param  pdev: Selected device
+  * @param  base_address: OTG base address
+  * @retval Status
+  */
+uint32_t HCD_Init(USB_OTG_CORE_HANDLE *pdev , 
+                  USB_OTG_CORE_ID_TypeDef coreID)
+{
+  uint8_t i = 0;
+  pdev->host.ConnSts = 0;
+  
+  for (i= 0; i< USB_OTG_MAX_TX_FIFOS; i++)
+  {
+  pdev->host.ErrCnt[i]  = 0;
+  pdev->host.XferCnt[i]   = 0;
+  pdev->host.HC_Status[i]   = HC_IDLE;
+  }
+  pdev->host.hc[0].max_packet  = 8; 
+
+  USB_OTG_SelectCore(pdev, coreID);
+#ifndef DUAL_ROLE_MODE_ENABLED
+  USB_OTG_DisableGlobalInt(pdev);
+  USB_OTG_CoreInit(pdev);
+
+  /* Force Host Mode*/
+  USB_OTG_SetCurrentMode(pdev , HOST_MODE);
+  USB_OTG_CoreInitHost(pdev);
+  USB_OTG_EnableGlobalInt(pdev);
+#endif
+   
+  return 0;
+}
+
+
+/**
+  * @brief  HCD_GetCurrentSpeed
+  *         Get Current device Speed.
+  * @param  pdev : Selected device
+  * @retval Status
+  */
+
+uint32_t HCD_GetCurrentSpeed (USB_OTG_CORE_HANDLE *pdev)
+{    
+    USB_OTG_HPRT0_TypeDef  HPRT0;
+    HPRT0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
+    
+    return HPRT0.b.prtspd;
+}
+
+/**
+  * @brief  HCD_ResetPort
+  *         Issues the reset command to device
+  * @param  pdev : Selected device
+  * @retval Status
+  */
+uint32_t HCD_ResetPort(USB_OTG_CORE_HANDLE *pdev)
+{
+  /*
+  Before starting to drive a USB reset, the application waits for the OTG 
+  interrupt triggered by the debounce done bit (DBCDNE bit in OTG_FS_GOTGINT), 
+  which indicates that the bus is stable again after the electrical debounce 
+  caused by the attachment of a pull-up resistor on DP (FS) or DM (LS).
+  */
+  
+  USB_OTG_ResetPort(pdev); 
+  return 0;
+}
+
+/**
+  * @brief  HCD_IsDeviceConnected
+  *         Check if the device is connected.
+  * @param  pdev : Selected device
+  * @retval Device connection status. 1 -> connected and 0 -> disconnected
+  * 
+  */
+uint32_t HCD_IsDeviceConnected(USB_OTG_CORE_HANDLE *pdev)
+{
+  return (pdev->host.ConnSts);
+}
+
+/**
+  * @brief  HCD_GetCurrentFrame 
+  *         This function returns the frame number for sof packet
+  * @param  pdev : Selected device
+  * @retval Frame number
+  * 
+  */
+uint32_t HCD_GetCurrentFrame (USB_OTG_CORE_HANDLE *pdev) 
+{
+ return (USB_OTG_READ_REG32(&pdev->regs.HREGS->HFNUM) & 0xFFFF) ;
+}
+
+/**
+  * @brief  HCD_GetURB_State 
+  *         This function returns the last URBstate
+  * @param  pdev: Selected device
+  * @retval URB_STATE
+  * 
+  */
+URB_STATE HCD_GetURB_State (USB_OTG_CORE_HANDLE *pdev , uint8_t ch_num) 
+{
+  return pdev->host.URB_State[ch_num] ;
+}
+
+/**
+  * @brief  HCD_GetXferCnt 
+  *         This function returns the last URBstate
+  * @param  pdev: Selected device
+  * @retval No. of data bytes transferred
+  * 
+  */
+uint32_t HCD_GetXferCnt (USB_OTG_CORE_HANDLE *pdev, uint8_t ch_num) 
+{
+  return pdev->host.XferCnt[ch_num] ;
+}
+
+
+
+/**
+  * @brief  HCD_GetHCState 
+  *         This function returns the HC Status 
+  * @param  pdev: Selected device
+  * @retval HC_STATUS
+  * 
+  */
+HC_STATUS HCD_GetHCState (USB_OTG_CORE_HANDLE *pdev ,  uint8_t ch_num) 
+{
+  return pdev->host.HC_Status[ch_num] ;
+}
+
+/**
+  * @brief  HCD_HC_Init 
+  *         This function prepare a HC and start a transfer
+  * @param  pdev: Selected device
+  * @param  hc_num: Channel number 
+  * @retval status 
+  */
+uint32_t HCD_HC_Init (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) 
+{
+  return USB_OTG_HC_Init(pdev, hc_num);  
+}
+
+/**
+  * @brief  HCD_SubmitRequest 
+  *         This function prepare a HC and start a transfer
+  * @param  pdev: Selected device
+  * @param  hc_num: Channel number 
+  * @retval status
+  */
+uint32_t HCD_SubmitRequest (USB_OTG_CORE_HANDLE *pdev , uint8_t hc_num) 
+{
+  
+  pdev->host.URB_State[hc_num] =   URB_IDLE;  
+  pdev->host.hc[hc_num].xfer_count = 0 ;
+  return USB_OTG_HC_StartXfer(pdev, hc_num);
+}
+
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_hcd_int.c b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_hcd_int.c
new file mode 100644
index 0000000000000000000000000000000000000000..4fdbe2facba3fe8ea6ea9d55d61ec46d9f38eb21
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_hcd_int.c
@@ -0,0 +1,858 @@
+/**
+  ******************************************************************************
+  * @file    usb_hcd_int.c
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   Host driver interrupt subroutines
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_core.h"
+#include "usb_defines.h"
+#include "usb_hcd_int.h"
+
+#if defined   (__CC_ARM) /*!< ARM Compiler */
+#pragma O0
+#elif defined (__GNUC__) /*!< GNU Compiler */
+#pragma GCC optimize ("O0")
+#elif defined  (__TASKING__) /*!< TASKING Compiler */ 
+#pragma optimize=0                          
+
+#endif /* __CC_ARM */
+
+/** @addtogroup USB_OTG_DRIVER
+* @{
+*/
+
+/** @defgroup USB_HCD_INT 
+* @brief This file contains the interrupt subroutines for the Host mode.
+* @{
+*/
+
+
+/** @defgroup USB_HCD_INT_Private_Defines
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_HCD_INT_Private_TypesDefinitions
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+
+/** @defgroup USB_HCD_INT_Private_Macros
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_HCD_INT_Private_Variables
+* @{
+*/ 
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_HCD_INT_Private_FunctionPrototypes
+* @{
+*/ 
+
+static uint32_t USB_OTG_USBH_handle_sof_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_USBH_handle_port_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev ,
+                                                 uint32_t num);
+static uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , 
+                                                  uint32_t num);
+static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev);
+
+/**
+* @}
+*/ 
+
+
+/** @defgroup USB_HCD_INT_Private_Functions
+* @{
+*/ 
+
+/**
+* @brief  HOST_Handle_ISR 
+*         This function handles all USB Host Interrupts
+* @param  pdev: Selected device
+* @retval status 
+*/
+
+uint32_t USBH_OTG_ISR_Handler (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  uint32_t retval = 0;
+  
+  gintsts.d32 = 0;
+  
+  /* Check if HOST Mode */
+  if (USB_OTG_IsHostMode(pdev))
+  {
+    gintsts.d32 = USB_OTG_ReadCoreItr(pdev);
+    if (!gintsts.d32)
+    {
+      return 0;
+    }
+    
+    if (gintsts.b.sofintr)
+    {
+      retval |= USB_OTG_USBH_handle_sof_ISR (pdev);
+    }
+    
+    if (gintsts.b.rxstsqlvl)
+    {
+      retval |= USB_OTG_USBH_handle_rx_qlvl_ISR (pdev);
+    }
+    
+    if (gintsts.b.nptxfempty)
+    {
+      retval |= USB_OTG_USBH_handle_nptxfempty_ISR (pdev);
+    }
+    
+    if (gintsts.b.ptxfempty)
+    {
+      retval |= USB_OTG_USBH_handle_ptxfempty_ISR (pdev);
+    }    
+    
+    if (gintsts.b.hcintr)
+    {
+      retval |= USB_OTG_USBH_handle_hc_ISR (pdev);
+    }
+    
+    if (gintsts.b.portintr)
+    {
+      retval |= USB_OTG_USBH_handle_port_ISR (pdev);
+    }
+    
+    if (gintsts.b.disconnect)
+    {
+      retval |= USB_OTG_USBH_handle_Disconnect_ISR (pdev);  
+      
+    }
+    
+    if (gintsts.b.incomplisoout)
+    {
+      retval |= USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (pdev);
+    }
+    
+    
+  }
+  return retval;
+}
+
+/**
+* @brief  USB_OTG_USBH_handle_hc_ISR 
+*         This function indicates that one or more host channels has a pending
+* @param  pdev: Selected device
+* @retval status 
+*/
+static uint32_t USB_OTG_USBH_handle_hc_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_HAINT_TypeDef        haint;
+  USB_OTG_HCCHAR_TypeDef       hcchar;
+  uint32_t i = 0;
+  uint32_t retval = 0;
+  
+  /* Clear appropriate bits in HCINTn to clear the interrupt bit in
+  * GINTSTS */
+  
+  haint.d32 = USB_OTG_ReadHostAllChannels_intr(pdev);
+  
+  for (i = 0; i < pdev->cfg.host_channels ; i++)
+  {
+    if (haint.b.chint & (1 << i))
+    {
+      hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[i]->HCCHAR);
+      
+      if (hcchar.b.epdir)
+      {
+        retval |= USB_OTG_USBH_handle_hc_n_In_ISR (pdev, i);
+      }
+      else
+      {
+        retval |=  USB_OTG_USBH_handle_hc_n_Out_ISR (pdev, i);
+      }
+    }
+  }
+  
+  return retval;
+}
+
+/**
+* @brief  USB_OTG_otg_hcd_handle_sof_intr 
+*         Handles the start-of-frame interrupt in host mode.
+* @param  pdev: Selected device
+* @retval status 
+*/
+static uint32_t USB_OTG_USBH_handle_sof_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef      gintsts;
+  gintsts.d32 = 0;
+  
+  USBH_HCD_INT_fops->SOF(pdev);
+  
+  /* Clear interrupt */
+  gintsts.b.sofintr = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  
+  return 1;
+}
+
+/**
+* @brief  USB_OTG_USBH_handle_Disconnect_ISR 
+*         Handles disconnect event.
+* @param  pdev: Selected device
+* @retval status 
+*/
+static uint32_t USB_OTG_USBH_handle_Disconnect_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef      gintsts;
+  
+  gintsts.d32 = 0;
+  
+  USBH_HCD_INT_fops->DevDisconnected(pdev);
+  
+  /* Clear interrupt */
+  gintsts.b.disconnect = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  
+  return 1;
+}
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma optimize = none
+#endif /* __CC_ARM */
+/**
+* @brief  USB_OTG_USBH_handle_nptxfempty_ISR 
+*         Handles non periodic tx fifo empty.
+* @param  pdev: Selected device
+* @retval status 
+*/
+static uint32_t USB_OTG_USBH_handle_nptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTMSK_TypeDef      intmsk;
+  USB_OTG_HNPTXSTS_TypeDef     hnptxsts; 
+  uint16_t                     len_words , len; 
+  
+  hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
+  
+  len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len + 3) / 4;
+  
+  while ((hnptxsts.b.nptxfspcavail > len_words)&&
+         (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len != 0))
+  {
+    
+    len = hnptxsts.b.nptxfspcavail * 4;
+    
+    if (len > pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len)
+    {
+      /* Last packet */
+      len = pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len;
+      
+      intmsk.d32 = 0;
+      intmsk.b.nptxfempty = 1;
+      USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);       
+    }
+    
+    len_words = (pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len + 3) / 4;
+    
+    USB_OTG_WritePacket (pdev , pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff, hnptxsts.b.nptxqtop.chnum, len);
+    
+    pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_buff  += len;
+    pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_len   -= len;
+    pdev->host.hc[hnptxsts.b.nptxqtop.chnum].xfer_count  += len; 
+    
+    hnptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->HNPTXSTS);
+  }  
+  
+  return 1;
+}
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma optimize = none
+#endif /* __CC_ARM */
+/**
+* @brief  USB_OTG_USBH_handle_ptxfempty_ISR 
+*         Handles periodic tx fifo empty
+* @param  pdev: Selected device
+* @retval status 
+*/
+static uint32_t USB_OTG_USBH_handle_ptxfempty_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTMSK_TypeDef      intmsk;
+  USB_OTG_HPTXSTS_TypeDef      hptxsts; 
+  uint16_t                     len_words , len; 
+  
+  hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
+  
+  len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len + 3) / 4;
+  
+  while ((hptxsts.b.ptxfspcavail > len_words)&&
+         (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len != 0))    
+  {
+    
+    len = hptxsts.b.ptxfspcavail * 4;
+    
+    if (len > pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len)
+    {
+      len = pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len;
+      /* Last packet */
+      intmsk.d32 = 0;
+      intmsk.b.ptxfempty = 1;
+      USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0); 
+    }
+    
+    len_words = (pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len + 3) / 4;
+    
+    USB_OTG_WritePacket (pdev , pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff, hptxsts.b.ptxqtop.chnum, len);
+    
+    pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_buff  += len;
+    pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_len   -= len;
+    pdev->host.hc[hptxsts.b.ptxqtop.chnum].xfer_count  += len; 
+    
+    hptxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HPTXSTS);
+  }  
+  
+  return 1;
+}
+
+/**
+* @brief  USB_OTG_USBH_handle_port_ISR 
+*         This function determines which interrupt conditions have occurred
+* @param  pdev: Selected device
+* @retval status 
+*/
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma optimize = none
+#endif /* __CC_ARM */
+static uint32_t USB_OTG_USBH_handle_port_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_HPRT0_TypeDef  hprt0;
+  USB_OTG_HPRT0_TypeDef  hprt0_dup;
+  USB_OTG_HCFG_TypeDef   hcfg;    
+  uint32_t do_reset = 0;
+  uint32_t retval = 0;
+  
+  hcfg.d32 = 0;
+  hprt0.d32 = 0;
+  hprt0_dup.d32 = 0;
+  
+  hprt0.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
+  hprt0_dup.d32 = USB_OTG_READ_REG32(pdev->regs.HPRT0);
+  
+  /* Clear the interrupt bits in GINTSTS */
+  
+  hprt0_dup.b.prtena = 0;
+  hprt0_dup.b.prtconndet = 0;
+  hprt0_dup.b.prtenchng = 0;
+  hprt0_dup.b.prtovrcurrchng = 0;
+  
+  /* Port Connect Detected */
+  if (hprt0.b.prtconndet)
+  {
+
+    hprt0_dup.b.prtconndet = 1;
+    USBH_HCD_INT_fops->DevConnected(pdev);
+    retval |= 1;
+  }
+  
+  /* Port Enable Changed */
+  if (hprt0.b.prtenchng)
+  {
+    hprt0_dup.b.prtenchng = 1;
+    
+    if (hprt0.b.prtena == 1)
+    {
+      
+      USBH_HCD_INT_fops->DevConnected(pdev);
+      
+      if ((hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED) ||
+          (hprt0.b.prtspd == HPRT0_PRTSPD_FULL_SPEED))
+      {
+        
+        hcfg.d32 = USB_OTG_READ_REG32(&pdev->regs.HREGS->HCFG);
+        
+        if (hprt0.b.prtspd == HPRT0_PRTSPD_LOW_SPEED)
+        {
+          USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 6000 );
+          if (hcfg.b.fslspclksel != HCFG_6_MHZ)
+          {
+            if(pdev->cfg.phy_itface  == USB_OTG_EMBEDDED_PHY)
+            {
+              USB_OTG_InitFSLSPClkSel(pdev ,HCFG_6_MHZ );
+            }
+            do_reset = 1;
+          }
+        }
+        else
+        {
+          
+          USB_OTG_WRITE_REG32(&pdev->regs.HREGS->HFIR, 48000 );            
+          if (hcfg.b.fslspclksel != HCFG_48_MHZ)
+          {
+            USB_OTG_InitFSLSPClkSel(pdev ,HCFG_48_MHZ );
+            do_reset = 1;
+          }
+        }
+      }
+      else
+      {
+        do_reset = 1;
+      }
+    }
+  }
+  /* Overcurrent Change Interrupt */
+  if (hprt0.b.prtovrcurrchng)
+  {
+    hprt0_dup.b.prtovrcurrchng = 1;
+    retval |= 1;
+  }
+  if (do_reset)
+  {
+    USB_OTG_ResetPort(pdev);
+  }
+  /* Clear Port Interrupts */
+  USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0_dup.d32);
+  
+  return retval;
+}
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma optimize = none
+#endif /* __CC_ARM */
+/**
+* @brief  USB_OTG_USBH_handle_hc_n_Out_ISR 
+*         Handles interrupt for a specific Host Channel
+* @param  pdev: Selected device
+* @param  hc_num: Channel number
+* @retval status 
+*/
+uint32_t USB_OTG_USBH_handle_hc_n_Out_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num)
+{
+  
+  USB_OTG_HCINTn_TypeDef     hcint;
+  USB_OTG_HCINTMSK_TypeDef  hcintmsk;
+  USB_OTG_HC_REGS *hcreg;
+  USB_OTG_HCCHAR_TypeDef     hcchar; 
+  
+  hcreg = pdev->regs.HC_REGS[num];
+  hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT);
+  hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK);
+  hcint.d32 = hcint.d32 & hcintmsk.d32;
+  
+  hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR);
+  
+  if (hcint.b.ahberr)
+  {
+    CLEAR_HC_INT(hcreg ,ahberr);
+    UNMASK_HOST_INT_CHH (num);
+  } 
+  else if (hcint.b.ack)
+  {
+    CLEAR_HC_INT(hcreg , ack);
+  }
+  else if (hcint.b.frmovrun)
+  {
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg ,frmovrun);
+  }
+  else if (hcint.b.xfercompl)
+  {
+    pdev->host.ErrCnt[num] = 0;
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg , xfercompl);
+    pdev->host.HC_Status[num] = HC_XFRC;            
+  }
+  
+  else if (hcint.b.stall)
+  {
+    CLEAR_HC_INT(hcreg , stall);
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    pdev->host.HC_Status[num] = HC_STALL;      
+  }
+  
+  else if (hcint.b.nak)
+  {
+    pdev->host.ErrCnt[num] = 0;
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg , nak);
+    pdev->host.HC_Status[num] = HC_NAK;      
+  }
+  
+  else if (hcint.b.xacterr)
+  {
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    pdev->host.ErrCnt[num] ++;
+    pdev->host.HC_Status[num] = HC_XACTERR;
+    CLEAR_HC_INT(hcreg , xacterr);
+  }
+  else if (hcint.b.nyet)
+  {
+    pdev->host.ErrCnt[num] = 0;
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg , nyet);
+    pdev->host.HC_Status[num] = HC_NYET;    
+  }
+  else if (hcint.b.datatglerr)
+  {
+    
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg , nak);   
+    pdev->host.HC_Status[num] = HC_DATATGLERR;
+    
+    CLEAR_HC_INT(hcreg , datatglerr);
+  }  
+  else if (hcint.b.chhltd)
+  {
+    MASK_HOST_INT_CHH (num);
+    
+    if(pdev->host.HC_Status[num] == HC_XFRC)
+    {
+      pdev->host.URB_State[num] = URB_DONE;  
+      
+      if (hcchar.b.eptype == EP_TYPE_BULK)
+      {
+        pdev->host.hc[num].toggle_out ^= 1; 
+      }
+    }
+    else if(pdev->host.HC_Status[num] == HC_NAK)
+    {
+      pdev->host.URB_State[num] = URB_NOTREADY;      
+    }    
+    else if(pdev->host.HC_Status[num] == HC_NYET)
+    {
+      if(pdev->host.hc[num].do_ping == 1)
+      {
+        USB_OTG_HC_DoPing(pdev, num);
+      }
+      pdev->host.URB_State[num] = URB_NOTREADY;      
+    }      
+    else if(pdev->host.HC_Status[num] == HC_STALL)
+    {
+      pdev->host.URB_State[num] = URB_STALL;      
+    }  
+    else if(pdev->host.HC_Status[num] == HC_XACTERR)
+    {
+      if (pdev->host.ErrCnt[num] == 3)
+      {
+        pdev->host.URB_State[num] = URB_ERROR;  
+        pdev->host.ErrCnt[num] = 0;
+      }
+    }
+    CLEAR_HC_INT(hcreg , chhltd);    
+  }
+  
+  
+  return 1;
+}
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma optimize = none
+#endif /* __CC_ARM */
+/**
+* @brief  USB_OTG_USBH_handle_hc_n_In_ISR 
+*         Handles interrupt for a specific Host Channel
+* @param  pdev: Selected device
+* @param  hc_num: Channel number
+* @retval status 
+*/
+uint32_t USB_OTG_USBH_handle_hc_n_In_ISR (USB_OTG_CORE_HANDLE *pdev , uint32_t num)
+{
+  USB_OTG_HCINTn_TypeDef     hcint;
+  USB_OTG_HCINTMSK_TypeDef  hcintmsk;
+  USB_OTG_HCCHAR_TypeDef     hcchar; 
+  USB_OTG_HCTSIZn_TypeDef  hctsiz;
+  USB_OTG_HC_REGS *hcreg;
+  
+  
+  hcreg = pdev->regs.HC_REGS[num];
+  hcint.d32 = USB_OTG_READ_REG32(&hcreg->HCINT);
+  hcintmsk.d32 = USB_OTG_READ_REG32(&hcreg->HCINTMSK);
+  hcint.d32 = hcint.d32 & hcintmsk.d32;
+  hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCCHAR);
+  hcintmsk.d32 = 0;
+  
+  
+  if (hcint.b.ahberr)
+  {
+    CLEAR_HC_INT(hcreg ,ahberr);
+    UNMASK_HOST_INT_CHH (num);
+  }  
+  else if (hcint.b.ack)
+  {
+    CLEAR_HC_INT(hcreg ,ack);
+  }
+  
+  else if (hcint.b.stall)  
+  {
+    UNMASK_HOST_INT_CHH (num);
+    pdev->host.HC_Status[num] = HC_STALL; 
+    CLEAR_HC_INT(hcreg , nak);   /* Clear the NAK Condition */
+    CLEAR_HC_INT(hcreg , stall); /* Clear the STALL Condition */
+    hcint.b.nak = 0;           /* NOTE: When there is a 'stall', reset also nak, 
+                                  else, the pdev->host.HC_Status = HC_STALL
+    will be overwritten by 'nak' in code below */
+    USB_OTG_HC_Halt(pdev, num);    
+  }
+  else if (hcint.b.datatglerr)
+  {
+    
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg , nak);   
+    pdev->host.HC_Status[num] = HC_DATATGLERR; 
+    CLEAR_HC_INT(hcreg , datatglerr);
+  }    
+  
+  if (hcint.b.frmovrun)
+  {
+    UNMASK_HOST_INT_CHH (num);
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg ,frmovrun);
+  }
+  
+  else if (hcint.b.xfercompl)
+  {
+    
+    if (pdev->cfg.dma_enable == 1)
+    {
+      hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[num]->HCTSIZ);
+      pdev->host.XferCnt[num] =  pdev->host.hc[num].xfer_len - hctsiz.b.xfersize;
+    }
+    
+    pdev->host.HC_Status[num] = HC_XFRC;     
+    pdev->host.ErrCnt [num]= 0;
+    CLEAR_HC_INT(hcreg , xfercompl);
+    
+    if ((hcchar.b.eptype == EP_TYPE_CTRL)||
+        (hcchar.b.eptype == EP_TYPE_BULK))
+    {
+      UNMASK_HOST_INT_CHH (num);
+      USB_OTG_HC_Halt(pdev, num);
+      CLEAR_HC_INT(hcreg , nak); 
+      pdev->host.hc[num].toggle_in ^= 1;
+      
+    }
+    else if(hcchar.b.eptype == EP_TYPE_INTR)
+    {
+      hcchar.b.oddfrm  = 1;
+      USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32); 
+      pdev->host.URB_State[num] = URB_DONE;  
+    }
+    
+  }
+  else if (hcint.b.chhltd)
+  {
+    MASK_HOST_INT_CHH (num);
+    
+    if(pdev->host.HC_Status[num] == HC_XFRC)
+    {
+      pdev->host.URB_State[num] = URB_DONE;      
+    }
+    
+    else if (pdev->host.HC_Status[num] == HC_STALL) 
+    {
+      pdev->host.URB_State[num] = URB_STALL;
+    }   
+    
+    else if((pdev->host.HC_Status[num] == HC_XACTERR) ||
+            (pdev->host.HC_Status[num] == HC_DATATGLERR))
+    {
+      pdev->host.ErrCnt[num] = 0;
+      pdev->host.URB_State[num] = URB_ERROR;  
+      
+    }
+    else if(hcchar.b.eptype == EP_TYPE_INTR)
+    {
+      pdev->host.hc[num].toggle_in ^= 1;
+    }
+    
+    CLEAR_HC_INT(hcreg , chhltd);    
+    
+  }    
+  else if (hcint.b.xacterr)
+  {
+    UNMASK_HOST_INT_CHH (num);
+    pdev->host.ErrCnt[num] ++;
+    pdev->host.HC_Status[num] = HC_XACTERR;
+    USB_OTG_HC_Halt(pdev, num);
+    CLEAR_HC_INT(hcreg , xacterr);    
+    
+  }
+  else if (hcint.b.nak)  
+  {  
+    if(hcchar.b.eptype == EP_TYPE_INTR)
+    {
+      UNMASK_HOST_INT_CHH (num);
+      USB_OTG_HC_Halt(pdev, num);
+    }
+    else if  ((hcchar.b.eptype == EP_TYPE_CTRL)||
+              (hcchar.b.eptype == EP_TYPE_BULK))
+    {
+      /* re-activate the channel  */
+      hcchar.b.chen = 1;
+      hcchar.b.chdis = 0;
+      USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[num]->HCCHAR, hcchar.d32); 
+    }
+    pdev->host.HC_Status[num] = HC_NAK;
+    CLEAR_HC_INT(hcreg , nak);   
+  }
+  
+  
+  return 1;
+  
+}
+
+/**
+* @brief  USB_OTG_USBH_handle_rx_qlvl_ISR 
+*         Handles the Rx Status Queue Level Interrupt
+* @param  pdev: Selected device
+* @retval status 
+*/
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma optimize = none
+#endif /* __CC_ARM */
+static uint32_t USB_OTG_USBH_handle_rx_qlvl_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GRXFSTS_TypeDef       grxsts;
+  USB_OTG_GINTMSK_TypeDef       intmsk;
+  USB_OTG_HCTSIZn_TypeDef       hctsiz; 
+  USB_OTG_HCCHAR_TypeDef        hcchar;
+  __IO uint8_t                  channelnum =0;  
+  uint32_t                      count;    
+  
+  /* Disable the Rx Status Queue Level interrupt */
+  intmsk.d32 = 0;
+  intmsk.b.rxstsqlvl = 1;
+  USB_OTG_MODIFY_REG32( &pdev->regs.GREGS->GINTMSK, intmsk.d32, 0);
+  
+  grxsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GRXSTSP);
+  channelnum = grxsts.b.chnum;  
+  hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR);
+  
+  switch (grxsts.b.pktsts)
+  {
+  case GRXSTS_PKTSTS_IN:
+    /* Read the data into the host buffer. */
+    if ((grxsts.b.bcnt > 0) && (pdev->host.hc[channelnum].xfer_buff != (void  *)0))
+    {  
+      
+      USB_OTG_ReadPacket(pdev, pdev->host.hc[channelnum].xfer_buff, grxsts.b.bcnt);
+      /*manage multiple Xfer */
+      pdev->host.hc[grxsts.b.chnum].xfer_buff += grxsts.b.bcnt;           
+      pdev->host.hc[grxsts.b.chnum].xfer_count  += grxsts.b.bcnt;
+      
+      
+      count = pdev->host.hc[channelnum].xfer_count;
+      pdev->host.XferCnt[channelnum]  = count;
+      
+      hctsiz.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[channelnum]->HCTSIZ);
+      if(hctsiz.b.pktcnt > 0)
+      {
+        /* re-activate the channel when more packets are expected */
+        hcchar.b.chen = 1;
+        hcchar.b.chdis = 0;
+        USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[channelnum]->HCCHAR, hcchar.d32);
+      }
+    }
+    break;
+    
+  case GRXSTS_PKTSTS_IN_XFER_COMP:
+    
+  case GRXSTS_PKTSTS_DATA_TOGGLE_ERR:
+  case GRXSTS_PKTSTS_CH_HALTED:
+  default:
+    break;
+  }
+  
+  /* Enable the Rx Status Queue Level interrupt */
+  intmsk.b.rxstsqlvl = 1;
+  USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, 0, intmsk.d32);
+  return 1;
+}
+
+/**
+* @brief  USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR 
+*         Handles the incomplete Periodic transfer Interrupt
+* @param  pdev: Selected device
+* @retval status 
+*/
+#if defined ( __ICCARM__ ) /*!< IAR Compiler */
+#pragma optimize = none
+#endif /* __CC_ARM */
+static uint32_t USB_OTG_USBH_handle_IncompletePeriodicXfer_ISR (USB_OTG_CORE_HANDLE *pdev)
+{
+  
+  USB_OTG_GINTSTS_TypeDef       gintsts;
+  USB_OTG_HCCHAR_TypeDef        hcchar; 
+  
+  
+  
+  
+  hcchar.d32 = USB_OTG_READ_REG32(&pdev->regs.HC_REGS[0]->HCCHAR);
+  hcchar.b.chen = 1;
+  hcchar.b.chdis = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.HC_REGS[0]->HCCHAR, hcchar.d32);  
+  
+  gintsts.d32 = 0;
+  /* Clear interrupt */
+  gintsts.b.incomplisoout = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  
+  return 1;
+}
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_otg.c b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_otg.c
new file mode 100644
index 0000000000000000000000000000000000000000..17c5eb685a28a330e0c852ad968c57a0e3f76237
--- /dev/null
+++ b/crazyflie-firmware-src/src/lib/STM32_USB_OTG_Driver/src/usb_otg.c
@@ -0,0 +1,418 @@
+/**
+  ******************************************************************************
+  * @file    usb_otg.c
+  * @author  MCD Application Team
+  * @version V2.1.0
+  * @date    19-March-2012
+  * @brief   OTG Core Layer
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
+  *
+  * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
+  * You may not use this file except in compliance with the License.
+  * You may obtain a copy of the License at:
+  *
+  *        http://www.st.com/software_license_agreement_liberty_v2
+  *
+  * Unless required by applicable law or agreed to in writing, software 
+  * distributed under the License is distributed on an "AS IS" BASIS, 
+  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+  * See the License for the specific language governing permissions and
+  * limitations under the License.
+  *
+  ******************************************************************************
+  */
+
+/* Includes ------------------------------------------------------------------*/
+#include "usb_defines.h"
+#include "usb_regs.h"
+#include "usb_core.h"
+#include "usb_otg.h"
+
+/** @addtogroup USB_OTG_DRIVER
+  * @{
+  */
+  
+/** @defgroup USB_OTG 
+  * @brief This file is the interface between EFSL ans Host mass-storage class
+  * @{
+  */
+
+
+/** @defgroup USB_OTG_Private_Defines
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+ 
+
+/** @defgroup USB_OTG_Private_TypesDefinitions
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+
+/** @defgroup USB_OTG_Private_Macros
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_OTG_Private_Variables
+  * @{
+  */ 
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_OTG_Private_FunctionPrototypes
+  * @{
+  */ 
+
+uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev);
+
+static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev);
+static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev);
+
+/**
+  * @}
+  */ 
+
+
+/** @defgroup USB_OTG_Private_Functions
+  * @{
+  */ 
+
+
+/*                           OTG Interrupt Handler                         */
+
+
+/**
+  * @brief  STM32_USBO_OTG_ISR_Handler
+  *         
+  * @param  None
+  * @retval : None
+  */
+uint32_t STM32_USBO_OTG_ISR_Handler(USB_OTG_CORE_HANDLE *pdev)
+{
+  uint32_t retval = 0;
+  USB_OTG_GINTSTS_TypeDef  gintsts ;
+  gintsts.d32 = 0;
+
+  gintsts.d32 = USB_OTG_Read_itr(pdev);
+  if (gintsts.d32 == 0)
+  {
+    return 0;
+  }
+  if (gintsts.b.otgintr)
+  {
+    retval |= USB_OTG_HandleOTG_ISR(pdev);
+  }
+  if (gintsts.b.conidstschng)
+  {
+    retval |= USB_OTG_HandleConnectorIDStatusChange_ISR(pdev);
+  }
+  if (gintsts.b.sessreqintr)
+  {
+    retval |= USB_OTG_HandleSessionRequest_ISR(pdev);
+  }
+  return retval;
+}
+
+
+/**
+  * @brief  USB_OTG_Read_itr
+  *         returns the Core Interrupt register
+  * @param  None
+  * @retval : status
+  */
+static uint32_t USB_OTG_Read_itr(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  USB_OTG_GINTMSK_TypeDef  gintmsk;
+  USB_OTG_GINTMSK_TypeDef  gintmsk_common;
+  
+  
+  gintsts.d32 = 0;
+  gintmsk.d32 = 0;
+  gintmsk_common.d32 = 0;
+  
+  /* OTG interrupts */
+  gintmsk_common.b.sessreqintr = 1;
+  gintmsk_common.b.conidstschng = 1;
+  gintmsk_common.b.otgintr = 1;
+  
+  gintsts.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTSTS);
+  gintmsk.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GINTMSK);
+  return ((gintsts.d32 & gintmsk.d32 ) & gintmsk_common.d32);
+}
+
+
+/**
+  * @brief  USB_OTG_HandleOTG_ISR
+  *         handles the OTG Interrupts
+  * @param  None
+  * @retval : status
+  */
+static uint32_t USB_OTG_HandleOTG_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GOTGINT_TypeDef  gotgint;
+  USB_OTG_GOTGCTL_TypeDef  gotgctl;
+  
+  
+  gotgint.d32 = 0;
+  gotgctl.d32 = 0;
+  
+  gotgint.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGINT);
+  gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
+  
+  if (gotgint.b.sesenddet)
+  {
+    gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
+    
+    
+    if (USB_OTG_IsDeviceMode(pdev))
+    {
+
+    }
+    else if (USB_OTG_IsHostMode(pdev))
+    {
+
+    }
+  }
+
+  /* ----> SRP SUCCESS or FAILURE INTERRUPT <---- */
+  if (gotgint.b.sesreqsucstschng)
+  {
+    gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
+    if (gotgctl.b.sesreqscs) /* Session request success                                          */
+    {
+      if (USB_OTG_IsDeviceMode(pdev))
+      {
+
+      }
+      /* Clear Session Request */
+      gotgctl.d32 = 0;
+      gotgctl.b.sesreq = 1;
+      USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GOTGCTL, gotgctl.d32, 0);
+    }
+    else /* Session request failure                                          */
+    {
+      if (USB_OTG_IsDeviceMode(pdev))
+      {
+
+      }
+    }
+  }
+  /* ----> HNP SUCCESS or FAILURE INTERRUPT <---- */
+  if (gotgint.b.hstnegsucstschng)
+  {
+    gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
+
+    if (gotgctl.b.hstnegscs)                                    /* Host negotiation success                                         */
+    {
+      if (USB_OTG_IsHostMode(pdev))                              /* The core AUTOMATICALLY sets the Host mode                        */
+      {
+
+      }
+    }
+    else                                                        /* Host negotiation failure */
+    {
+
+    }
+    gotgint.b.hstnegsucstschng = 1;                             /* Ack "Host Negotiation Success Status Change" interrupt.          */
+  }
+  /* ----> HOST NEGOTIATION DETECTED INTERRUPT <---- */
+  if (gotgint.b.hstnegdet)
+  {
+    if (USB_OTG_IsDeviceMode(pdev))                              /* The core AUTOMATICALLY sets the Host mode                        */
+    {
+
+    }
+    else
+    {
+
+    }
+  }
+  if (gotgint.b.adevtoutchng)
+  {}
+  if (gotgint.b.debdone)
+  {
+    USB_OTG_ResetPort(pdev);
+  }
+  /* Clear OTG INT */
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGINT, gotgint.d32);
+  return 1;
+}
+
+
+/**
+  * @brief  USB_OTG_HandleConnectorIDStatusChange_ISR
+  *         handles the Connector ID Status Change Interrupt
+  * @param  None
+  * @retval : status
+  */
+static uint32_t USB_OTG_HandleConnectorIDStatusChange_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTMSK_TypeDef  gintmsk;
+  USB_OTG_GOTGCTL_TypeDef   gotgctl;
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  
+  gintsts.d32 = 0 ;
+  gintmsk.d32 = 0 ;
+  gotgctl.d32 = 0 ;
+  gintmsk.b.sofintr = 1;
+  
+  USB_OTG_MODIFY_REG32(&pdev->regs.GREGS->GINTMSK, gintmsk.d32, 0);
+  gotgctl.d32 = USB_OTG_READ_REG32(&pdev->regs.GREGS->GOTGCTL);
+  
+  /* B-Device connector (Device Mode) */
+  if (gotgctl.b.conidsts)
+  {
+    USB_OTG_DisableGlobalInt(pdev);
+    USB_OTG_CoreInitDev(pdev);
+    USB_OTG_EnableGlobalInt(pdev);
+    pdev->otg.OTG_State = B_PERIPHERAL;
+  }
+  else
+  {
+    USB_OTG_DisableGlobalInt(pdev);
+    USB_OTG_CoreInitHost(pdev);
+    USB_OTG_EnableGlobalInt(pdev);
+    pdev->otg.OTG_State = A_HOST;
+  }
+  /* Set flag and clear interrupt */
+  gintsts.b.conidstschng = 1;
+  USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  return 1;
+}
+
+
+/**
+  * @brief  USB_OTG_HandleSessionRequest_ISR 
+  *           Initiating the Session Request Protocol
+  * @param  None
+  * @retval : status
+  */
+static uint32_t USB_OTG_HandleSessionRequest_ISR(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GINTSTS_TypeDef  gintsts;
+  USB_OTG_GOTGCTL_TypeDef   gotgctl;
+
+
+  gotgctl.d32 = 0;
+  gintsts.d32 = 0;
+
+  gotgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
+  if (USB_OTG_IsDeviceMode(pdev) && (gotgctl.b.bsesvld))
+  {
+
+  }
+  else if (gotgctl.b.asesvld)
+  {
+  }
+  /* Clear interrupt */
+  gintsts.d32 = 0;
+  gintsts.b.sessreqintr = 1;
+  USB_OTG_WRITE_REG32 (&pdev->regs.GREGS->GINTSTS, gintsts.d32);
+  return 1;
+}
+
+
+/**
+  * @brief  USB_OTG_InitiateSRP
+  *         Initiate an srp session
+  * @param  None
+  * @retval : None
+  */
+void USB_OTG_InitiateSRP(USB_OTG_CORE_HANDLE *pdev)
+{
+  USB_OTG_GOTGCTL_TypeDef  otgctl;
+
+  otgctl.d32 = 0;
+
+  otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
+  if (otgctl.b.sesreq)
+  {
+    return; /* SRP in progress */
+  }
+  otgctl.b.sesreq = 1;
+  USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
+}
+
+
+/**
+  * @brief  USB_OTG_InitiateHNP
+  *         Initiate HNP
+  * @param  None
+  * @retval : None
+  */
+void USB_OTG_InitiateHNP(USB_OTG_CORE_HANDLE *pdev , uint8_t state, uint8_t mode)
+{
+  USB_OTG_GOTGCTL_TypeDef   otgctl;
+  USB_OTG_HPRT0_TypeDef    hprt0;
+  
+  otgctl.d32 = 0;
+  hprt0.d32  = 0;
+
+  otgctl.d32 = USB_OTG_READ_REG32( &pdev->regs.GREGS->GOTGCTL );
+  if (mode)
+  { /* Device mode */
+    if (state)
+    {
+
+      otgctl.b.devhnpen = 1; /* B-Dev has been enabled to perform HNP         */
+      otgctl.b.hnpreq   = 1; /* Initiate an HNP req. to the connected USB host*/
+      USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
+    }
+  }
+  else
+  { /* Host mode */
+    if (state)
+    {
+      otgctl.b.hstsethnpen = 1; /* A-Dev has enabled B-device for HNP       */
+      USB_OTG_WRITE_REG32(&pdev->regs.GREGS->GOTGCTL, otgctl.d32);
+      /* Suspend the bus so that B-dev will disconnect indicating the initial condition for HNP to DWC_Core */
+      hprt0.d32  = USB_OTG_ReadHPRT0(pdev);
+      hprt0.b.prtsusp = 1; /* The core clear this bit when disconnect interrupt generated (GINTSTS.DisconnInt = '1') */
+      USB_OTG_WRITE_REG32(pdev->regs.HPRT0, hprt0.d32);
+    }
+  }
+}
+
+
+/**
+  * @brief  USB_OTG_GetCurrentState
+  *         Return current OTG State
+  * @param  None
+  * @retval : None
+  */
+uint32_t USB_OTG_GetCurrentState (USB_OTG_CORE_HANDLE *pdev)
+{
+  return pdev->otg.OTG_State;
+}
+
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/ 
+
+/**
+* @}
+*/
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/crazyflie-firmware-src/src/modules/interface/attitude_controller.h b/crazyflie-firmware-src/src/modules/interface/attitude_controller.h
new file mode 100644
index 0000000000000000000000000000000000000000..275ca149056d7643ce442edf040c129782e18333
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/attitude_controller.h
@@ -0,0 +1,67 @@
+/**
+ *    ||          ____  _ __  ______
+ * +------+      / __ )(_) /_/ ____/_________ _____  ___
+ * | 0xBC |     / __  / / __/ /    / ___/ __ `/_  / / _	\
+ * +------+    / /_/ / / /_/ /___ / /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\____//_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * attitude_controller.h: PID-based attitude controller
+ */
+
+#ifndef ATTITUDE_CONTROLLER_H_
+#define ATTITUDE_CONTROLLER_H_
+
+#include <stdbool.h>
+#include "commander.h"
+
+
+void attitudeControllerInit(const float updateDt);
+bool attitudeControllerTest(void);
+
+/**
+ * Make the controller run an update of the attitude PID. The output is
+ * the desired rate which should be fed into a rate controller. The
+ * attitude controller can be run in a slower update rate then the rate
+ * controller.
+ */
+void attitudeControllerCorrectAttitudePID(
+       float eulerRollActual, float eulerPitchActual, float eulerYawActual,
+       float eulerRollDesired, float eulerPitchDesired, float eulerYawDesired,
+       float* rollRateDesired, float* pitchRateDesired, float* yawRateDesired);
+
+/**
+ * Make the controller run an update of the rate PID. The output is
+ * the actuator force.
+ */
+void attitudeControllerCorrectRatePID(
+       float rollRateActual, float pitchRateActual, float yawRateActual,
+       float rollRateDesired, float pitchRateDesired, float yawRateDesired);
+
+/**
+ * Reset controller roll, pitch and yaw PID's.
+ */
+void attitudeControllerResetAllPID(void);
+
+/**
+ * Get the actuator output.
+ */
+void attitudeControllerGetActuatorOutput(int16_t* roll, int16_t* pitch, int16_t* yaw);
+
+
+#endif /* ATTITUDE_CONTROLLER_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/comm.h b/crazyflie-firmware-src/src/modules/interface/comm.h
new file mode 100644
index 0000000000000000000000000000000000000000..2b1325b12b0933afd3930c9d708546a39d50ef63
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/comm.h
@@ -0,0 +1,33 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * comm.c - High level communication module
+ */
+
+#ifndef __COMM_H__
+#define __COMM_H__
+
+void commInit(void);
+bool commTest(void);
+
+#endif //__COMM_H__
diff --git a/crazyflie-firmware-src/src/modules/interface/commander.h b/crazyflie-firmware-src/src/modules/interface/commander.h
new file mode 100644
index 0000000000000000000000000000000000000000..fddeceabf44b6a06547d81ee6ee3d72d5ef517e2
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/commander.h
@@ -0,0 +1,65 @@
+/**
+ *    ||          ____  _ __  ______
+ * +------+      / __ )(_) /_/ ____/_________ _____  ___
+ * | 0xBC |     / __  / / __/ /    / ___/ __ `/_  / / _	\
+ * +------+    / /_/ / / /_/ /___ / /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\____//_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ */
+
+#ifndef COMMANDER_H_
+#define COMMANDER_H_
+#include <stdint.h>
+#include <stdbool.h>
+#include "config.h"
+#include "stabilizer_types.h"
+
+#ifdef PLATFORM_CF1
+  #define DEFAULT_YAW_MODE  PLUSMODE
+#else
+  #define DEFAULT_YAW_MODE  XMODE
+#endif
+
+#define COMMANDER_WDT_TIMEOUT_STABILIZE  M2T(500)
+#define COMMANDER_WDT_TIMEOUT_SHUTDOWN   M2T(2000)
+
+/**
+ * CRTP commander data struct
+ */
+struct CommanderCrtpValues
+{
+  float roll;       // deg
+  float pitch;      // deg
+  float yaw;        // deg
+  uint16_t thrust;
+  uint16_t cmd1;
+  uint16_t cmd2;
+  uint16_t cmd3;
+  uint16_t cmd4;
+  uint16_t SPtype;
+} __attribute__((packed));
+
+void commanderInit(void);
+bool commanderTest(void);
+uint32_t commanderGetInactivityTime(void);
+void commanderExtrxSet(const struct CommanderCrtpValues* val);
+
+void commanderGetSetpoint(setpoint_t *setpoint, const state_t *state);
+
+#endif /* COMMANDER_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/console.h b/crazyflie-firmware-src/src/modules/interface/console.h
new file mode 100644
index 0000000000000000000000000000000000000000..aace9cca6bc20a7ff485165a3a5f7e3afdcd344e
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/console.h
@@ -0,0 +1,81 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * console.h - Used to send console data to the client
+ */
+
+#ifndef CONSOLE_H_
+#define CONSOLE_H_
+
+#include <stdbool.h>
+#include "eprintf.h"
+
+/**
+ * Initialize the console
+ */
+void consoleInit(void);
+
+bool consoleTest(void);
+
+/**
+ * Put a character to the console buffer
+ *
+ * @param ch character that shall be printed
+ * @return The character casted to unsigned int or EOF in case of error
+ */
+int consolePutchar(int ch);
+
+/**
+ * Put a character to the console buffer
+ *
+ * @param ch character that shall be printed
+ * @return The character casted to unsigned int or EOF in case of error
+ *
+ * @note This version can be called by interrup. In such case the internal
+ * buffer is going to be used. If a task currently is printing or if the
+ * interrupts prints too much the data will be ignored.
+ */
+int consolePutcharFromISR(int ch);
+
+/**
+ * Put a null-terminated string on the console buffer
+ *
+ * @param str Null terminated string
+ * @return a nonnegative number on success, or EOF on error.
+ */
+int consolePuts(char *str);
+
+/**
+ * Flush the console buffer
+ */
+void consoleFlush(void);
+
+/**
+ * Macro implementing consolePrintf with eprintf
+ *
+ * @param FMT String format
+ * @patam ... Parameters to print
+ */
+#define consolePrintf(FMT, ...) eprintf(consolePutchar, FMT, ## __VA_ARGS__)
+
+#endif /*CONSOLE_H_*/
diff --git a/crazyflie-firmware-src/src/modules/interface/controller.h b/crazyflie-firmware-src/src/modules/interface/controller.h
new file mode 100644
index 0000000000000000000000000000000000000000..bfe71b6ba28a54bb70cdc4f584b3fd0ecf5b6472
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/controller.h
@@ -0,0 +1,38 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * controller.h - State controller interface
+ */
+#ifndef __CONTROLLER_H__
+#define __CONTROLLER_H__
+
+#include "stabilizer_types.h"
+
+void stateControllerInit(void);
+bool stateControllerTest(void);
+void stateController(control_t *control, setpoint_t *setpoint,
+                                         const sensorData_t *sensors,
+                                         const state_t *state,
+                                         const uint32_t tick);
+
+#endif //__CONTROLLER_H__
diff --git a/crazyflie-firmware-src/src/modules/interface/crtp.h b/crazyflie-firmware-src/src/modules/interface/crtp.h
new file mode 100644
index 0000000000000000000000000000000000000000..fe7ecc8c5a96b582f828e066c087b7c9168ed7b3
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/crtp.h
@@ -0,0 +1,188 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * crtp.h - CrazyRealtimeTransferProtocol stack
+ */
+
+#ifndef CRTP_H_
+#define CRTP_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#define CRTP_MAX_DATA_SIZE 30
+
+#define CRTP_HEADER(port, channel) (((port & 0x0F) << 4) | (channel & 0x0F))
+
+#define CRTP_IS_NULL_PACKET(P) ((P.header&0xF3)==0xF3)
+
+typedef enum {
+  CRTP_PORT_CONSOLE     = 0x00,
+  CRTP_PORT_PARAM       = 0x02,
+  CRTP_PORT_SETPOINT    = 0x03,
+  CRTP_PORT_MEM         = 0x04,
+  CRTP_PORT_LOG         = 0x05,
+  CRTP_PORT_POSITION    = 0x06,
+  CRTP_PORT_PLATFORM    = 0x0D,
+  CRTP_PORT_LINK        = 0x0F,
+} CRTPPort;
+
+typedef struct _CRTPPacket
+{
+  uint8_t size;
+  union {
+    struct {
+      union {
+        uint8_t header;
+        struct {
+#ifndef CRTP_HEADER_COMPAT
+          uint8_t channel     : 2;
+          uint8_t reserved    : 2;
+          uint8_t port        : 4;
+#else
+          uint8_t channel  : 2;
+          uint8_t port     : 4;
+          uint8_t reserved : 2;
+#endif
+        };
+      };
+      uint8_t data[CRTP_MAX_DATA_SIZE];
+    };
+    uint8_t raw[CRTP_MAX_DATA_SIZE+1];
+  };
+} __attribute__((packed)) CRTPPacket;
+
+typedef void (*CrtpCallback)(CRTPPacket *);
+
+/**
+ * Initialize the CRTP stack
+ */
+void crtpInit(void);
+
+bool crtpTest(void);
+
+/**
+ * Initializes the queue and dispatch of an task.
+ *
+ * @param[in] taskId The id of the CRTP task
+ */
+void crtpInitTaskQueue(CRTPPort taskId);
+
+/**
+ * Register a callback to be called for a particular port.
+ *
+ * @param[in] port Crtp port for which the callback is set
+ * @param[in] cb Callback that will be called when a packet is received on
+ *            'port'.
+ *
+ * @note Only one callback can be registered per port! The last callback
+ *       registered will be the one called
+ */
+void crtpRegisterPortCB(int port, CrtpCallback cb);
+
+/**
+ * Put a packet in the TX task
+ *
+ * If the TX stack is full, the oldest lowest priority packet is dropped
+ *
+ * @param[in] p CRTPPacket to send
+ */
+int crtpSendPacket(CRTPPacket *p);
+
+/**
+ * Put a packet in the TX task
+ *
+ * If the TX stack is full, the function block until one place is free (Good for console implementation)
+ */
+int crtpSendPacketBlock(CRTPPacket *p);
+
+/**
+ * Fetch a packet with a specidied task ID.
+ *
+ * @param[in]  taskId The id of the CRTP task
+ * @param[out] p      The CRTP Packet with infomation (unchanged if nothing to fetch)
+ *
+ * @returns status of fetch from queue
+ */
+int crtpReceivePacket(CRTPPort taskId, CRTPPacket *p);
+
+/**
+ * Fetch a packet with a specidied task ID. Wait some time befor giving up
+ *
+ * @param[in]  taskId The id of the CRTP task
+ * @param[out] p      The CRTP Packet with infomation (unchanged if nothing to fetch)
+ * @param[in] wait    Wait time in milisecond
+ *
+ * @returns status of fetch from queue
+ */
+int crtpReceivePacketWait(CRTPPort taskId, CRTPPacket *p, int wait);
+
+/**
+ * Get the number of free tx packets in the queue
+ *
+ * @return Number of free packets
+ */
+int crtpGetFreeTxQueuePackets(void);
+
+/**
+ * Wait for a packet to arrive for the specified taskID
+ *
+ * @param[in]  taskId The id of the CRTP task
+ * @paran[out] p      The CRTP Packet with information
+ *
+ * @return status of fetch from queue
+ */
+int crtpReceivePacketBlock(CRTPPort taskId, CRTPPacket *p);
+
+/**
+ * Function pointer structure to be filled by the CRTP link to permits CRTP to
+ * use manu link
+ */
+struct crtpLinkOperations
+{
+  int (*setEnable)(bool enable);
+  int (*sendPacket)(CRTPPacket *pk);
+  int (*receivePacket)(CRTPPacket *pk);
+  bool (*isConnected)(void);
+  int (*reset)(void);
+};
+
+void crtpSetLink(struct crtpLinkOperations * lk);
+
+/**
+ * Check if the connection timeout has been reached, otherwise
+ * we will assume that we are connected.
+ *
+ * @return true if conencted, otherwise false
+ */
+bool crtpIsConnected(void);
+
+/**
+ * Reset the CRTP communication by flushing all the queues that
+ * contain packages.
+ *
+ * @return 0 for success
+ */
+int crtpReset(void);
+
+#endif /*CRTP_H_*/
diff --git a/crazyflie-firmware-src/src/modules/interface/crtpservice.h b/crazyflie-firmware-src/src/modules/interface/crtpservice.h
new file mode 100644
index 0000000000000000000000000000000000000000..50b40e2b3d25ecea7ce3f934a0dbf24adff4e42b
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/crtpservice.h
@@ -0,0 +1,40 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * link.h - Used to send/receive link packats
+ */
+
+#ifndef __CRTPSERVICE_H__
+#define __CRTPSERVICE_H__
+
+#include <stdbool.h>
+
+/**
+ * Initialize the link task
+ */
+void crtpserviceInit(void);
+
+bool crtpserviceTest(void);
+
+#endif /* __CRTPSERVICE_H__ */
+
diff --git a/crazyflie-firmware-src/src/modules/interface/estimator.h b/crazyflie-firmware-src/src/modules/interface/estimator.h
new file mode 100644
index 0000000000000000000000000000000000000000..7e32f03eabe9741c96602ed095d17059643ded64
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/estimator.h
@@ -0,0 +1,35 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * extimator.h - State estimator interface
+ */
+#ifndef __ESTIMATOR_H__
+#define __ESTIMATOR_H__
+
+#include "stabilizer_types.h"
+
+void stateEstimatorInit(void);
+bool stateEstimatorTest(void);
+void stateEstimator(state_t *state, const sensorData_t *sensorData, const uint32_t tick);
+
+#endif //__ESTIMATOR_H__
diff --git a/crazyflie-firmware-src/src/modules/interface/estimator_kalman.h b/crazyflie-firmware-src/src/modules/interface/estimator_kalman.h
new file mode 100644
index 0000000000000000000000000000000000000000..aa4a2511b0f1d5acbda80566afe1ec2394922c21
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/estimator_kalman.h
@@ -0,0 +1,70 @@
+/**
+ * Authored by Michael Hamer (http://www.mikehamer.info), June 2016
+ * Thank you to Mark Mueller (www.mwm.im) for advice during implementation,
+ * and for derivation of the original filter in the below-cited paper.
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * ============================================================================
+ *
+ * The Kalman filter implemented in this file is based on the papers:
+ *
+ * "Fusing ultra-wideband range measurements with accelerometers and rate gyroscopes for quadrocopter state estimation"
+ * http://ieeexplore.ieee.org/xpl/articleDetails.jsp?arnumber=7139421
+ *
+ * and
+ *
+ * "Kalman filtering with an attitude" as published in the PhD thesis "Increased autonomy for quadrocopter systems: trajectory generation, fail-safe strategies, and state estimation"
+ * http://dx.doi.org/10.3929/ethz-a-010655275
+ * TODO: Update the above reference once the paper has been published
+ *
+ * Academic citation would be appreciated.
+ *
+ * BIBTEX ENTRIES:
+      @INPROCEEDINGS{MuellerHamer2015,
+      author  = {Mueller, M. W. and Hamer, M. and D'Andrea, R.},
+      title   = {Fusing ultra-wideband range measurements with accelerometers and rate gyroscopes for quadrocopter state estimation},
+      booktitle = {2015 IEEE International Conference on Robotics and Automation (ICRA)},
+      year    = {2015},
+      month   = {May},
+      pages   = {1730-1736},
+      doi     = {10.1109/ICRA.2015.7139421},
+      ISSN    = {1050-4729}}
+      
+      @PHDTHESIS {Mueller2016,
+      author  = {Mueller, M. W.},
+      title   = {Increased autonomy for quadrocopter systems: trajectory generation, fail-safe strategies, and state-estimation},
+      school  = {ETH Zurich},
+      year    = {2016},
+      doi     = {10.3929/ethz-a-010655275}}
+ *
+ * ============================================================================
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include "stabilizer_types.h"
+
+void stateEstimatorInit(void);
+void stateEstimatorUpdate(state_t *state, sensorData_t *sensors, control_t *control);
+bool stateEstimatorTest(void);
+
+
+/**
+ * The filter supports the incorporation of additional sensors into the state estimate via the following functions:
+ */
+bool stateEstimatorEnqueueTDOA(tdoaMeasurement_t *uwb);
+bool stateEstimatorEnqueuePosition(positionMeasurement_t *pos);
+bool stateEstimatorEnqueueDistance(distanceMeasurement_t *dist);
+bool stateEstimatorEnqueueTOF(tofMeasurement_t *tof);
diff --git a/crazyflie-firmware-src/src/modules/interface/ext_position.h b/crazyflie-firmware-src/src/modules/interface/ext_position.h
new file mode 100644
index 0000000000000000000000000000000000000000..23c8f5939028461ef893abff400a4f5bbac0d94c
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/ext_position.h
@@ -0,0 +1,47 @@
+/**
+ *    ||          ____  _ __  ______
+ * +------+      / __ )(_) /_/ ____/_________ _____  ___
+ * | 0xBC |     / __  / / __/ /    / ___/ __ `/_  / / _	\
+ * +------+    / /_/ / / /_/ /___ / /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\____//_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ */
+
+#ifndef _EXT_POSITION_H_
+#define _EXT_POSITION_H_
+
+#include "stabilizer_types.h"
+
+/**
+ * CRTP external position data struct
+ */
+struct CrtpExtPosition
+{
+  float x; // in m
+  float y; // in m
+  float z; // in m
+} __attribute__((packed));
+
+// Set up the callback for the CRTP_PORT_POSITION
+void extPositionInit(void);
+
+// Get the current position from the cache
+bool getExtPosition(state_t *state);
+
+#endif /* _EXT_POSITION_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/extrx.h b/crazyflie-firmware-src/src/modules/interface/extrx.h
new file mode 100644
index 0000000000000000000000000000000000000000..4a3dc338a48c8e9658ddcf68aeb42b3922f163dd
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/extrx.h
@@ -0,0 +1,31 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2013 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * extrx.h -  Module to handle external receiver inputs
+ */
+
+#include <stdint.h>
+
+void extRxInit(void);
+
diff --git a/crazyflie-firmware-src/src/modules/interface/info.h b/crazyflie-firmware-src/src/modules/interface/info.h
new file mode 100644
index 0000000000000000000000000000000000000000..1c7501a97ccdd382c446d3c6ee0a8a07256bbbf4
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/info.h
@@ -0,0 +1,43 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * info.h - Receive information requests and send them back to the client
+ */
+#ifndef __INFO_H__
+#define __INFO_H__
+ 
+#include "crtp.h"
+
+/**
+ * Initialize the information task
+ *
+ */
+void infoInit();
+
+/**
+ * Battery minimum voltage before sending an automatic warning message
+ */
+#define INFO_BAT_WARNING 3.3
+
+#endif //__INFO_H__
+
diff --git a/crazyflie-firmware-src/src/modules/interface/log.h b/crazyflie-firmware-src/src/modules/interface/log.h
new file mode 100644
index 0000000000000000000000000000000000000000..c2d88b00ef4b14c485ae030b7192e360cec87557
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/log.h
@@ -0,0 +1,83 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * log.h - Dynamic log system
+ */
+
+#ifndef __LOG_H__
+#define __LOG_H__
+
+#include <stdbool.h>
+#include <stdint.h>
+
+/* Public functions */
+void logInit(void);
+bool logTest(void);
+
+/* Internal access of log variables */
+int logGetVarId(char* group, char* name);
+float logGetFloat(int varid);
+int logGetInt(int varid);
+unsigned int logGetUint(int varid);
+
+/* Basic log structure */
+struct log_s {
+  uint8_t type;
+  char * name;
+  void * address;
+};
+
+/* Possible variable types */
+#define LOG_UINT8  1
+#define LOG_UINT16 2
+#define LOG_UINT32 3
+#define LOG_INT8   4
+#define LOG_INT16  5
+#define LOG_INT32  6
+#define LOG_FLOAT  7
+#define LOG_FP16   8
+
+/* Internal defines */
+#define LOG_GROUP 0x80
+#define LOG_START 1
+#define LOG_STOP  0
+
+/* Macros */
+#define LOG_ADD(TYPE, NAME, ADDRESS) \
+   { .type = TYPE, .name = #NAME, .address = (void*)(ADDRESS), },
+
+#define LOG_ADD_GROUP(TYPE, NAME, ADDRESS) \
+   { \
+  .type = TYPE, .name = #NAME, .address = (void*)(ADDRESS), },
+
+#define LOG_GROUP_START(NAME)  \
+  static const struct log_s __logs_##NAME[] __attribute__((section(".log." #NAME), used)) = { \
+  LOG_ADD_GROUP(LOG_GROUP | LOG_START, NAME, 0x0)
+
+//#define LOG_GROUP_START_SYNC(NAME, LOCK) LOG_ADD_GROUP(LOG_GROUP | LOG_START, NAME, LOCK);
+
+#define LOG_GROUP_STOP(NAME) \
+  LOG_ADD_GROUP(LOG_GROUP | LOG_STOP, stop_##NAME, 0x0) \
+  };
+
+#endif /* __LOG_H__ */
diff --git a/crazyflie-firmware-src/src/modules/interface/mem.h b/crazyflie-firmware-src/src/modules/interface/mem.h
new file mode 100644
index 0000000000000000000000000000000000000000..06d1d2b02b83d30fcc6f0ae91923836c744cdb62
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/mem.h
@@ -0,0 +1,37 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * log.h - Dynamic log system
+ */
+
+#ifndef __MEM_H__
+#define __MEM_H__
+
+#include <stdbool.h>
+#include <stdint.h>
+
+/* Public functions */
+void memInit(void);
+bool memTest(void);
+
+#endif /* __MEM_H__ */
diff --git a/crazyflie-firmware-src/src/modules/interface/param.h b/crazyflie-firmware-src/src/modules/interface/param.h
new file mode 100644
index 0000000000000000000000000000000000000000..73438c54063ced915ebe92020445b1e30d1328a2
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/param.h
@@ -0,0 +1,95 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * param.h - Crazy parameter system header file.
+ */
+
+#ifndef __PARAM_H__
+#define __PARAM_H__
+
+#include <stdbool.h>
+#include <stdint.h>
+
+/* Public functions */
+void paramInit(void);
+bool paramTest(void);
+
+/* Basic parameter structure */
+struct param_s {
+  uint8_t type;
+  char * name;
+  void * address;
+};
+
+#define PARAM_BYTES_MASK 0x03
+#define PARAM_1BYTE  0x00
+#define PARAM_2BYTES 0x01
+#define PARAM_4BYTES 0x02
+#define PARAM_8BYTES 0x03
+
+#define PARAM_TYPE_INT   (0x00<<2)
+#define PARAM_TYPE_FLOAT (0x01<<2)
+
+#define PARAM_SIGNED (0x00<<3)
+#define PARAM_UNSIGNED (0x01<<3)
+
+#define PARAM_VARIABLE (0x00<<7)
+#define PARAM_GROUP    (0x01<<7)
+
+#define PARAM_RONLY (1<<6)
+
+#define PARAM_START 1
+#define PARAM_STOP  0
+
+#define PARAM_SYNC 0x02
+
+// User-friendly macros
+#define PARAM_UINT8 (PARAM_1BYTE | PARAM_TYPE_INT | PARAM_UNSIGNED)
+#define PARAM_INT8  (PARAM_1BYTE | PARAM_TYPE_INT | PARAM_SIGNED)
+#define PARAM_UINT16 (PARAM_2BYTES | PARAM_TYPE_INT | PARAM_UNSIGNED)
+#define PARAM_INT16  (PARAM_2BYTES | PARAM_TYPE_INT | PARAM_SIGNED)
+#define PARAM_UINT32 (PARAM_4BYTES | PARAM_TYPE_INT | PARAM_UNSIGNED)
+#define PARAM_INT32  (PARAM_4BYTES | PARAM_TYPE_INT | PARAM_SIGNED)
+
+#define PARAM_FLOAT (PARAM_4BYTES | PARAM_TYPE_FLOAT | PARAM_SIGNED)
+
+/* Macros */
+#define PARAM_ADD(TYPE, NAME, ADDRESS) \
+   { .type = TYPE, .name = #NAME, .address = (void*)(ADDRESS), },
+
+#define PARAM_ADD_GROUP(TYPE, NAME, ADDRESS) \
+   { \
+  .type = TYPE, .name = #NAME, .address = (void*)(ADDRESS), },
+
+#define PARAM_GROUP_START(NAME)  \
+  static const struct param_s __params_##NAME[] __attribute__((section(".param." #NAME), used)) = { \
+  PARAM_ADD_GROUP(PARAM_GROUP | PARAM_START, NAME, 0x0)
+
+//#define PARAM_GROUP_START_SYNC(NAME, LOCK) PARAM_ADD_GROUP(PARAM_GROUP | PARAM_START, NAME, LOCK);
+
+#define PARAM_GROUP_STOP(NAME) \
+  PARAM_ADD_GROUP(PARAM_GROUP | PARAM_STOP, stop_##NAME, 0x0) \
+  };
+
+#endif /* __PARAM_H__ */
+
diff --git a/crazyflie-firmware-src/src/modules/interface/pid.h b/crazyflie-firmware-src/src/modules/interface/pid.h
new file mode 100644
index 0000000000000000000000000000000000000000..54a94e27ded16503d2de935506fbb26aa82196e0
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/pid.h
@@ -0,0 +1,229 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * pid.h - implementation of the PID regulator
+ */
+#ifndef PID_H_
+#define PID_H_
+
+#include <stdbool.h>
+#include "filter.h"
+
+#if defined(PLATFORM_CF2)
+
+#define PID_ROLL_RATE_KP  250.0
+#define PID_ROLL_RATE_KI  500.0
+#define PID_ROLL_RATE_KD  2.5
+#define PID_ROLL_RATE_INTEGRATION_LIMIT    33.3
+
+#define PID_PITCH_RATE_KP  250.0
+#define PID_PITCH_RATE_KI  500.0
+#define PID_PITCH_RATE_KD  2.5
+#define PID_PITCH_RATE_INTEGRATION_LIMIT   33.3
+
+#define PID_YAW_RATE_KP  120.0
+#define PID_YAW_RATE_KI  16.7
+#define PID_YAW_RATE_KD  0.0
+#define PID_YAW_RATE_INTEGRATION_LIMIT     166.7
+
+#define PID_ROLL_KP  6.0
+#define PID_ROLL_KI  3.0
+#define PID_ROLL_KD  0.0
+#define PID_ROLL_INTEGRATION_LIMIT    20.0
+
+#define PID_PITCH_KP  6.0
+#define PID_PITCH_KI  3.0
+#define PID_PITCH_KD  0.0
+#define PID_PITCH_INTEGRATION_LIMIT   20.0
+
+#define PID_YAW_KP  6.0
+#define PID_YAW_KI  1.0
+#define PID_YAW_KD  0.35
+#define PID_YAW_INTEGRATION_LIMIT     360.0
+
+
+#define DEFAULT_PID_INTEGRATION_LIMIT  5000.0
+
+#else
+
+#define PID_ROLL_RATE_KP  70.0
+#define PID_ROLL_RATE_KI  0.0
+#define PID_ROLL_RATE_KD  0.0
+#define PID_ROLL_RATE_INTEGRATION_LIMIT    33.3
+
+#define PID_PITCH_RATE_KP  70.0
+#define PID_PITCH_RATE_KI  0.0
+#define PID_PITCH_RATE_KD  0.0
+#define PID_PITCH_RATE_INTEGRATION_LIMIT   33.3
+
+#define PID_YAW_RATE_KP  70.0
+#define PID_YAW_RATE_KI  16.7
+#define PID_YAW_RATE_KD  0.0
+#define PID_YAW_RATE_INTEGRATION_LIMIT     166.7
+
+#define PID_ROLL_KP  3.5
+#define PID_ROLL_KI  2.0
+#define PID_ROLL_KD  0.0
+#define PID_ROLL_INTEGRATION_LIMIT    20.0
+
+#define PID_PITCH_KP  3.5
+#define PID_PITCH_KI  2.0
+#define PID_PITCH_KD  0.0
+#define PID_PITCH_INTEGRATION_LIMIT   20.0
+
+#define PID_YAW_KP  10.0
+#define PID_YAW_KI  1.0
+#define PID_YAW_KD  0.35
+#define PID_YAW_INTEGRATION_LIMIT     360.0
+
+
+#define DEFAULT_PID_INTEGRATION_LIMIT  10000.0
+
+#endif
+
+typedef struct
+{
+  float desired;      //< set point
+  float error;        //< error
+  float prevError;    //< previous error
+  float integ;        //< integral
+  float deriv;        //< derivative
+  float kp;           //< proportional gain
+  float ki;           //< integral gain
+  float kd;           //< derivative gain
+  float outP;         //< proportional output (debugging)
+  float outI;         //< integral output (debugging)
+  float outD;         //< derivative output (debugging)
+  float iLimit;       //< integral limit
+  float outputLimit;  //< output limit
+  float dt;           //< delta-time dt
+  lpf2pData dFilter;  //< filter for D term
+  bool enableDFilter; //< filter for D term enable flag
+} PidObject;
+
+/**
+ * PID object initialization.
+ *
+ * @param[out] pid   A pointer to the pid object to initialize.
+ * @param[in] desired  The initial set point.
+ * @param[in] kp        The proportional gain
+ * @param[in] ki        The integral gain
+ * @param[in] kd        The derivative gain
+ * @param[in] dt        Delta time since the last call
+ * @param[in] samplingRate Frequency the update will be called
+ * @param[in] cutoffFreq   Frequency to set the low pass filter cutoff at
+ * @param[in] enableDFilter Enable setting for the D lowpass filter
+ */
+ void pidInit(PidObject* pid, const float desired, const float kp,
+              const float ki, const float kd, const float dt,
+              const float samplingRate, const float cutoffFreq,
+              bool enableDFilter);
+
+/**
+ * Set the integral limit for this PID in deg.
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] limit Pid integral swing limit.
+ */
+void pidSetIntegralLimit(PidObject* pid, const float limit);
+
+/**
+ * Reset the PID error values
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] limit Pid integral swing limit.
+ */
+void pidReset(PidObject* pid);
+
+/**
+ * Update the PID parameters.
+ *
+ * @param[in] pid         A pointer to the pid object.
+ * @param[in] measured    The measured value
+ * @param[in] updateError Set to TRUE if error should be calculated.
+ *                        Set to False if pidSetError() has been used.
+ * @return PID algorithm output
+ */
+float pidUpdate(PidObject* pid, const float measured, const bool updateError);
+
+/**
+ * Set a new set point for the PID to track.
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] angle The new set point
+ */
+void pidSetDesired(PidObject* pid, const float desired);
+
+/**
+ * Set a new set point for the PID to track.
+ * @return The set point
+ */
+float pidGetDesired(PidObject* pid);
+
+/**
+ * Find out if PID is active
+ * @return TRUE if active, FALSE otherwise
+ */
+bool pidIsActive(PidObject* pid);
+
+/**
+ * Set a new error. Use if a special error calculation is needed.
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] error The new error
+ */
+void pidSetError(PidObject* pid, const float error);
+
+/**
+ * Set a new proportional gain for the PID.
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] kp    The new proportional gain
+ */
+void pidSetKp(PidObject* pid, const float kp);
+
+/**
+ * Set a new integral gain for the PID.
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] ki    The new integral gain
+ */
+void pidSetKi(PidObject* pid, const float ki);
+
+/**
+ * Set a new derivative gain for the PID.
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] kd    The derivative gain
+ */
+void pidSetKd(PidObject* pid, const float kd);
+
+/**
+ * Set a new dt gain for the PID. Defaults to IMU_UPDATE_DT upon construction
+ *
+ * @param[in] pid   A pointer to the pid object.
+ * @param[in] dt    Delta time
+ */
+void pidSetDt(PidObject* pid, const float dt);
+#endif /* PID_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/pidctrl.h b/crazyflie-firmware-src/src/modules/interface/pidctrl.h
new file mode 100644
index 0000000000000000000000000000000000000000..3b49e7c94cac1f6303a24dde71781180ae96e5bb
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/pidctrl.h
@@ -0,0 +1,32 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * pidtctrl.h - Used to receive/answer requests from client and to receive updated PID values from client
+ */
+#include "crtp.h"
+
+/**
+ * Initialize the PID control task
+ */
+void pidCtrlInit();
+
diff --git a/crazyflie-firmware-src/src/modules/interface/platformservice.h b/crazyflie-firmware-src/src/modules/interface/platformservice.h
new file mode 100644
index 0000000000000000000000000000000000000000..0d7a5c2e3fcb3005645b091ea47d972a08bc11c9
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/platformservice.h
@@ -0,0 +1,40 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * platformservice.h - Used to send platform commands
+ */
+
+#ifndef __PLATFORMSERVICE_H__
+#define __PLATFORMSERVICE_H__
+
+#include <stdbool.h>
+
+/**
+ * Initialize the platform CRTP port
+ */
+void platformserviceInit(void);
+
+bool platformserviceTest(void);
+
+#endif /* __PLATFORMSERVICE_H__ */
+
diff --git a/crazyflie-firmware-src/src/modules/interface/position_controller.h b/crazyflie-firmware-src/src/modules/interface/position_controller.h
new file mode 100644
index 0000000000000000000000000000000000000000..b6655f8a16c43073c76233c2e26d470fceaba601
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/position_controller.h
@@ -0,0 +1,40 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ */
+#ifndef POSITION_CONTROLLER_H_
+#define POSITION_CONTROLLER_H_
+
+#include "stabilizer_types.h"
+
+// A position controller calculate the thrust, roll, pitch to approach
+// a 3D position setpoint
+void positionControllerInit();
+void positionControllerResetAllPID();
+void positionController(float* thrust, attitude_t *attitude, setpoint_t *setpoint,
+                                                             const state_t *state);
+void velocityController(float* thrust, attitude_t *attitude, setpoint_t *setpoint,
+                                                             const state_t *state);
+
+#endif /* POSITION_CONTROLLER_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/position_estimator.h b/crazyflie-firmware-src/src/modules/interface/position_estimator.h
new file mode 100644
index 0000000000000000000000000000000000000000..87af8e55524e3278743dbccebfe21d31f3638513
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/position_estimator.h
@@ -0,0 +1,34 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ */
+#ifndef POSITION_ESTIMATOR_H_
+#define POSITION_ESTIMATOR_H_
+
+#include "stabilizer_types.h"
+
+void positionEstimate(state_t* estimate, float asl, float dt);
+void positionUpdateVelocity(float accWZ, float dt);
+
+#endif /* POSITION_ESTIMATOR_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/power_distribution.h b/crazyflie-firmware-src/src/modules/interface/power_distribution.h
new file mode 100644
index 0000000000000000000000000000000000000000..0cd4e8be0d55136709cbfdfbe4e8b6948cda9207
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/power_distribution.h
@@ -0,0 +1,36 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * power_distribution.h - Interface to stabilizer power distribution
+ */
+#ifndef __POWER_DISTRIBUTION_H__
+#define __POWER_DISTRIBUTION_H__
+
+#include "stabilizer_types.h"
+
+void powerDistributionInit(void);
+bool powerDistributionTest(void);
+void powerDistribution(const control_t *control);
+
+
+#endif //__POWER_DISTRIBUTION_H__
diff --git a/crazyflie-firmware-src/src/modules/interface/queuemonitor.h b/crazyflie-firmware-src/src/modules/interface/queuemonitor.h
new file mode 100644
index 0000000000000000000000000000000000000000..5018e53d8c53149868f3f1a8c6b99a9b345071b1
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/queuemonitor.h
@@ -0,0 +1,46 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * log.h - Dynamic log system
+ */
+
+#ifndef __QUEUE_MONITOR_H__
+#define __QUEUE_MONITOR_H__
+
+
+#include "FreeRTOS.h"
+
+#ifdef DEBUG_QUEUE_MONITOR
+  #include "queue.h"
+
+  void queueMonitorInit();
+  #define DEBUG_QUEUE_MONITOR_REGISTER(queue) qmRegisterQueue(queue, __FILE__, #queue)
+
+  void qm_traceQUEUE_SEND(void* xQueue);
+  void qm_traceQUEUE_SEND_FAILED(void* xQueue);
+  void qmRegisterQueue(xQueueHandle* xQueue, char* fileName, char* queueName);
+#else
+  #define DEBUG_QUEUE_MONITOR_REGISTER(queue)
+#endif // DEBUG_QUEUE_MONITOR
+
+#endif // __QUEUE_MONITOR_H__
\ No newline at end of file
diff --git a/crazyflie-firmware-src/src/modules/interface/sensfusion6.h b/crazyflie-firmware-src/src/modules/interface/sensfusion6.h
new file mode 100644
index 0000000000000000000000000000000000000000..0ac15895b2b7c8fc6fde8e0ec6966f8a5d040b52
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/sensfusion6.h
@@ -0,0 +1,38 @@
+/**
+ *    ||          ____  _ __  ______
+ * +------+      / __ )(_) /_/ ____/_________ _____  ___
+ * | 0xBC |     / __  / / __/ /    / ___/ __ `/_  / / _	\
+ * +------+    / /_/ / / /_/ /___ / /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\____//_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ */
+
+#ifndef SENSORFUSION6_H_
+#define SENSORFUSION6_H_
+#include <stdbool.h>
+
+void sensfusion6Init(void);
+bool sensfusion6Test(void);
+
+void sensfusion6UpdateQ(float gx, float gy, float gz, float ax, float ay, float az, float dt);
+void sensfusion6GetEulerRPY(float* roll, float* pitch, float* yaw);
+float sensfusion6GetAccZWithoutGravity(const float ax, const float ay, const float az);
+float sensfusion6GetInvThrustCompensationForTilt();
+
+#endif /* SENSORFUSION6_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/sitaw.h b/crazyflie-firmware-src/src/modules/interface/sitaw.h
new file mode 100644
index 0000000000000000000000000000000000000000..42df88928b3235a63e4861ef5c5f60017397b79a
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/sitaw.h
@@ -0,0 +1,72 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sitaw.h - Interface to situation awareness.
+ */
+
+#ifndef __SITAW_H__
+#define __SITAW_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "stabilizer_types.h"
+
+bool sitAwFFTest(float accWZ, float accMag);
+bool sitAwFFDetected(void);
+bool sitAwARTest(float accX, float accY, float accZ);
+bool sitAwARDetected(void);
+bool sitAwTuTest(float eulerRollActual, float eulerPitchActual);
+bool sitAwTuDetected(void);
+void sitAwInit(void);
+void sitAwUpdateSetpoint(setpoint_t *setpoint, const sensorData_t *sensorData,
+                                               const state_t *state);
+/* Enable the situation awareness framework. */
+//#define SITAW_ENABLED
+
+/* Configuration options for the 'Free Fall' detection. */
+#define SITAW_FF_THRESHOLD 0.1     /* The default tolerance for AccWZ deviations from -1, indicating Free Fall. */
+#define SITAW_FF_TRIGGER_COUNT 15  /* The number of consecutive tests for Free Fall to be detected. Configured for 250Hz testing. */
+
+/* Configuration options for the 'At Rest' detection. */
+#define SITAW_AR_THRESHOLD 0.05    /* The default tolerance for AccZ deviations from 1 and AccX, AccY deviations from 0, indicating At Rest. */
+#define SITAW_AR_TRIGGER_COUNT 500 /* The number of consecutive tests for At Rest to be detected. Configured for 250Hz testing. */
+
+/* Configuration options for the 'Tumbled' detection. */
+#define SITAW_TU_THRESHOLD 60      /* The minimum roll angle indicating a Tumbled situation. */
+#define SITAW_TU_TRIGGER_COUNT 15  /* The number of consecutive tests for Tumbled to be detected. Configured for 250Hz testing. */
+
+/* LOG configurations. Enable these to be able to log detection in the cfclient. */
+#define SITAW_LOG_ENABLED            /* Uncomment to enable LOG framework. */
+//#define SITAW_FF_LOG_ENABLED       /* Uncomment to enable LOG framework for the Free Fall detection trigger object. */
+//#define SITAW_AR_LOG_ENABLED       /* Uncomment to enable LOG framework for the At Rest detection trigger object. */
+//#define SITAW_TU_LOG_ENABLED       /* Uncomment to enable LOG framework for the Tumbled detection trigger object. */
+#define SITAW_LOG_ALL_DETECT_ENABLED /* Uncomment to enable LOG framework for all 'Detected' flags. */
+
+/* PARAM configurations. Enable these to be able to tweak detection configurations from the cfclient. */
+//#define SITAW_PARAM_ENABLED        /* Uncomment to enable PARAM framework. */
+//#define SITAW_FF_PARAM_ENABLED     /* Uncomment to enable PARAM framework for the Free Fall detection. */
+//#define SITAW_AR_PARAM_ENABLED     /* Uncomment to enable PARAM framework for the At Rest detection. */
+//#define SITAW_TU_PARAM_ENABLED     /* Uncomment to enable PARAM framework for the Tumbled detection. */
+
+#endif
diff --git a/crazyflie-firmware-src/src/modules/interface/sound.h b/crazyflie-firmware-src/src/modules/interface/sound.h
new file mode 100644
index 0000000000000000000000000000000000000000..79d5d649307ff4575518815f46a0ad02cecfe6c7
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/sound.h
@@ -0,0 +1,63 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sound.h - Module used to play melodies and system sounds though a buzzer
+ */
+
+#ifndef __SOUND_H__
+#define __SOUND_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+#define SND_OFF         0
+#define FACTORY_TEST    1
+#define SND_USB_DISC    2
+#define SND_USB_CONN    3
+#define SND_BAT_FULL    4
+#define SND_BAT_LOW     5
+#define SND_STARTUP     6
+#define SND_CALIB       7
+
+/**
+ * Initialize sound sub-system.
+ */
+void soundInit(void);
+
+/**
+ * Test the sound sub-system.
+ */
+bool soundTest(void);
+
+/**
+ * Set the effect that should be played by the sound sub-system.
+ */
+void soundSetEffect(uint32_t effect);
+
+/**
+ * Manufally set a frequency that should be played by the sound syb-system.
+ */
+void soundSetFreq(uint32_t freq);
+
+#endif /* __SOUND_H__ */
+
diff --git a/crazyflie-firmware-src/src/modules/interface/stabilizer.h b/crazyflie-firmware-src/src/modules/interface/stabilizer.h
new file mode 100644
index 0000000000000000000000000000000000000000..96537c18cd293cbb2863e3a5c679cf8a2df22a93
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/stabilizer.h
@@ -0,0 +1,37 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * stabilizer.h: Stabilizer orchestrator
+ */
+#ifndef STABALIZER_H_
+#define STABALIZER_H_
+
+#include <stdbool.h>
+#include <stdint.h>
+
+void stabilizerInit(void);
+
+bool stabilizerTest(void);
+
+
+#endif /* STABALIZER_H_ */
diff --git a/crazyflie-firmware-src/src/modules/interface/stabilizer_types.h b/crazyflie-firmware-src/src/modules/interface/stabilizer_types.h
new file mode 100644
index 0000000000000000000000000000000000000000..7b20c53e87ed0e400ca50b88b7244b69df6b395b
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/stabilizer_types.h
@@ -0,0 +1,224 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * stabilizer.h: Stabilizer orchestrator
+ */
+#ifndef __STABILIZER_TYPES_H__
+#define __STABILIZER_TYPES_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "imu_types.h"
+
+#ifndef SPMODE
+#define modeRate 0
+#define modeAngle 1
+#define modeMotorCmd 2
+#endif
+
+/* Data structure used by the stabilizer subsystem.
+ * All have a timestamp to be set when the data is calculated.
+ */
+
+/** Attitude in euler angle form */
+typedef struct attitude_s {
+  uint32_t timestamp;  // Timestamp when the data was computed
+
+  float roll;
+  float pitch;
+  float yaw;
+} attitude_t;
+
+/* x,y,z vector */
+struct vec3_s {
+  uint32_t timestamp; // Timestamp when the data was computed
+
+  float x;
+  float y;
+  float z;
+};
+
+typedef struct vec3_s point_t;
+typedef struct vec3_s velocity_t;
+typedef struct vec3_s acc_t;
+
+/* Orientation as a quaternion */
+typedef struct quaternion_s {
+  uint32_t timestamp;
+
+  union {
+    struct {
+      float q0;
+      float q1;
+      float q2;
+      float q3;
+    };
+    struct {
+      float x;
+      float y;
+      float z;
+      float w;
+    };
+  };
+} quaternion_t;
+
+typedef struct tdoaMeasurement_s {
+  point_t anchorPosition[2];
+  float distanceDiff;
+  float timeBetweenMeasurements;
+  float stdDev;
+} tdoaMeasurement_t;
+
+typedef struct baro_s {
+  float pressure;
+  float temperature;
+  float asl;
+} baro_t;
+
+typedef struct positionMeasurement_s {
+  union {
+    struct {
+      float x;
+      float y;
+      float z;
+    };
+    float pos[3];
+  };
+  float stdDev;
+} positionMeasurement_t;
+
+typedef struct distanceMeasurement_s {
+  union {
+    struct {
+      float x;
+      float y;
+      float z;
+    };
+    float pos[3];
+  };
+  float distance;
+  float stdDev;
+} distanceMeasurement_t;
+
+typedef struct sensorData_s {
+  Axis3f acc;
+  Axis3f gyro;
+  Axis3f mag;
+  baro_t baro;
+  point_t position;
+} sensorData_t;
+
+typedef struct state_s {
+  attitude_t attitude;
+  quaternion_t attitudeQuaternion;
+  point_t position;
+  velocity_t velocity;
+  acc_t acc;
+} state_t;
+
+typedef struct control_s {
+  int16_t roll;
+  int16_t pitch;
+  int16_t yaw;
+  float thrust;
+  uint16_t cmd1;
+  uint16_t cmd2;
+  uint16_t cmd3;
+  uint16_t cmd4;
+} control_t;
+
+typedef enum mode_e {
+  modeDisable = 0,
+  modeAbs,
+  modeVelocity
+} mode_t;
+
+
+//typedef enum SPtype_e {
+//	modeRate=0,
+//	modeAngle=1,
+//	modeMotorCmd=2
+//} SPtype_t;
+
+
+typedef struct setpoint_s {
+  attitude_t attitude;
+  attitude_t attitudeRate;
+  float thrust;
+  point_t position;
+  velocity_t velocity;
+
+  struct {
+    mode_t x;
+    mode_t y;
+    mode_t z;
+    mode_t roll;
+    mode_t pitch;
+    mode_t yaw;
+  } mode;
+  
+  uint16_t SPtype;
+  
+  uint16_t cmd[4];
+} setpoint_t;
+
+/** Estimate of position */
+typedef struct estimate_s {
+  uint32_t timestamp; // Timestamp when the data was computed
+
+  point_t position;
+} estimate_t;
+
+/** Setpoint for althold */
+typedef struct setpointZ_s {
+  float z;
+  bool isUpdate; // True = small update of setpoint, false = completely new
+} setpointZ_t;
+
+/** TOF measurement**/
+typedef struct tofMeasurement_s {
+  uint32_t timestamp;
+  float distance;
+  float stdDev;
+} tofMeasurement_t;
+
+// Frequencies to bo used with the RATE_DO_EXECUTE_HZ macro. Do NOT use an arbitrary number.
+#define RATE_1000_HZ 1000
+#define RATE_500_HZ 500
+#define RATE_250_HZ 250
+#define RATE_100_HZ 100
+#define RATE_50_HZ 50
+#define RATE_25_HZ 25
+
+#ifdef ESTIMATOR_TYPE_kalman
+#define RATE_MAIN_LOOP RATE_1000_HZ
+#else
+#define RATE_MAIN_LOOP RATE_1000_HZ
+#endif
+
+#define ATTITUDE_RATE RATE_500_HZ
+#define POSITION_RATE RATE_100_HZ
+
+#define RATE_DO_EXECUTE(RATE_HZ, TICK) ((TICK % (RATE_MAIN_LOOP / RATE_HZ)) == 0)
+
+#endif
diff --git a/crazyflie-firmware-src/src/modules/interface/system.h b/crazyflie-firmware-src/src/modules/interface/system.h
new file mode 100644
index 0000000000000000000000000000000000000000..b69bcd6e83dd7a48b44cf00b0e249b7b77e95e8b
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/system.h
@@ -0,0 +1,43 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * system.h - Top level module header file
+ */
+
+#ifndef __SYSTEM_H__
+#define __SYSTEM_H__
+
+#include <stdint.h>
+
+void systemInit(void);
+bool systemTest(void);
+
+void systemLaunch(void);
+
+
+void systemStart();
+void systemWaitStart(void);
+void systemSetCanFly(bool val);
+bool systemCanFly(void);
+
+#endif //__SYSTEM_H__
diff --git a/crazyflie-firmware-src/src/modules/interface/trigger.h b/crazyflie-firmware-src/src/modules/interface/trigger.h
new file mode 100644
index 0000000000000000000000000000000000000000..2ce10745ca4a683b4a53ce72c6d4ef70627e8af8
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/trigger.h
@@ -0,0 +1,69 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * trigger.h - Interface to trigger mechanism.
+ */
+
+#ifndef __TRIGGER_H__
+#define __TRIGGER_H__
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/* Trigger function type. */
+typedef enum {
+  triggerFuncNone   = 0, /* No trigger function. */
+  triggerFuncIsLE   = 1, /* Increases testCounter if test value is Less than or Equal to threshold value. */
+  triggerFuncIsGE   = 2, /* Increases testCounter if test value is Greater than or Equal to threshold value. */
+} triggerFunc_t;
+
+/* Trigger handler function type. */
+typedef void (*triggerHandler_t)(void *);
+
+/**
+ * Trigger object.
+ *
+ * This object is published here so that users may investigate the testCounter and released attributes
+ * during debugging. Such attributes can for instance be passed through the LOG framework.
+ */
+typedef struct {
+    bool active;              /* Indicates if the trigger is active or not. */
+    triggerFunc_t func;       /* The trigger function type. */
+    float threshold;          /* The threshold the test value is compared against using the trigger function. */
+    uint32_t triggerCount;    /* When testCounter reaches this value, a trigger is released. */
+    triggerHandler_t handler; /* If registered, the handler function is called when the trigger is released. */
+    bool handlerCalled;       /* Indicates if the handler has been called. The handler is only called once after the trigger is released. */
+    void *handlerArg;         /* The argument to pass to the handler function. */
+    uint32_t testCounter;     /* As long as smaller than triggerCount, this counter is incremented for each consecutive test the tested value is within the threshold. */
+    bool released;            /* Indicates if the trigger has been released (true) or not (false). */
+} trigger_t;
+
+/* Trigger functionality. */
+void triggerInit(trigger_t *trigger, triggerFunc_t func, float threshold, uint32_t triggerCount);
+void triggerRegisterHandler(trigger_t *trigger, triggerHandler_t handler, void *handlerArg);
+void triggerDeInit(trigger_t *trigger);
+void triggerActivate(trigger_t *trigger, bool active);
+void triggerReset(trigger_t *trigger);
+bool triggerTestValue(trigger_t *trigger, float testValue);
+
+#endif
diff --git a/crazyflie-firmware-src/src/modules/interface/worker.h b/crazyflie-firmware-src/src/modules/interface/worker.h
new file mode 100644
index 0000000000000000000000000000000000000000..63d5dba360f74b196fda072e96bb744c385aa379
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/interface/worker.h
@@ -0,0 +1,54 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * worker.h - Worker system that can execute asynchronous actions in tasks
+ */
+#ifndef __WORKER_H
+#define __WORKER_H
+
+#include <stdbool.h>
+
+void workerInit();
+
+bool workerTest();
+
+/**
+ * Light printf implementation
+ *
+ * This function exectute the worker loop and never returns except if the worker
+ * module has not been initialized.
+ */
+void workerLoop();
+
+/**
+ * Schedule a function for execution by the worker loop
+ * The function will be executed as soon as possible by the worker loop.
+ * Scheduled functions are stacked in a FIFO queue.
+ *
+ * @param function Function to be executed
+ * @param arg      Argument that will be passed to the function when executed
+ * @return         0 in case of success. Anything else on failure.
+ */
+int workerSchedule(void (*function)(void*), void *arg);
+
+#endif //__WORKER_H
diff --git a/crazyflie-firmware-src/src/modules/src/attitude_pid_controller.c b/crazyflie-firmware-src/src/modules/src/attitude_pid_controller.c
new file mode 100644
index 0000000000000000000000000000000000000000..860923b391ce57ae677e6a88275ccb13ce33b0e9
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/attitude_pid_controller.c
@@ -0,0 +1,215 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * attitude_pid_controller.c: Attitude controler using PID correctors
+ */
+#include <stdbool.h>
+
+#include "FreeRTOS.h"
+
+#include "attitude_controller.h"
+#include "pid.h"
+#include "param.h"
+#include "log.h"
+
+#define ATTITUDE_LPF_CUTOFF_FREQ      15.0f
+#define ATTITUDE_LPF_ENABLE false
+#define ATTITUDE_RATE_LPF_CUTOFF_FREQ 30.0f
+#define ATTITUDE_RATE_LPF_ENABLE false
+
+
+static inline int16_t saturateSignedInt16(float in)
+{
+  // don't use INT16_MIN, because later we may negate it, which won't work for that value.
+  if (in > INT16_MAX)
+    return INT16_MAX;
+  else if (in < -INT16_MAX)
+    return -INT16_MAX;
+  else
+    return (int16_t)in;
+}
+
+PidObject pidRollRate;
+PidObject pidPitchRate;
+PidObject pidYawRate;
+PidObject pidRoll;
+PidObject pidPitch;
+PidObject pidYaw;
+
+static int16_t rollOutput;
+static int16_t pitchOutput;
+static int16_t yawOutput;
+
+static float rpRateLimit  = 150.0f;
+static float yawRateLimit = 150.0f;
+static float rpyRateLimitOverhead = 1.1f;
+
+static bool isInit;
+
+void attitudeControllerInit(const float updateDt)
+{
+  if(isInit)
+    return;
+
+  //TODO: get parameters from configuration manager instead
+  pidInit(&pidRollRate,  0, PID_ROLL_RATE_KP,  PID_ROLL_RATE_KI,  PID_ROLL_RATE_KD,
+      updateDt, ATTITUDE_RATE, ATTITUDE_RATE_LPF_CUTOFF_FREQ, ATTITUDE_RATE_LPF_ENABLE);
+  pidInit(&pidPitchRate, 0, PID_PITCH_RATE_KP, PID_PITCH_RATE_KI, PID_PITCH_RATE_KD,
+      updateDt, ATTITUDE_RATE, ATTITUDE_RATE_LPF_CUTOFF_FREQ, ATTITUDE_RATE_LPF_ENABLE);
+  pidInit(&pidYawRate,   0, PID_YAW_RATE_KP,   PID_YAW_RATE_KI,   PID_YAW_RATE_KD,
+      updateDt, ATTITUDE_RATE, ATTITUDE_RATE_LPF_CUTOFF_FREQ, ATTITUDE_RATE_LPF_ENABLE);
+
+  pidSetIntegralLimit(&pidRollRate,  PID_ROLL_RATE_INTEGRATION_LIMIT);
+  pidSetIntegralLimit(&pidPitchRate, PID_PITCH_RATE_INTEGRATION_LIMIT);
+  pidSetIntegralLimit(&pidYawRate,   PID_YAW_RATE_INTEGRATION_LIMIT);
+
+  pidInit(&pidRoll,  0, PID_ROLL_KP,  PID_ROLL_KI,  PID_ROLL_KD,  updateDt,
+      ATTITUDE_RATE, ATTITUDE_LPF_CUTOFF_FREQ, ATTITUDE_LPF_ENABLE);
+  pidInit(&pidPitch, 0, PID_PITCH_KP, PID_PITCH_KI, PID_PITCH_KD, updateDt,
+      ATTITUDE_RATE, ATTITUDE_LPF_CUTOFF_FREQ, ATTITUDE_LPF_ENABLE);
+  pidInit(&pidYaw,   0, PID_YAW_KP,   PID_YAW_KI,   PID_YAW_KD,   updateDt,
+      ATTITUDE_RATE, ATTITUDE_LPF_CUTOFF_FREQ, ATTITUDE_LPF_ENABLE);
+
+  pidSetIntegralLimit(&pidRoll,  PID_ROLL_INTEGRATION_LIMIT);
+  pidSetIntegralLimit(&pidPitch, PID_PITCH_INTEGRATION_LIMIT);
+  pidSetIntegralLimit(&pidYaw,   PID_YAW_INTEGRATION_LIMIT);
+
+  pidRollRate.outputLimit  = INT16_MAX;
+  pidPitchRate.outputLimit = INT16_MAX;
+  pidYawRate.outputLimit   = INT16_MAX;
+
+  isInit = true;
+}
+
+bool attitudeControllerTest()
+{
+  return isInit;
+}
+
+void attitudeControllerCorrectRatePID(
+       float rollRateActual, float pitchRateActual, float yawRateActual,
+       float rollRateDesired, float pitchRateDesired, float yawRateDesired)
+{
+  pidSetDesired(&pidRollRate, rollRateDesired);
+  rollOutput = saturateSignedInt16(pidUpdate(&pidRollRate, rollRateActual, true));
+
+  pidSetDesired(&pidPitchRate, pitchRateDesired);
+  pitchOutput = saturateSignedInt16(pidUpdate(&pidPitchRate, pitchRateActual, true));
+
+  pidSetDesired(&pidYawRate, yawRateDesired);
+  yawOutput = saturateSignedInt16(pidUpdate(&pidYawRate, yawRateActual, true));
+}
+
+void attitudeControllerCorrectAttitudePID(
+       float eulerRollActual, float eulerPitchActual, float eulerYawActual,
+       float eulerRollDesired, float eulerPitchDesired, float eulerYawDesired,
+       float* rollRateDesired, float* pitchRateDesired, float* yawRateDesired)
+{
+  pidRoll.outputLimit  = rpRateLimit  * rpyRateLimitOverhead;
+  pidPitch.outputLimit = rpRateLimit  * rpyRateLimitOverhead;
+  pidYaw.outputLimit   = yawRateLimit * rpyRateLimitOverhead;
+
+  pidSetDesired(&pidRoll, eulerRollDesired);
+  *rollRateDesired = pidUpdate(&pidRoll, eulerRollActual, true);
+
+  // Update PID for pitch axis
+  pidSetDesired(&pidPitch, eulerPitchDesired);
+  *pitchRateDesired = pidUpdate(&pidPitch, eulerPitchActual, true);
+
+  // Update PID for yaw axis
+  float yawError;
+  yawError = eulerYawDesired - eulerYawActual;
+  if (yawError > 180.0)
+    yawError -= 360.0;
+  else if (yawError < -180.0)
+    yawError += 360.0;
+  pidSetError(&pidYaw, yawError);
+  *yawRateDesired = pidUpdate(&pidYaw, eulerYawActual, false);
+}
+
+void attitudeControllerResetAllPID(void)
+{
+  pidReset(&pidRoll);
+  pidReset(&pidPitch);
+  pidReset(&pidYaw);
+  pidReset(&pidRollRate);
+  pidReset(&pidPitchRate);
+  pidReset(&pidYawRate);
+}
+
+void attitudeControllerGetActuatorOutput(int16_t* roll, int16_t* pitch, int16_t* yaw)
+{
+  *roll = rollOutput;
+  *pitch = pitchOutput;
+  *yaw = yawOutput;
+}
+
+LOG_GROUP_START(pid_attitude)
+LOG_ADD(LOG_FLOAT, roll_outP, &pidRoll.outP)
+LOG_ADD(LOG_FLOAT, roll_outI, &pidRoll.outI)
+LOG_ADD(LOG_FLOAT, roll_outD, &pidRoll.outD)
+LOG_ADD(LOG_FLOAT, pitch_outP, &pidPitch.outP)
+LOG_ADD(LOG_FLOAT, pitch_outI, &pidPitch.outI)
+LOG_ADD(LOG_FLOAT, pitch_outD, &pidPitch.outD)
+LOG_ADD(LOG_FLOAT, yaw_outP, &pidYaw.outP)
+LOG_ADD(LOG_FLOAT, yaw_outI, &pidYaw.outI)
+LOG_ADD(LOG_FLOAT, yaw_outD, &pidYaw.outD)
+LOG_GROUP_STOP(pid_attitude)
+
+LOG_GROUP_START(pid_rate)
+LOG_ADD(LOG_FLOAT, roll_outP, &pidRollRate.outP)
+LOG_ADD(LOG_FLOAT, roll_outI, &pidRollRate.outI)
+LOG_ADD(LOG_FLOAT, roll_outD, &pidRollRate.outD)
+LOG_ADD(LOG_FLOAT, pitch_outP, &pidPitchRate.outP)
+LOG_ADD(LOG_FLOAT, pitch_outI, &pidPitchRate.outI)
+LOG_ADD(LOG_FLOAT, pitch_outD, &pidPitchRate.outD)
+LOG_ADD(LOG_FLOAT, yaw_outP, &pidYawRate.outP)
+LOG_ADD(LOG_FLOAT, yaw_outI, &pidYawRate.outI)
+LOG_ADD(LOG_FLOAT, yaw_outD, &pidYawRate.outD)
+LOG_GROUP_STOP(pid_rate)
+
+PARAM_GROUP_START(pid_attitude)
+PARAM_ADD(PARAM_FLOAT, roll_kp, &pidRoll.kp)
+PARAM_ADD(PARAM_FLOAT, roll_ki, &pidRoll.ki)
+PARAM_ADD(PARAM_FLOAT, roll_kd, &pidRoll.kd)
+PARAM_ADD(PARAM_FLOAT, pitch_kp, &pidPitch.kp)
+PARAM_ADD(PARAM_FLOAT, pitch_ki, &pidPitch.ki)
+PARAM_ADD(PARAM_FLOAT, pitch_kd, &pidPitch.kd)
+PARAM_ADD(PARAM_FLOAT, yaw_kp, &pidYaw.kp)
+PARAM_ADD(PARAM_FLOAT, yaw_ki, &pidYaw.ki)
+PARAM_ADD(PARAM_FLOAT, yaw_kd, &pidYaw.kd)
+PARAM_GROUP_STOP(pid_attitude)
+
+PARAM_GROUP_START(pid_rate)
+PARAM_ADD(PARAM_FLOAT, rpRateLimit,  &rpRateLimit)
+PARAM_ADD(PARAM_FLOAT, yawRateLimit, &yawRateLimit)
+PARAM_ADD(PARAM_FLOAT, roll_kp, &pidRollRate.kp)
+PARAM_ADD(PARAM_FLOAT, roll_ki, &pidRollRate.ki)
+PARAM_ADD(PARAM_FLOAT, roll_kd, &pidRollRate.kd)
+PARAM_ADD(PARAM_FLOAT, pitch_kp, &pidPitchRate.kp)
+PARAM_ADD(PARAM_FLOAT, pitch_ki, &pidPitchRate.ki)
+PARAM_ADD(PARAM_FLOAT, pitch_kd, &pidPitchRate.kd)
+PARAM_ADD(PARAM_FLOAT, yaw_kp, &pidYawRate.kp)
+PARAM_ADD(PARAM_FLOAT, yaw_ki, &pidYawRate.ki)
+PARAM_ADD(PARAM_FLOAT, yaw_kd, &pidYawRate.kd)
+PARAM_GROUP_STOP(pid_rate)
diff --git a/crazyflie-firmware-src/src/modules/src/comm.c b/crazyflie-firmware-src/src/modules/src/comm.c
new file mode 100644
index 0000000000000000000000000000000000000000..d1f60efeb32a56cf042c7846251d405b5e780e7c
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/comm.c
@@ -0,0 +1,116 @@
+/*
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * comm.c - High level communication module
+ */
+
+#include <stdbool.h>
+
+#include "config.h"
+
+#include "nrf24link.h"
+#include "crtp.h"
+#include "console.h"
+#include "crtpservice.h"
+#include "param.h"
+#include "log.h"
+#include "eskylink.h"
+#include "uart_syslink.h"
+#include "radiolink.h"
+#include "nrf24link.h"
+#include "usblink.h"
+#include "platformservice.h"
+#include "syslink.h"
+
+static bool isInit;
+
+void commInit(void)
+{
+  if (isInit)
+    return;
+#ifdef PLATFORM_CF1
+  #ifdef USE_ESKYLINK
+    eskylinkInit();
+  #else
+    nrf24linkInit();
+  #endif
+#else
+  uartslkInit();
+  radiolinkInit();
+#endif
+
+  /* These functions are moved to be initialized early so
+   * that DEBUG_PRINT can be used early */
+  // crtpInit();
+  // consoleInit();
+
+#ifdef USE_RADIOLINK_CRTP
+  crtpSetLink(radiolinkGetLink());
+#elif defined(USE_ESKYLINK)
+  crtpSetLink(eskylinkGetLink());
+#else
+  crtpSetLink(nrf24linkGetLink());
+#endif
+
+  crtpserviceInit();
+#ifdef PLATFORM_CF2
+  platformserviceInit();
+#endif
+  logInit();
+  paramInit();
+  
+  //setup CRTP communication channel
+  //TODO: check for USB first and prefer USB over radio
+  //if (usbTest())
+  //  crtpSetLink(usbGetLink);
+  //else if(radiolinkTest())
+  //  crtpSetLink(radiolinkGetLink());
+  
+  isInit = true;
+}
+
+bool commTest(void)
+{
+  bool pass=isInit;
+  
+#ifdef PLATFORM_CF1
+  #ifdef USE_ESKYLINK
+    pass &= eskylinkTest();
+  #else
+    pass &= nrf24linkTest();
+  #endif
+#else
+  pass &= radiolinkTest();
+#endif
+  
+  pass &= crtpTest();
+  pass &= crtpserviceTest();
+#ifdef PLATFORM_CF2
+  pass &= platformserviceTest();
+#endif
+  pass &= consoleTest();
+  pass &= paramTest();
+  
+  return pass;
+}
+
diff --git a/crazyflie-firmware-src/src/modules/src/commander.c b/crazyflie-firmware-src/src/modules/src/commander.c
new file mode 100644
index 0000000000000000000000000000000000000000..4107614f7670e9b8c6321ea84cd2153b6cfb5fec
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/commander.c
@@ -0,0 +1,498 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ */
+#include <math.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "commander.h"
+#include "crtp.h"
+#include "configblock.h"
+#include "log.h"
+#include "param.h"
+#include "num.h"
+#include "debug.h"
+#include "ext_position.h"
+
+#include "power_distribution.h"
+#include "motors.h"
+
+
+
+#define MIN_THRUST  1000
+#define MAX_THRUST  60000
+
+/**
+ * Commander control data
+ */
+typedef struct
+{
+  struct CommanderCrtpValues targetVal[2];
+  bool activeSide;
+  uint32_t timestamp; // FreeRTOS ticks
+} CommanderCache;
+
+
+/**
+ * Stabilization modes for Roll, Pitch, Yaw.
+ */
+typedef enum
+{
+  RATE    = 0,
+  ANGLE   = 1,
+} RPYType;
+
+/**
+ * Yaw flight Modes
+ */
+typedef enum
+{
+  CAREFREE  = 0, // Yaw is locked to world coordinates thus heading stays the same when yaw rotates
+  PLUSMODE  = 1, // Plus-mode. Motor M1 is defined as front
+  XMODE     = 2, // X-mode. M1 & M4 are defined as front
+} YawModeType;
+
+static bool isInit;
+static CommanderCache crtpCache;
+static CommanderCache extrxCache;
+static CommanderCache* activeCache;
+
+static uint32_t lastUpdate;
+static bool isInactive;
+static bool thrustLocked;
+static bool altHoldMode = false;
+static bool posHoldMode = false;
+static bool posSetMode = false;
+
+static RPYType stabilizationModeRoll  = ANGLE; // Current stabilization type of roll (rate or angle)
+static RPYType stabilizationModePitch = ANGLE; // Current stabilization type of pitch (rate or angle)
+static RPYType stabilizationModeYaw   = RATE;  // Current stabilization type of yaw (rate or angle)
+
+static YawModeType yawMode = DEFAULT_YAW_MODE; // Yaw mode configuration
+static bool carefreeResetFront;             // Reset what is front in carefree mode
+
+static void commanderCrtpCB(CRTPPacket* pk);
+//static void commanderCacheSelectorUpdate(void);
+
+/* Private functions */
+//static void commanderSetActiveThrus t(uint16_t thrust)
+//{
+//  activeCache->targetVal[activeCache->activeSide].thrust = thrust;
+//}
+
+//static void commanderSetActiveRoll(float roll)
+//{
+//  activeCache->targetVal[activeCache->activeSide].roll = roll;
+//}
+//
+//static void commanderSetActivePitch(float pitch)
+//{
+//  activeCache->targetVal[activeCache->activeSide].pitch = pitch;
+//}
+//
+//static void commanderSetActiveYaw(float yaw)
+//{
+//  activeCache->targetVal[activeCache->activeSide].yaw = yaw;
+//}
+
+//static uint16_t commanderGetActiveThrust(void)
+//{
+//  commanderCacheSelectorUpdate();
+//  return activeCache->targetVal[activeCache->activeSide].thrust;
+//}
+
+static float commanderGetActiveRoll(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].roll;
+}
+
+static float commanderGetActivePitch(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].pitch;
+}
+
+static float commanderGetActiveYaw(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].yaw;
+}
+
+static uint16_t commanderGetActiveCmd1(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].cmd1;
+}
+
+static uint16_t commanderGetActiveCmd2(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].cmd2;
+}
+
+static uint16_t commanderGetActiveCmd3(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].cmd3;
+}
+
+static uint16_t commanderGetActiveCmd4(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].cmd4;
+}
+
+static uint16_t commanderGetActiveSPtype(void)
+{
+  return activeCache->targetVal[activeCache->activeSide].SPtype;
+}
+
+//static void commanderLevelRPY(void)
+//{
+//  commanderSetActiveRoll(0);
+//  commanderSetActivePitch(0);
+//  commanderSetActiveYaw(0);
+//}
+
+//static void commanderDropToGround(void)
+//{
+//  altHoldMode = false;
+//  commanderSetActiveThrust(0);
+//  commanderLevelRPY();
+//}
+
+//static void commanderCacheSelectorUpdate(void)
+//{
+//  uint32_t tickNow = xTaskGetTickCount();
+//
+//  /* Check inputs and prioritize. Extrx higher then crtp */
+//  if ((tickNow - extrxCache.timestamp) < COMMANDER_WDT_TIMEOUT_STABILIZE) {
+//    activeCache = &extrxCache;
+//  } else if ((tickNow - crtpCache.timestamp) < COMMANDER_WDT_TIMEOUT_STABILIZE) {
+//    activeCache = &crtpCache;
+//  } else if ((tickNow - extrxCache.timestamp) < COMMANDER_WDT_TIMEOUT_SHUTDOWN) {
+//    activeCache = &extrxCache;
+//    commanderLevelRPY();
+//  } else if ((tickNow - crtpCache.timestamp) < COMMANDER_WDT_TIMEOUT_SHUTDOWN) {
+//    activeCache = &crtpCache;
+//    commanderLevelRPY();
+//  } else {
+//    activeCache = &crtpCache;
+//    commanderDropToGround();
+//  }
+//}
+
+static void commanderCrtpCB(CRTPPacket* pk)
+{
+  crtpCache.targetVal[!crtpCache.activeSide] = *((struct CommanderCrtpValues*)pk->data);
+  crtpCache.activeSide = !crtpCache.activeSide;
+  crtpCache.timestamp = xTaskGetTickCount();
+
+  if (crtpCache.targetVal[crtpCache.activeSide].thrust == 0) {
+    thrustLocked = false;
+  }
+  
+  if(crtpCache.targetVal[crtpCache.activeSide].SPtype == modeMotorCmd)
+  {
+	    motorsSetRatio(MOTOR_M1, limitUint16(crtpCache.targetVal[crtpCache.activeSide].cmd1));
+	    motorsSetRatio(MOTOR_M2, limitUint16(crtpCache.targetVal[crtpCache.activeSide].cmd2));
+	    motorsSetRatio(MOTOR_M3, limitUint16(crtpCache.targetVal[crtpCache.activeSide].cmd3));
+	    motorsSetRatio(MOTOR_M4, limitUint16(crtpCache.targetVal[crtpCache.activeSide].cmd4));
+  }
+}
+
+/**
+ * Rotate Yaw so that the Crazyflie will change what is considered front.
+ *
+ * @param yawRad Amount of radians to rotate yaw.
+ */
+//static void rotateYaw(setpoint_t *setpoint, float yawRad)
+//{
+//  float cosy = cosf(yawRad);
+//  float siny = sinf(yawRad);
+//  float originalRoll = setpoint->attitude.roll;
+//  float originalPitch = setpoint->attitude.pitch;
+//
+//  setpoint->attitude.roll = originalRoll * cosy - originalPitch * siny;
+//  setpoint->attitude.pitch = originalPitch * cosy + originalRoll * siny;
+//}
+
+/**
+ * Yaw carefree mode means yaw will stay in world coordinates. So even though
+ * the Crazyflie rotates around the yaw, front will stay the same as when it started.
+ * This makes makes it a bit easier for beginners
+ */
+//static void rotateYawCarefree(setpoint_t *setpoint, const state_t *state, bool reset)
+//{
+//  static float carefreeFrontAngle;
+//
+//  if (reset) {
+//    carefreeFrontAngle = state->attitude.yaw;
+//  }
+//
+//  float yawRad = (state->attitude.yaw - carefreeFrontAngle) * (float)M_PI / 180;
+//  rotateYaw(setpoint, yawRad);
+//}
+
+/**
+ * Update Yaw according to current setting
+ */
+#ifdef PLATFORM_CF1
+static void yawModeUpdate(setpoint_t *setpoint, const state_t *state)
+{
+  switch (yawMode)
+  {
+    case CAREFREE:
+      rotateYawCarefree(setpoint, state, carefreeResetFront);
+      break;
+    case PLUSMODE:
+      // Default in plus mode. Do nothing
+      break;
+    case XMODE: // Fall through
+    default:
+      rotateYaw(setpoint, -45 * M_PI / 180);
+      break;
+  }
+}
+#else
+//static void yawModeUpdate(setpoint_t *setpoint, const state_t *state)
+//{
+//  switch (yawMode)
+//  {
+//    case CAREFREE:
+//      rotateYawCarefree(setpoint, state, carefreeResetFront);
+//      break;
+//    case PLUSMODE:
+//      rotateYaw(setpoint, 45 * M_PI / 180);
+//      break;
+//    case XMODE: // Fall through
+//    default:
+//      // Default in x-mode. Do nothing
+//      break;
+//  }
+//}
+#endif
+
+/* Public functions */
+void commanderInit(void)
+{
+  if(isInit) {
+    return;
+  }
+
+  crtpInit();
+  crtpRegisterPortCB(CRTP_PORT_SETPOINT, commanderCrtpCB);
+  //extPositionInit(); // Set callback for CRTP_PORT_POSITION
+
+  activeCache = &crtpCache;
+  lastUpdate = xTaskGetTickCount();
+  isInactive = true;
+  thrustLocked = true;
+  isInit = true;
+}
+
+bool commanderTest(void)
+{
+  crtpTest();
+  return isInit;
+}
+
+void commanderExtrxSet(const struct CommanderCrtpValues *val)
+{
+  extrxCache.targetVal[!extrxCache.activeSide] = *((struct CommanderCrtpValues*)val);
+  extrxCache.activeSide = !extrxCache.activeSide;
+  extrxCache.timestamp = xTaskGetTickCount();
+
+  if (extrxCache.targetVal[extrxCache.activeSide].thrust == 0) {
+    thrustLocked = false;
+  }
+}
+
+uint32_t commanderGetInactivityTime(void)
+{
+  return xTaskGetTickCount() - lastUpdate;
+}
+
+void commanderGetSetpoint(setpoint_t *setpoint, const state_t *state)
+{
+	
+	setpoint->SPtype=commanderGetActiveSPtype();
+	
+	setpoint->cmd[0]=commanderGetActiveCmd1();
+	setpoint->cmd[1]=commanderGetActiveCmd2();
+	setpoint->cmd[2]=commanderGetActiveCmd3();
+	setpoint->cmd[3]=commanderGetActiveCmd4();
+
+	
+	//we dont use position controller onboard
+	setpoint->mode.x=modeDisable;
+	setpoint->mode.y=modeDisable;
+	setpoint->mode.z=modeDisable;
+	setpoint->thrust=0;
+	setpoint->position.x=0;
+	setpoint->position.y=0;
+	setpoint->position.z=0;
+	setpoint->velocity.x=0;
+	setpoint->velocity.y=0;
+	setpoint->velocity.z=0;
+	
+	if(setpoint->SPtype==modeRate)
+	{
+		setpoint->mode.roll=modeVelocity;
+		setpoint->mode.pitch=modeVelocity;
+		setpoint->mode.yaw=modeVelocity;
+		
+		setpoint->attitude.roll=0;
+		setpoint->attitude.pitch=0;
+		setpoint->attitude.yaw=0;
+		
+		setpoint->attitudeRate.roll=commanderGetActiveRoll();
+		setpoint->attitudeRate.pitch=commanderGetActivePitch();
+		setpoint->attitudeRate.yaw=commanderGetActiveYaw();
+		
+	}
+	
+	if(setpoint->SPtype==modeAngle)
+	{
+		setpoint->mode.roll=modeAbs;
+		setpoint->mode.pitch=modeAbs;
+		setpoint->mode.yaw=modeAbs;
+		
+		setpoint->attitudeRate.roll=0;
+		setpoint->attitudeRate.pitch=0;
+		setpoint->attitudeRate.yaw=0;
+		
+		setpoint->attitude.roll=commanderGetActiveRoll();
+		setpoint->attitude.pitch=commanderGetActivePitch();
+		setpoint->attitude.yaw=commanderGetActiveYaw();
+	}
+	
+	if(setpoint->SPtype==modeMotorCmd)
+	{
+		setpoint->mode.roll=modeDisable;
+		setpoint->mode.pitch=modeDisable;
+		setpoint->mode.yaw=modeDisable;
+		
+		setpoint->attitude.roll=0;
+		setpoint->attitude.pitch=0;
+		setpoint->attitude.yaw=0;
+		setpoint->attitudeRate.roll=0;
+		setpoint->attitudeRate.pitch=0;
+		setpoint->attitudeRate.yaw=0;
+	
+		
+		
+	}
+	
+	
+	
+//  // Thrust
+//  uint16_t rawThrust = commanderGetActiveThrust();
+//
+//  if (thrustLocked || (rawThrust < MIN_THRUST)) {
+//    setpoint->thrust = 0;
+//  } else {
+//    setpoint->thrust = min(rawThrust, MAX_THRUST);
+//  }
+//
+//  if (altHoldMode) {
+//    setpoint->thrust = 0;
+//    setpoint->mode.z = modeVelocity;
+//
+//    setpoint->velocity.z = ((float) rawThrust - 32767.f) / 32767.f;
+//  } else {
+//    setpoint->mode.z = modeDisable;
+//  }
+//
+//  // roll/pitch
+//  if (posHoldMode) {
+//    setpoint->mode.x = modeVelocity;
+//    setpoint->mode.y = modeVelocity;
+//    setpoint->mode.roll = modeDisable;
+//    setpoint->mode.pitch = modeDisable;
+//
+//    setpoint->velocity.x = commanderGetActivePitch()/30.0f;
+//    setpoint->velocity.y = commanderGetActiveRoll()/30.0f;
+//    setpoint->attitude.roll  = 0;
+//    setpoint->attitude.pitch = 0;
+//  } else if (posSetMode && commanderGetActiveThrust() != 0) {
+//    setpoint->mode.x = modeAbs;
+//    setpoint->mode.y = modeAbs;
+//    setpoint->mode.z = modeAbs;
+//    setpoint->mode.roll = modeDisable;
+//    setpoint->mode.pitch = modeDisable;
+//    setpoint->mode.yaw = modeAbs;
+//
+//    setpoint->position.x = -commanderGetActivePitch();
+//    setpoint->position.y = commanderGetActiveRoll();
+//    setpoint->position.z = commanderGetActiveThrust()/1000.0f;
+//
+//    setpoint->attitude.roll  = 0;
+//    setpoint->attitude.pitch = 0;
+//    setpoint->attitude.yaw = commanderGetActiveYaw();
+//    setpoint->thrust = 0;
+//  } else {
+//    setpoint->mode.x = modeDisable;
+//    setpoint->mode.y = modeDisable;
+//
+//    if (stabilizationModeRoll == RATE) {
+//      setpoint->mode.roll = modeVelocity;
+//      setpoint->attitudeRate.roll = commanderGetActiveRoll();
+//      setpoint->attitude.roll = 0;
+//    } else {
+//      setpoint->mode.roll = modeAbs;
+//      setpoint->attitudeRate.roll = 0;
+//      setpoint->attitude.roll = commanderGetActiveRoll();
+//    }
+//
+//    if (stabilizationModePitch == RATE) {
+//      setpoint->mode.pitch = modeVelocity;
+//      setpoint->attitudeRate.pitch = commanderGetActivePitch();
+//      setpoint->attitude.pitch = 0;
+//    } else {
+//      setpoint->mode.pitch = modeAbs;
+//      setpoint->attitudeRate.pitch = 0;
+//      setpoint->attitude.pitch = commanderGetActivePitch();
+//    }
+//
+//    setpoint->velocity.x = 0;
+//    setpoint->velocity.y = 0;
+//  }
+//
+//  // Yaw
+//  if (!posSetMode) {
+//    setpoint->attitudeRate.yaw  = commanderGetActiveYaw();
+//    yawModeUpdate(setpoint, state);
+//
+//    setpoint->mode.yaw = modeVelocity;
+//  }
+}
+
+// Params for flight modes
+PARAM_GROUP_START(flightmode)
+PARAM_ADD(PARAM_UINT8, althold, &altHoldMode)
+PARAM_ADD(PARAM_UINT8, poshold, &posHoldMode)
+PARAM_ADD(PARAM_UINT8, posSet, &posSetMode)
+PARAM_ADD(PARAM_UINT8, yawMode, &yawMode)
+PARAM_ADD(PARAM_UINT8, yawRst, &carefreeResetFront)
+PARAM_ADD(PARAM_UINT8, stabModeRoll, &stabilizationModeRoll)
+PARAM_ADD(PARAM_UINT8, stabModePitch, &stabilizationModePitch)
+PARAM_ADD(PARAM_UINT8, stabModeYaw, &stabilizationModeYaw)
+PARAM_GROUP_STOP(flightmode)
diff --git a/crazyflie-firmware-src/src/modules/src/console.c b/crazyflie-firmware-src/src/modules/src/console.c
new file mode 100644
index 0000000000000000000000000000000000000000..e147742d822e255f45ec064b1d77f1bd53ea2497
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/console.c
@@ -0,0 +1,156 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * console.c - Used to send console data to client
+ */
+
+#include <stdbool.h>
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "semphr.h"
+
+#include "crtp.h"
+
+#ifdef STM32F40_41xxx
+#include "stm32f4xx.h"
+#else
+#include "stm32f10x.h"
+#ifndef SCB_ICSR_VECTACTIVE_Msk
+#define SCB_ICSR_VECTACTIVE_Msk 0x1FFUL
+#endif
+#endif
+
+CRTPPacket messageToPrint;
+xSemaphoreHandle synch = NULL;
+
+static const char fullMsg[] = "<F>\n";
+static bool isInit;
+
+/**
+ * Send the data to the client
+ * returns TRUE if successful otherwise FALSE
+ */
+static bool consoleSendMessage(void)
+{
+
+  if (crtpSendPacket(&messageToPrint) == pdTRUE)
+  {
+    messageToPrint.size = 0;
+  }
+  else
+  {
+    return false;
+  }
+
+  return true;
+}
+
+void consoleInit()
+{
+  if (isInit)
+    return;
+
+  messageToPrint.size = 0;
+  messageToPrint.header = CRTP_HEADER(CRTP_PORT_CONSOLE, 0);
+  vSemaphoreCreateBinary(synch);
+
+  isInit = true;
+}
+
+bool consoleTest(void)
+{
+  return isInit;
+}
+
+int consolePutchar(int ch)
+{
+  int i;
+  bool isInInterrupt = (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) != 0;
+
+  if (!isInit) {
+    return 0;
+  }
+
+  if (isInInterrupt) {
+    return consolePutcharFromISR(ch);
+  }
+
+  if (xSemaphoreTake(synch, portMAX_DELAY) == pdTRUE)
+  {
+    if (messageToPrint.size < CRTP_MAX_DATA_SIZE)
+    {
+      messageToPrint.data[messageToPrint.size] = (unsigned char)ch;
+      messageToPrint.size++;
+    }
+    if (ch == '\n' || messageToPrint.size >= CRTP_MAX_DATA_SIZE)
+    {
+      if (crtpGetFreeTxQueuePackets() == 1)
+      {
+        for (i = 0; i < sizeof(fullMsg) && (messageToPrint.size - i) > 0; i++)
+        {
+          messageToPrint.data[messageToPrint.size - i] =
+              (uint8_t)fullMsg[sizeof(fullMsg) - i - 1];
+        }
+      }
+      consoleSendMessage();
+    }
+    xSemaphoreGive(synch);
+  }
+
+  return (unsigned char)ch;
+}
+
+int consolePutcharFromISR(int ch) {
+  BaseType_t higherPriorityTaskWoken;
+
+  if (xSemaphoreTakeFromISR(synch, &higherPriorityTaskWoken) == pdTRUE) {
+    if (messageToPrint.size < CRTP_MAX_DATA_SIZE)
+    {
+      messageToPrint.data[messageToPrint.size] = (unsigned char)ch;
+      messageToPrint.size++;
+    }
+    xSemaphoreGiveFromISR(synch, &higherPriorityTaskWoken);
+  }
+
+  return ch;
+}
+
+int consolePuts(char *str)
+{
+  int ret = 0;
+
+  while(*str)
+    ret |= consolePutchar(*str++);
+
+  return ret;
+}
+
+void consoleFlush(void)
+{
+  if (xSemaphoreTake(synch, portMAX_DELAY) == pdTRUE)
+  {
+    consoleSendMessage();
+    xSemaphoreGive(synch);
+  }
+}
diff --git a/crazyflie-firmware-src/src/modules/src/controller_pid.c b/crazyflie-firmware-src/src/modules/src/controller_pid.c
new file mode 100644
index 0000000000000000000000000000000000000000..53551a80e750bd2df5448fdb6c658fa680617884
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/controller_pid.c
@@ -0,0 +1,158 @@
+
+#include "stabilizer.h"
+#include "stabilizer_types.h"
+
+#include "attitude_controller.h"
+#include "sensfusion6.h"
+#include "position_controller.h"
+
+#include "log.h"
+#include "param.h"
+
+#define ATTITUDE_UPDATE_DT    (float)(1.0f/ATTITUDE_RATE)
+
+static bool tiltCompensationEnabled = false;
+
+static attitude_t attitudeDesired;
+static attitude_t rateDesired;
+static float actuatorThrust;
+
+void stateControllerInit(void)
+{
+  attitudeControllerInit(ATTITUDE_UPDATE_DT);
+  positionControllerInit();
+}
+
+bool stateControllerTest(void)
+{
+  bool pass = true;
+
+  pass &= attitudeControllerTest();
+
+  return pass;
+}
+
+void stateController(control_t *control, setpoint_t *setpoint,
+                                         const sensorData_t *sensors,
+                                         const state_t *state,
+                                         const uint32_t tick)
+{
+  if (RATE_DO_EXECUTE(ATTITUDE_RATE, tick)) {
+    // Rate-controled YAW is moving YAW angle setpoint
+    if (setpoint->mode.yaw == modeVelocity) {
+       attitudeDesired.yaw -= setpoint->attitudeRate.yaw/500.0;
+      while (attitudeDesired.yaw > 180.0)
+        attitudeDesired.yaw -= 360.0;
+      while (attitudeDesired.yaw < -180.0)
+        attitudeDesired.yaw += 360.0;
+    } else {
+      attitudeDesired.yaw = setpoint->attitude.yaw;
+    }
+  }
+
+//  if (RATE_DO_EXECUTE(POSITION_RATE, tick)) {
+//    if (setpoint->mode.z == modeAbs) {
+//      positionController(&actuatorThrust, &attitudeDesired, setpoint, state);
+//    } else if (setpoint->mode.z == modeVelocity) {
+//      velocityController(&actuatorThrust, &attitudeDesired, setpoint, state);
+//    }
+//  }
+
+  if (RATE_DO_EXECUTE(ATTITUDE_RATE, tick)) {
+    // Switch between manual and automatic position control
+    if (setpoint->mode.z == modeDisable) {
+      actuatorThrust = setpoint->thrust;
+    }
+    if (setpoint->mode.x == modeDisable || setpoint->mode.y == modeDisable) {
+      attitudeDesired.roll = setpoint->attitude.roll;
+      attitudeDesired.pitch = setpoint->attitude.pitch;
+    }
+
+    attitudeControllerCorrectAttitudePID(state->attitude.roll, state->attitude.pitch, state->attitude.yaw,
+                                attitudeDesired.roll, attitudeDesired.pitch, attitudeDesired.yaw,
+                                &rateDesired.roll, &rateDesired.pitch, &rateDesired.yaw);
+
+    if (setpoint->mode.roll == modeVelocity) {
+      rateDesired.roll = setpoint->attitudeRate.roll;
+    }
+    if (setpoint->mode.pitch == modeVelocity) {
+      rateDesired.pitch = setpoint->attitudeRate.pitch;
+    }
+
+    // TODO: Investigate possibility to subtract gyro drift.
+    attitudeControllerCorrectRatePID(sensors->gyro.x, -sensors->gyro.y, sensors->gyro.z,
+                             rateDesired.roll, rateDesired.pitch, rateDesired.yaw);
+
+    attitudeControllerGetActuatorOutput(&control->roll,
+                                        &control->pitch,
+                                        &control->yaw);
+    
+    control->cmd1=setpoint->cmd[0];
+    control->cmd2=setpoint->cmd[1];
+    control->cmd3=setpoint->cmd[2];
+    control->cmd4=setpoint->cmd[3];
+
+    control->yaw = -control->yaw;
+  }
+
+//  if (tiltCompensationEnabled)
+//  {
+//    control->thrust = actuatorThrust / sensfusion6GetInvThrustCompensationForTilt();
+//  }
+//  else
+//  {
+//    control->thrust = actuatorThrust;
+//  }
+
+//  if (control->thrust == 0)
+//  {
+//    control->thrust = 0;
+//    control->roll = 0;
+//    control->pitch = 0;
+//    control->yaw = 0;
+//
+//    attitudeControllerResetAllPID();
+//    positionControllerResetAllPID();
+//
+//    // Reset the calculated YAW angle for rate control
+//    attitudeDesired.yaw = state->attitude.yaw;
+//  }
+  
+  if(setpoint->SPtype==modeMotorCmd)
+  {
+	      control->roll = 0;
+	      control->pitch = 0;
+	      control->yaw = 0;
+	      
+	      attitudeControllerResetAllPID();
+	      positionControllerResetAllPID();
+	      attitudeDesired.yaw = state->attitude.yaw;
+  }
+  
+  if(control->cmd1==0 && control->cmd2==0 && control->cmd3==0 && control->cmd4==0)
+  {
+	  control->roll=0;
+	  control->pitch=0;
+	  control->yaw=0;
+	  
+      attitudeControllerResetAllPID();
+      positionControllerResetAllPID();
+      attitudeDesired.yaw = state->attitude.yaw;
+	  
+  }
+}
+
+
+LOG_GROUP_START(controller)
+LOG_ADD(LOG_FLOAT, actuatorThrust, &actuatorThrust)
+LOG_ADD(LOG_FLOAT, roll,      &attitudeDesired.roll)
+LOG_ADD(LOG_FLOAT, pitch,     &attitudeDesired.pitch)
+LOG_ADD(LOG_FLOAT, yaw,       &attitudeDesired.yaw)
+LOG_ADD(LOG_FLOAT, rollRate,  &rateDesired.roll)
+LOG_ADD(LOG_FLOAT, pitchRate, &rateDesired.pitch)
+LOG_ADD(LOG_FLOAT, yawRate,   &rateDesired.yaw)
+LOG_GROUP_STOP(controller)
+
+PARAM_GROUP_START(controller)
+PARAM_ADD(PARAM_UINT8, tiltComp, &tiltCompensationEnabled)
+PARAM_GROUP_STOP(controller)
diff --git a/crazyflie-firmware-src/src/modules/src/crtp.c b/crazyflie-firmware-src/src/modules/src/crtp.c
new file mode 100644
index 0000000000000000000000000000000000000000..44110dd3da6a23403dd3f2b0774c965e6eee0948
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/crtp.c
@@ -0,0 +1,242 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * crtp.c - CrazyRealtimeTransferProtocol stack
+ */
+
+#include <stdbool.h>
+#include <errno.h>
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+#include "queue.h"
+
+#include "config.h"
+
+#include "crtp.h"
+#include "info.h"
+#include "cfassert.h"
+#include "queuemonitor.h"
+
+static bool isInit;
+
+static int nopFunc(void);
+static struct crtpLinkOperations nopLink = {
+  .setEnable         = (void*) nopFunc,
+  .sendPacket        = (void*) nopFunc,
+  .receivePacket     = (void*) nopFunc,
+}; 
+
+static struct crtpLinkOperations *link = &nopLink;
+
+static xQueueHandle  txQueue;
+
+#define CRTP_NBR_OF_PORTS 16
+#define CRTP_TX_QUEUE_SIZE 60
+#define CRTP_RX_QUEUE_SIZE 2
+
+static void crtpTxTask(void *param);
+static void crtpRxTask(void *param);
+
+static xQueueHandle queues[CRTP_NBR_OF_PORTS];
+static volatile CrtpCallback callbacks[CRTP_NBR_OF_PORTS];
+
+void crtpInit(void)
+{
+  if(isInit)
+    return;
+
+  txQueue = xQueueCreate(CRTP_TX_QUEUE_SIZE, sizeof(CRTPPacket));
+  DEBUG_QUEUE_MONITOR_REGISTER(txQueue);
+
+  xTaskCreate(crtpTxTask, CRTP_TX_TASK_NAME,
+              CRTP_TX_TASK_STACKSIZE, NULL, CRTP_TX_TASK_PRI, NULL);
+  xTaskCreate(crtpRxTask, CRTP_RX_TASK_NAME,
+              CRTP_RX_TASK_STACKSIZE, NULL, CRTP_RX_TASK_PRI, NULL);
+
+  /* Start Rx/Tx tasks */
+
+
+  isInit = true;
+}
+
+bool crtpTest(void)
+{
+  return isInit;
+}
+
+void crtpInitTaskQueue(CRTPPort portId)
+{
+  ASSERT(queues[portId] == NULL);
+  
+  queues[portId] = xQueueCreate(1, sizeof(CRTPPacket));
+  DEBUG_QUEUE_MONITOR_REGISTER(queues[portId]);
+}
+
+int crtpReceivePacket(CRTPPort portId, CRTPPacket *p)
+{
+  ASSERT(queues[portId]);
+  ASSERT(p);
+    
+  return xQueueReceive(queues[portId], p, 0);
+}
+
+int crtpReceivePacketBlock(CRTPPort portId, CRTPPacket *p)
+{
+  ASSERT(queues[portId]);
+  ASSERT(p);
+  
+  return xQueueReceive(queues[portId], p, portMAX_DELAY);
+}
+
+
+int crtpReceivePacketWait(CRTPPort portId, CRTPPacket *p, int wait)
+{
+  ASSERT(queues[portId]);
+  ASSERT(p);
+  
+  return xQueueReceive(queues[portId], p, M2T(wait));
+}
+
+int crtpGetFreeTxQueuePackets(void)
+{
+  return (CRTP_TX_QUEUE_SIZE - uxQueueMessagesWaiting(txQueue));
+}
+
+void crtpTxTask(void *param)
+{
+  CRTPPacket p;
+
+  while (true)
+  {
+    if (link != &nopLink)
+    {
+      if (xQueueReceive(txQueue, &p, portMAX_DELAY) == pdTRUE)
+      {
+        // Keep testing, if the link changes to USB it will go though
+        while (link->sendPacket(&p) == false)
+        {
+          // Relaxation time
+          vTaskDelay(M2T(10));
+        }
+      }
+    }
+    else
+    {
+      vTaskDelay(M2T(10));
+    }
+  }
+}
+
+void crtpRxTask(void *param)
+{
+  CRTPPacket p;
+  static unsigned int droppedPacket=0;
+
+  while (true)
+  {
+    if (link != &nopLink)
+    {
+      if (!link->receivePacket(&p))
+      {
+        if (queues[p.port])
+        {
+          // The queue is only 1 long, so if the last packet hasn't been processed, we just replace it
+          xQueueOverwrite(queues[p.port], &p); 
+        }
+        else
+        {
+          droppedPacket++;
+        }
+
+        if (callbacks[p.port])
+          callbacks[p.port](&p);  //Dangerous?
+      }
+    }
+    else
+    {
+      vTaskDelay(M2T(10));
+    }
+  }
+}
+
+void crtpRegisterPortCB(int port, CrtpCallback cb)
+{
+  if (port>CRTP_NBR_OF_PORTS)
+    return;
+  
+  callbacks[port] = cb;
+}
+
+int crtpSendPacket(CRTPPacket *p)
+{
+  ASSERT(p); 
+  ASSERT(p->size <= CRTP_MAX_DATA_SIZE);
+
+  return xQueueSend(txQueue, p, 0);
+}
+
+int crtpSendPacketBlock(CRTPPacket *p)
+{
+  ASSERT(p); 
+  ASSERT(p->size <= CRTP_MAX_DATA_SIZE);
+
+  return xQueueSend(txQueue, p, portMAX_DELAY);
+}
+
+int crtpReset(void)
+{
+  xQueueReset(txQueue);
+  if (link->reset) {
+    link->reset();
+  }
+
+  return 0;
+}
+
+bool crtpIsConnected(void)
+{
+  if (link->isConnected)
+    return link->isConnected();
+  return true;
+}
+
+void crtpSetLink(struct crtpLinkOperations * lk)
+{
+  if(link)
+    link->setEnable(false);
+
+  if (lk)
+    link = lk;
+  else
+    link = &nopLink;
+
+  link->setEnable(true);
+}
+
+static int nopFunc(void)
+{
+  return ENETDOWN;
+}
diff --git a/crazyflie-firmware-src/src/modules/src/crtpservice.c b/crazyflie-firmware-src/src/modules/src/crtpservice.c
new file mode 100644
index 0000000000000000000000000000000000000000..881d242f3d479eb52c9fe9b08d90df541cf8d4d3
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/crtpservice.c
@@ -0,0 +1,81 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * crtpservice.c - Implements low level services for CRTP
+ */
+
+#include <stdbool.h>
+#include <string.h>
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+
+#include "crtp.h"
+#include "crtpservice.h"
+
+static bool isInit=false;
+
+typedef enum {
+  linkEcho   = 0x00,
+  linkSource = 0x01,
+  linkSink   = 0x02,
+} LinkNbr;
+
+void crtpserviceHandler(CRTPPacket *p);
+
+void crtpserviceInit(void)
+{
+  if (isInit)
+    return;
+
+  // Register a callback to service the Link port
+  crtpRegisterPortCB(CRTP_PORT_LINK, crtpserviceHandler);
+
+  isInit = true;
+}
+
+bool crtpserviceTest(void)
+{
+  return isInit;
+}
+
+void crtpserviceHandler(CRTPPacket *p)
+{
+  switch (p->channel)
+  {
+    case linkEcho:
+      crtpSendPacket(p);
+      break;
+    case linkSource:
+      p->size = CRTP_MAX_DATA_SIZE;
+      bzero(p->data, CRTP_MAX_DATA_SIZE);
+      strcpy((char*)p->data, "Bitcraze Crazyflie");
+      crtpSendPacket(p);
+      break;
+    case linkSink:
+      /* Ignore packet */
+      break;
+    default:
+      break;
+  }
+}
diff --git a/crazyflie-firmware-src/src/modules/src/estimator_complementary.c b/crazyflie-firmware-src/src/modules/src/estimator_complementary.c
new file mode 100644
index 0000000000000000000000000000000000000000..e69511fb8d8538ae4f7397dfca4113488375be92
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/estimator_complementary.c
@@ -0,0 +1,52 @@
+
+#include "stabilizer.h"
+#include "stabilizer_types.h"
+
+#include "sensfusion6.h"
+#include "position_estimator.h"
+
+#define ATTITUDE_UPDATE_RATE RATE_250_HZ
+#define ATTITUDE_UPDATE_DT 1.0/ATTITUDE_UPDATE_RATE
+
+#define POS_UPDATE_RATE RATE_100_HZ
+#define POS_UPDATE_DT 1.0/POS_UPDATE_RATE
+
+void stateEstimatorInit(void)
+{
+  sensfusion6Init();
+}
+
+bool stateEstimatorTest(void)
+{
+  bool pass = true;
+
+  pass &= sensfusion6Test();
+
+  return pass;
+}
+
+void stateEstimator(state_t *state, const sensorData_t *sensorData, const uint32_t tick)
+{
+  if (RATE_DO_EXECUTE(ATTITUDE_UPDATE_RATE, tick)) {
+    sensfusion6UpdateQ(sensorData->gyro.x, sensorData->gyro.y, sensorData->gyro.z,
+                       sensorData->acc.x, sensorData->acc.y, sensorData->acc.z,
+                       ATTITUDE_UPDATE_DT);
+    sensfusion6GetEulerRPY(&state->attitude.roll, &state->attitude.pitch, &state->attitude.yaw);
+
+    state->acc.z = sensfusion6GetAccZWithoutGravity(sensorData->acc.x,
+                                                    sensorData->acc.y,
+                                                    sensorData->acc.z);
+
+    positionUpdateVelocity(state->acc.z, ATTITUDE_UPDATE_DT);
+  }
+
+  if (RATE_DO_EXECUTE(POS_UPDATE_RATE, tick)) {
+    // If position sensor data is preset, pass it throught
+    // FIXME: The position sensor shall be used as an input of the estimator
+    if (sensorData->position.timestamp) {
+      state->position = sensorData->position;
+    } else {
+      positionEstimate(state, sensorData->baro.asl, POS_UPDATE_DT);
+    }
+  }
+}
diff --git a/crazyflie-firmware-src/src/modules/src/estimator_kalman.c b/crazyflie-firmware-src/src/modules/src/estimator_kalman.c
new file mode 100644
index 0000000000000000000000000000000000000000..2767e5d5186d223ea30c92bbec9cdb37822102ce
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/estimator_kalman.c
@@ -0,0 +1,1303 @@
+/**
+ * Authored by Michael Hamer (http://www.mikehamer.info), June 2016
+ * Thank you to Mark Mueller (www.mwm.im) for advice during implementation,
+ * and for derivation of the original filter in the below-cited paper.
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * ============================================================================
+ *
+ * The Kalman filter implemented in this file is based on the papers:
+ *
+ * "Fusing ultra-wideband range measurements with accelerometers and rate gyroscopes for quadrocopter state estimation"
+ * http://ieeexplore.ieee.org/xpl/articleDetails.jsp?arnumber=7139421
+ *
+ * and
+ *
+ * "Kalman filtering with an attitude" as published in the PhD thesis "Increased autonomy for quadrocopter systems: trajectory generation, fail-safe strategies, and state estimation"
+ * http://dx.doi.org/10.3929/ethz-a-010655275
+ * TODO: Update the above reference once the paper has been published
+ *
+ * Academic citation would be appreciated.
+ *
+ * BIBTEX ENTRIES:
+      @INPROCEEDINGS{MuellerHamer2015,
+      author  = {Mueller, M. W. and Hamer, M. and D'Andrea, R.},
+      title   = {Fusing ultra-wideband range measurements with accelerometers and rate gyroscopes for quadrocopter state estimation},
+      booktitle = {2015 IEEE International Conference on Robotics and Automation (ICRA)},
+      year    = {2015},
+      month   = {May},
+      pages   = {1730-1736},
+      doi     = {10.1109/ICRA.2015.7139421},
+      ISSN    = {1050-4729}}
+
+      @PHDTHESIS {Mueller2016,
+      author  = {Mueller, M. W.},
+      title   = {Increased autonomy for quadrocopter systems: trajectory generation, fail-safe strategies, and state-estimation},
+      school  = {ETH Zurich},
+      year    = {2016},
+      doi     = {10.3929/ethz-a-010655275}}
+ *
+ * ============================================================================
+ *
+ * MAJOR CHANGELOG:
+ * 2016.06.28, Mike Hamer: Initial version
+ *
+ */
+
+#ifdef PLATFORM_CF1
+#error ESTIMATOR = kalman is only compatible with the Crazyflie 2.0 // since it requires an FPU
+#endif
+
+#include "estimator_kalman.h"
+
+#include "stm32f4xx.h"
+
+#include "FreeRTOS.h"
+#include "queue.h"
+#include "task.h"
+#include "sensors.h"
+
+#include "log.h"
+#include "param.h"
+
+#include "math.h"
+#include "arm_math.h"
+
+//#define KALMAN_USE_BARO_UPDATE
+//#define KALMAN_NAN_CHECK
+
+
+/**
+ * Primary Kalman filter functions
+ *
+ * The filter progresses as:
+ *  - Predicting the current state forward */
+static void stateEstimatorPredict(float thrust, Axis3f *acc, Axis3f *gyro, float dt);
+static void stateEstimatorAddProcessNoise(float dt);
+
+/*  - Measurement updates based on sensors */
+static void stateEstimatorScalarUpdate(arm_matrix_instance_f32 *Hm, float error, float stdMeasNoise);
+static void stateEstimatorUpdateWithAccOnGround(Axis3f *acc);
+#ifdef KALMAN_USE_BARO_UPDATE
+static void stateEstimatorUpdateWithBaro(baro_t *baro);
+#endif
+
+/*  - Finalization to incorporate attitude error into body attitude */
+static void stateEstimatorFinalize(sensorData_t *sensors, uint32_t tick);
+
+/*  - Externalization to move the filter's internal state into the external state expected by other modules */
+static void stateEstimatorExternalizeState(state_t *state, sensorData_t *sensors, uint32_t tick);
+
+
+/**
+ * Additionally, the filter supports the incorporation of additional sensors into the state estimate
+ *
+ * This is done via the external functions:
+ * - bool stateEstimatorEnqueueUWBPacket(uwbPacket_t *uwb)
+ * - bool stateEstimatorEnqueuePosition(positionMeasurement_t *pos)
+ * - bool stateEstimatorEnqueueDistance(distanceMeasurement_t *dist)
+ *
+ * As well as by the following internal functions and datatypes
+ */
+
+// Distance-to-point measurements
+static xQueueHandle distDataQueue;
+#define DIST_QUEUE_LENGTH (10)
+
+static void stateEstimatorUpdateWithDistance(distanceMeasurement_t *dist);
+
+static inline bool stateEstimatorHasDistanceMeasurement(distanceMeasurement_t *dist) {
+  return (pdTRUE == xQueueReceive(distDataQueue, dist, 0));
+}
+
+// Direct measurements of Crazyflie position
+static xQueueHandle posDataQueue;
+#define POS_QUEUE_LENGTH (10)
+
+static void stateEstimatorUpdateWithPosition(positionMeasurement_t *pos);
+
+static inline bool stateEstimatorHasPositionMeasurement(positionMeasurement_t *pos) {
+  return (pdTRUE == xQueueReceive(posDataQueue, pos, 0));
+}
+
+// Measurements of a UWB Tx/Rx
+static xQueueHandle tdoaDataQueue;
+#define UWB_QUEUE_LENGTH (10)
+
+static void stateEstimatorUpdateWithTDOA(tdoaMeasurement_t *uwb);
+
+static inline bool stateEstimatorHasTDOAPacket(tdoaMeasurement_t *uwb) {
+  return (pdTRUE == xQueueReceive(tdoaDataQueue, uwb, 0));
+}
+
+// Measurements of TOF from laser sensor
+static xQueueHandle tofDataQueue;
+#define TOF_QUEUE_LENGTH (10)
+
+static void stateEstimatorUpdateWithTof(tofMeasurement_t *tof);
+
+static inline bool stateEstimatorHasTOFPacket(tofMeasurement_t *tof) {
+  return (pdTRUE == xQueueReceive(tofDataQueue, tof, 0));
+}
+
+/**
+ * Constants used in the estimator
+ */
+
+#define DEG_TO_RAD (PI/180.0f)
+#define RAD_TO_DEG (180.0f/PI)
+
+#define GRAVITY_MAGNITUDE (9.81f) // we use the magnitude such that the sign/direction is explicit in calculations
+#define CRAZYFLIE_WEIGHT_grams (27.0f)
+
+//thrust is thrust mapped for 65536 <==> 60 GRAMS!
+#define CONTROL_TO_ACC (GRAVITY_MAGNITUDE*60.0f/CRAZYFLIE_WEIGHT_grams/65536.0f)
+
+#define SPEED_OF_LIGHT (299792458)
+
+// TODO: Decouple the TDOA implementation from the Kalman filter...
+#define METERS_PER_TDOATICK (4.691763979e-3f)
+#define SECONDS_PER_TDOATICK (15.650040064e-12f)
+
+
+/**
+ * Tuning parameters
+ */
+#define PREDICT_RATE RATE_100_HZ // this is slower than the IMU update rate of 500Hz
+#define BARO_RATE RATE_25_HZ
+
+// the point at which the dynamics change from stationary to flying
+#define IN_FLIGHT_THRUST_THRESHOLD (GRAVITY_MAGNITUDE*0.1f)
+#define IN_FLIGHT_TIME_THRESHOLD (500)
+
+// the reversion of pitch and roll to zero
+#define ROLLPITCH_ZERO_REVERSION (1e-3f)
+
+// The bounds on the covariance, these shouldn't be hit, but sometimes are... why?
+#define MAX_COVARIANCE (100)
+#define MIN_COVARIANCE (1e-6)
+
+// The bounds on states, these shouldn't be hit...
+#define MAX_POSITION (10) //meters
+#define MAX_VELOCITY (10) //meters per second
+
+// Initial variances, uncertain of position, but know we're stationary and roughly flat
+static const float stdDevInitialPosition_xy = 100;
+static const float stdDevInitialPosition_z = 1;
+static const float stdDevInitialVelocity = 0.01;
+static const float stdDevInitialAttitude_rollpitch = 0.01;
+static const float stdDevInitialAttitude_yaw = 0.1;
+
+static float procNoiseAcc_xy = 0.5f;
+static float procNoiseAcc_z = 1.0f;
+static float procNoiseVel = 0;
+static float procNoisePos = 0;
+static float procNoiseAtt = 0;
+static float measNoiseBaro = 2.0f; // meters
+static float measNoiseGyro_rollpitch = 0.1f; // radians per second
+static float measNoiseGyro_yaw = 0.1f; // radians per second
+
+// We track a TDOA skew as part of the Kalman filter
+static const float stdDevInitialSkew = 0.1;
+static float procNoiseSkew = 10e-6f; // seconds per second^2 (is multiplied by dt to give skew noise)
+
+/**
+ * Quadrocopter State
+ *
+ * The internally-estimated state is:
+ * - X, Y, Z: the quad's position in the global frame
+ * - PX, PY, PZ: the quad's velocity in its body frame
+ * - D0, D1, D2: attitude error
+ * - SKEW: the skew from anchor system clock to quad clock
+ *
+ * For more information, refer to the paper
+ */
+
+// The quad's state, stored as a column vector
+typedef enum
+{
+  STATE_X, STATE_Y, STATE_Z, STATE_PX, STATE_PY, STATE_PZ, STATE_D0, STATE_D1, STATE_D2, STATE_DIM
+} stateIdx_t;
+
+static float S[STATE_DIM];
+
+// The quad's attitude as a quaternion (w,x,y,z)
+// We store as a quaternion to allow easy normalization (in comparison to a rotation matrix),
+// while also being robust against singularities (in comparison to euler angles)
+static float q[4] = {1,0,0,0};
+
+// The quad's attitude as a rotation matrix (used by the prediction, updated by the finalization)
+static float R[3][3] = {{1,0,0},{0,1,0},{0,0,1}};
+
+// The covariance matrix
+static float P[STATE_DIM][STATE_DIM];
+static arm_matrix_instance_f32 Pm = {STATE_DIM, STATE_DIM, (float *)P};
+
+
+/**
+ * Internal variables. Note that static declaration results in default initialization (to 0)
+ */
+
+static bool isInit = false;
+static bool resetEstimation = true;
+static int32_t lastPrediction;
+static int32_t lastBaroUpdate;
+static int32_t lastPNUpdate;
+static Axis3f accAccumulator;
+static float thrustAccumulator;
+static Axis3f gyroAccumulator;
+static baro_t baroAccumulator;
+static uint32_t accAccumulatorCount;
+static uint32_t thrustAccumulatorCount;
+static uint32_t gyroAccumulatorCount;
+static uint32_t baroAccumulatorCount;
+static bool quadIsFlying = false;
+static int32_t lastTDOAUpdate;
+static float stateSkew;
+static float varSkew;
+static uint32_t lastFlightCmd;
+static uint32_t takeoffTime;
+static uint32_t tdoaCount;
+
+/**
+ * Supporting and utility functions
+ */
+
+static inline void mat_trans(const arm_matrix_instance_f32 * pSrc, arm_matrix_instance_f32 * pDst)
+{ configASSERT(ARM_MATH_SUCCESS == arm_mat_trans_f32(pSrc, pDst)); }
+static inline void mat_inv(const arm_matrix_instance_f32 * pSrc, arm_matrix_instance_f32 * pDst)
+{ configASSERT(ARM_MATH_SUCCESS == arm_mat_inverse_f32(pSrc, pDst)); }
+static inline void mat_mult(const arm_matrix_instance_f32 * pSrcA, const arm_matrix_instance_f32 * pSrcB, arm_matrix_instance_f32 * pDst)
+{ configASSERT(ARM_MATH_SUCCESS == arm_mat_mult_f32(pSrcA, pSrcB, pDst)); }
+static inline float arm_sqrt(float32_t in)
+{ float pOut = 0; arm_status result = arm_sqrt_f32(in, &pOut); configASSERT(ARM_MATH_SUCCESS == result); return pOut; }
+
+#ifdef KALMAN_NAN_CHECK
+static void stateEstimatorAssertNotNaN() {
+  if ((isnan(S[STATE_X])) ||
+      (isnan(S[STATE_Y])) ||
+      (isnan(S[STATE_Z])) ||
+      (isnan(S[STATE_PX])) ||
+      (isnan(S[STATE_PY])) ||
+      (isnan(S[STATE_PZ])) ||
+      (isnan(S[STATE_D0])) ||
+      (isnan(S[STATE_D1])) ||
+      (isnan(S[STATE_D2])) ||
+      (isnan(q[0])) ||
+      (isnan(q[1])) ||
+      (isnan(q[2])) ||
+      (isnan(q[3]))) { resetEstimation = true; }
+
+  for(int i=0; i<STATE_DIM; i++) {
+    for(int j=0; j<STATE_DIM; j++)
+    {
+      if (isnan(P[i][j]))
+      {
+        resetEstimation = true;
+      }
+    }
+  }
+}
+#else
+static void stateEstimatorAssertNotNaN()
+{
+  return;
+}
+#endif
+
+
+// --------------------------------------------------
+
+
+void stateEstimatorUpdate(state_t *state, sensorData_t *sensors, control_t *control)
+{
+  // If the client (via a parameter update) triggers an estimator reset:
+  if (resetEstimation) { stateEstimatorInit(); resetEstimation = false; }
+
+  // Tracks whether an update to the state has been made, and the state therefore requires finalization
+  bool doneUpdate = false;
+
+  uint32_t tick = xTaskGetTickCount(); // would be nice if this had a precision higher than 1ms...
+
+  // Average the last IMU measurements. We do this because the prediction loop is
+  // slower than the IMU loop, but the IMU information is required externally at
+  // a higher rate (for body rate control).
+  if (sensorsReadAcc(&sensors->acc)) {
+    accAccumulator.x += GRAVITY_MAGNITUDE*sensors->acc.x; // accelerometer is in Gs
+    accAccumulator.y += GRAVITY_MAGNITUDE*sensors->acc.y; // but the estimator requires ms^-2
+    accAccumulator.z += GRAVITY_MAGNITUDE*sensors->acc.z;
+    accAccumulatorCount++;
+  }
+
+  if (sensorsReadGyro(&sensors->gyro)) {
+    gyroAccumulator.x += sensors->gyro.x * DEG_TO_RAD; // gyro is in deg/sec
+    gyroAccumulator.y += sensors->gyro.y * DEG_TO_RAD; // but the estimator requires rad/sec
+    gyroAccumulator.z += sensors->gyro.z * DEG_TO_RAD;
+    gyroAccumulatorCount++;
+  }
+
+  if (sensorsReadMag(&sensors->mag)) {
+      // Currently the magnetometer doesn't play a part in the estimation
+  }
+
+  // Average the thrust command from the last timestep, generated externally by the controller
+  thrustAccumulator += control->thrust * CONTROL_TO_ACC; // thrust is in grams, we need ms^-2
+  thrustAccumulatorCount++;
+
+  // Run the system dynamics to predict the state forward.
+  if ((tick-lastPrediction) >= configTICK_RATE_HZ/PREDICT_RATE // update at the PREDICT_RATE
+      && gyroAccumulatorCount > 0
+      && accAccumulatorCount > 0
+      && thrustAccumulatorCount > 0)
+  {
+    gyroAccumulator.x /= gyroAccumulatorCount;
+    gyroAccumulator.y /= gyroAccumulatorCount;
+    gyroAccumulator.z /= gyroAccumulatorCount;
+
+    accAccumulator.x /= accAccumulatorCount;
+    accAccumulator.y /= accAccumulatorCount;
+    accAccumulator.z /= accAccumulatorCount;
+
+    thrustAccumulator /= thrustAccumulatorCount;
+
+    float dt = (float)(tick-lastPrediction)/configTICK_RATE_HZ;
+    stateEstimatorPredict(thrustAccumulator, &accAccumulator, &gyroAccumulator, dt);
+
+    if (!quadIsFlying) { // accelerometers give us information about attitude on slanted ground
+      stateEstimatorUpdateWithAccOnGround(&accAccumulator);
+    }
+
+    lastPrediction = tick;
+
+    accAccumulator = (Axis3f){.axis={0}};
+    accAccumulatorCount = 0;
+    gyroAccumulator = (Axis3f){.axis={0}};
+    gyroAccumulatorCount = 0;
+    thrustAccumulator = 0;
+    thrustAccumulatorCount = 0;
+
+    doneUpdate = true;
+  }
+
+
+  /**
+   * Add process noise every loop, rather than every prediction
+   */
+  stateEstimatorAddProcessNoise((float)(tick-lastPNUpdate)/configTICK_RATE_HZ);
+  lastPNUpdate = tick;
+
+
+
+  /**
+   * Update the state estimate with the barometer measurements
+   */
+  // Accumulate the barometer measurements
+  if (sensorsReadBaro(&sensors->baro)) {
+#ifdef KALMAN_USE_BARO_UPDATE
+    baroAccumulator.asl += sensors->baro.asl;
+    baroAccumulatorCount++;
+  }
+
+  if ((tick-lastBaroUpdate) >= configTICK_RATE_HZ/BARO_RATE // update at BARO_RATE
+      && baroAccumulatorCount > 0)
+  {
+    baroAccumulator.asl /= baroAccumulatorCount;
+
+    stateEstimatorUpdateWithBaro(&sensors->baro);
+
+    baroAccumulator.asl = 0;
+    baroAccumulatorCount = 0;
+    lastBaroUpdate = tick;
+    doneUpdate = true;
+#endif
+  }
+
+  /**
+   * Sensor measurements can come in sporadically and faster than the stabilizer loop frequency,
+   * we therefore consume all measurements since the last loop, rather than accumulating
+   */
+
+  tofMeasurement_t tof;
+  while (stateEstimatorHasTOFPacket(&tof))
+  {
+    stateEstimatorUpdateWithTof(&tof);
+    doneUpdate = true;
+  }
+  
+  distanceMeasurement_t dist;
+  while (stateEstimatorHasDistanceMeasurement(&dist))
+  {
+    stateEstimatorUpdateWithDistance(&dist);
+    doneUpdate = true;
+  }
+
+  positionMeasurement_t pos;
+  while (stateEstimatorHasPositionMeasurement(&pos))
+  {
+    stateEstimatorUpdateWithPosition(&pos);
+    doneUpdate = true;
+  }
+
+  tdoaMeasurement_t tdoa;
+  while (stateEstimatorHasTDOAPacket(&tdoa))
+  {
+    stateEstimatorUpdateWithTDOA(&tdoa);
+    doneUpdate = true;
+  }
+
+  /**
+   * If an update has been made, the state is finalized:
+   * - the attitude error is moved into the body attitude quaternion,
+   * - the body attitude is converted into a rotation matrix for the next prediction, and
+   * - correctness of the covariance matrix is ensured
+   */
+
+  if (doneUpdate)
+  {
+    stateEstimatorFinalize(sensors, tick);
+    stateEstimatorAssertNotNaN();
+  }
+
+  /**
+   * Finally, the internal state is externalized.
+   * This is done every round, since the external state includes some sensor data
+   */
+  stateEstimatorExternalizeState(state, sensors, tick);
+  stateEstimatorAssertNotNaN();
+}
+
+static void stateEstimatorPredict(float cmdThrust, Axis3f *acc, Axis3f *gyro, float dt)
+{
+  /* Here we discretize (euler forward) and linearise the quadrocopter dynamics in order
+   * to push the covariance forward.
+   *
+   * QUADROCOPTER DYNAMICS (see paper):
+   *
+   * \dot{x} = R(I + [[d]])p
+   * \dot{p} = f/m * e3 - [[\omega]]p - g(I - [[d]])R^-1 e3 //drag negligible
+   * \dot{d} = \omega
+   *
+   * where [[.]] is the cross-product matrix of .
+   *       \omega are the gyro measurements
+   *       e3 is the column vector [0 0 1]'
+   *       I is the identity
+   *       R is the current attitude as a rotation matrix
+   *       f/m is the mass-normalized motor force (acceleration in the body's z direction)
+   *       g is gravity
+   *       x, p, d, skew are the quad's states
+   * note that d (attitude error) is zero at the beginning of each iteration,
+   * since error information is incorporated into R after each Kalman update.
+   */
+
+  // The linearized update matrix
+  static float A[STATE_DIM][STATE_DIM];
+  static arm_matrix_instance_f32 Am = { STATE_DIM, STATE_DIM, (float *)A}; // linearized dynamics for covariance update;
+
+  // Temporary matrices for the covariance updates
+  static float tmpNN1d[STATE_DIM * STATE_DIM];
+  static arm_matrix_instance_f32 tmpNN1m = { STATE_DIM, STATE_DIM, tmpNN1d};
+
+  static float tmpNN2d[STATE_DIM * STATE_DIM];
+  static arm_matrix_instance_f32 tmpNN2m = { STATE_DIM, STATE_DIM, tmpNN2d};
+
+  float dt2 = dt*dt;
+
+  // ====== DYNAMICS LINEARIZATION ======
+  // Initialize as the identity
+  A[STATE_X][STATE_X] = 1;
+  A[STATE_Y][STATE_Y] = 1;
+  A[STATE_Z][STATE_Z] = 1;
+
+  A[STATE_PX][STATE_PX] = 1;
+  A[STATE_PY][STATE_PY] = 1;
+  A[STATE_PZ][STATE_PZ] = 1;
+
+  A[STATE_D0][STATE_D0] = 1;
+  A[STATE_D1][STATE_D1] = 1;
+  A[STATE_D2][STATE_D2] = 1;
+
+  // position from body-frame velocity
+  A[STATE_X][STATE_PX] = R[0][0]*dt;
+  A[STATE_Y][STATE_PX] = R[1][0]*dt;
+  A[STATE_Z][STATE_PX] = R[2][0]*dt;
+
+  A[STATE_X][STATE_PY] = R[0][1]*dt;
+  A[STATE_Y][STATE_PY] = R[1][1]*dt;
+  A[STATE_Z][STATE_PY] = R[2][1]*dt;
+
+  A[STATE_X][STATE_PZ] = R[0][2]*dt;
+  A[STATE_Y][STATE_PZ] = R[1][2]*dt;
+  A[STATE_Z][STATE_PZ] = R[2][2]*dt;
+
+  // position from attitude error
+  A[STATE_X][STATE_D0] = (S[STATE_PY]*R[0][2] - S[STATE_PZ]*R[0][1])*dt;
+  A[STATE_Y][STATE_D0] = (S[STATE_PY]*R[1][2] - S[STATE_PZ]*R[1][1])*dt;
+  A[STATE_Z][STATE_D0] = (S[STATE_PY]*R[2][2] - S[STATE_PZ]*R[2][1])*dt;
+
+  A[STATE_X][STATE_D1] = (- S[STATE_PX]*R[0][2] + S[STATE_PZ]*R[0][0])*dt;
+  A[STATE_Y][STATE_D1] = (- S[STATE_PX]*R[1][2] + S[STATE_PZ]*R[1][0])*dt;
+  A[STATE_Z][STATE_D1] = (- S[STATE_PX]*R[2][2] + S[STATE_PZ]*R[2][0])*dt;
+
+  A[STATE_X][STATE_D2] = (S[STATE_PX]*R[0][1] - S[STATE_PY]*R[0][0])*dt;
+  A[STATE_Y][STATE_D2] = (S[STATE_PX]*R[1][1] - S[STATE_PY]*R[1][0])*dt;
+  A[STATE_Z][STATE_D2] = (S[STATE_PX]*R[2][1] - S[STATE_PY]*R[2][0])*dt;
+
+  // body-frame velocity from body-frame velocity
+  A[STATE_PX][STATE_PX] = 1; //drag negligible
+  A[STATE_PY][STATE_PX] =-gyro->z*dt;
+  A[STATE_PZ][STATE_PX] = gyro->y*dt;
+
+  A[STATE_PX][STATE_PY] = gyro->z*dt;
+  A[STATE_PY][STATE_PY] = 1; //drag negligible
+  A[STATE_PZ][STATE_PY] =-gyro->x*dt;
+
+  A[STATE_PX][STATE_PZ] =-gyro->y*dt;
+  A[STATE_PY][STATE_PZ] = gyro->x*dt;
+  A[STATE_PZ][STATE_PZ] = 1; //drag negligible
+
+  // body-frame velocity from attitude error
+  A[STATE_PX][STATE_D0] =  0;
+  A[STATE_PY][STATE_D0] = -GRAVITY_MAGNITUDE*R[2][2]*dt;
+  A[STATE_PZ][STATE_D0] =  GRAVITY_MAGNITUDE*R[2][1]*dt;
+
+  A[STATE_PX][STATE_D1] =  GRAVITY_MAGNITUDE*R[2][2]*dt;
+  A[STATE_PY][STATE_D1] =  0;
+  A[STATE_PZ][STATE_D1] = -GRAVITY_MAGNITUDE*R[2][0]*dt;
+
+  A[STATE_PX][STATE_D2] = -GRAVITY_MAGNITUDE*R[2][1]*dt;
+  A[STATE_PY][STATE_D2] =  GRAVITY_MAGNITUDE*R[2][0]*dt;
+  A[STATE_PZ][STATE_D2] =  0;
+
+  // attitude error from attitude error
+  /**
+   * At first glance, it may not be clear where the next values come from, since they do not appear directly in the
+   * dynamics. In this prediction step, we skip the step of first updating attitude-error, and then incorporating the
+   * new error into the current attitude (which requires a rotation of the attitude-error covariance). Instead, we
+   * directly update the body attitude, however still need to rotate the covariance, which is what you see below.
+   *
+   * This comes from a second order approximation to:
+   * Sigma_post = exps(-d) Sigma_pre exps(-d)'
+   *            ~ (I + [[-d]] + [[-d]]^2 / 2) Sigma_pre (I + [[-d]] + [[-d]]^2 / 2)'
+   * where d is the attitude error expressed as Rodriges parameters, ie. d0 = 1/2*gyro.x*dt under the assumption that
+   * d = [0,0,0] at the beginning of each prediction step and that gyro.x is constant over the sampling period
+   *
+   * As derived in the following paper:
+   * TODO: Once it is published, cite the paper Müller, Hehn and D'Andrea, "Kalman Filtering with an Attitude".
+   */
+  float d0 = gyro->x*dt/2;
+  float d1 = gyro->y*dt/2;
+  float d2 = gyro->z*dt/2;
+
+  A[STATE_D0][STATE_D0] =  1 - d1*d1/2 - d2*d2/2;
+  A[STATE_D0][STATE_D1] =  d2 + d0*d1/2;
+  A[STATE_D0][STATE_D2] = -d1 + d0*d2/2;
+
+  A[STATE_D1][STATE_D0] = -d2 + d0*d1/2;
+  A[STATE_D1][STATE_D1] =  1 - d0*d0/2 - d2*d2/2;
+  A[STATE_D1][STATE_D2] =  d0 + d1*d2/2;
+
+  A[STATE_D2][STATE_D0] =  d1 + d0*d2/2;
+  A[STATE_D2][STATE_D1] = -d0 + d1*d2/2;
+  A[STATE_D2][STATE_D2] = 1 - d0*d0/2 - d1*d1/2;
+
+
+  // ====== COVARIANCE UPDATE ======
+  mat_mult(&Am, &Pm, &tmpNN1m); // A P
+  mat_trans(&Am, &tmpNN2m); // A'
+  mat_mult(&tmpNN1m, &tmpNN2m, &Pm); // A P A'
+  // Process noise is added after the return from the prediction step
+
+  // ====== PREDICTION STEP ======
+  // The prediction depends on whether we're on the ground, or in flight.
+  // When flying, the accelerometer directly measures thrust (hence is useless to estimate body angle while flying)
+
+  // TODO: Find a better check for whether the quad is flying
+  // Assume that the flight begins when the thrust is large enough and for now we never stop "flying".
+  if (cmdThrust > IN_FLIGHT_THRUST_THRESHOLD) {
+    lastFlightCmd = xTaskGetTickCount();
+    if (!quadIsFlying) {
+      takeoffTime = lastFlightCmd;
+    }
+  }
+  quadIsFlying = (xTaskGetTickCount()-lastFlightCmd) < IN_FLIGHT_TIME_THRESHOLD;
+
+  float dx, dy, dz;
+  float tmpSPX, tmpSPY, tmpSPZ;
+  float zacc;
+
+  if (quadIsFlying) // only acceleration in z direction
+  {
+    // TODO: In the next lines, can either use cmdThrust/mass, or acc->z. Need to test which is more reliable.
+    // cmdThrust's error comes from poorly calibrated mass, and inexact cmdThrust -> thrust map
+    // acc->z's error comes from measurement noise and accelerometer scaling
+    // float zacc = cmdThrust;
+    zacc = acc->z;
+
+    // position updates in the body frame (will be rotated to inertial frame)
+    dx = S[STATE_PX] * dt;
+    dy = S[STATE_PY] * dt;
+    dz = S[STATE_PZ] * dt + zacc * dt2 / 2.0f; // thrust can only be produced in the body's Z direction
+
+    // position update
+    S[STATE_X] += R[0][0] * dx + R[0][1] * dy + R[0][2] * dz;
+    S[STATE_Y] += R[1][0] * dx + R[1][1] * dy + R[1][2] * dz;
+    S[STATE_Z] += R[2][0] * dx + R[2][1] * dy + R[2][2] * dz - GRAVITY_MAGNITUDE * dt2 / 2.0f;
+
+    // keep previous time step's state for the update
+    tmpSPX = S[STATE_PX];
+    tmpSPY = S[STATE_PY];
+    tmpSPZ = S[STATE_PZ];
+
+    // body-velocity update: accelerometers + gyros cross velocity - gravity in body frame
+    S[STATE_PX] += dt * (gyro->z * tmpSPY - gyro->y * tmpSPZ - GRAVITY_MAGNITUDE * R[2][0]);
+    S[STATE_PY] += dt * (gyro->z * tmpSPX + gyro->x * tmpSPZ - GRAVITY_MAGNITUDE * R[2][1]);
+    S[STATE_PZ] += dt * (zacc + gyro->y * tmpSPX - gyro->x * tmpSPY - GRAVITY_MAGNITUDE * R[2][2]);
+  }
+  else // Acceleration can be in any direction, as measured by the accelerometer. This occurs, eg. in freefall or while being carried.
+  {
+    // position updates in the body frame (will be rotated to inertial frame)
+    dx = S[STATE_PX] * dt + acc->x * dt2 / 2.0f;
+    dy = S[STATE_PY] * dt + acc->y * dt2 / 2.0f;
+    dz = S[STATE_PZ] * dt + acc->z * dt2 / 2.0f; // thrust can only be produced in the body's Z direction
+
+    // position update
+    S[STATE_X] += R[0][0] * dx + R[0][1] * dy + R[0][2] * dz;
+    S[STATE_Y] += R[1][0] * dx + R[1][1] * dy + R[1][2] * dz;
+    S[STATE_Z] += R[2][0] * dx + R[2][1] * dy + R[2][2] * dz - GRAVITY_MAGNITUDE * dt2 / 2.0f;
+
+    // keep previous time step's state for the update
+    tmpSPX = S[STATE_PX];
+    tmpSPY = S[STATE_PY];
+    tmpSPZ = S[STATE_PZ];
+
+    // body-velocity update: accelerometers + gyros cross velocity - gravity in body frame
+    S[STATE_PX] += dt * (acc->x + gyro->z * tmpSPY - gyro->y * tmpSPZ - GRAVITY_MAGNITUDE * R[2][0]);
+    S[STATE_PY] += dt * (acc->y + gyro->z * tmpSPX + gyro->x * tmpSPZ - GRAVITY_MAGNITUDE * R[2][1]);
+    S[STATE_PZ] += dt * (acc->z + gyro->y * tmpSPX - gyro->x * tmpSPY - GRAVITY_MAGNITUDE * R[2][2]);
+  }
+
+  if(S[STATE_Z] < 0) {
+    S[STATE_Z] = 0;
+    S[STATE_PX] = 0;
+    S[STATE_PY] = 0;
+    S[STATE_PZ] = 0;
+  }
+
+  // attitude update (rotate by gyroscope), we do this in quaternions
+  // this is the gyroscope angular velocity integrated over the sample period
+  float dtwx = dt*gyro->x;
+  float dtwy = dt*gyro->y;
+  float dtwz = dt*gyro->z;
+
+  // compute the quaternion values in [w,x,y,z] order
+  float angle = arm_sqrt(dtwx*dtwx + dtwy*dtwy + dtwz*dtwz);
+  float ca = arm_cos_f32(angle/2.0f);
+  float sa = arm_sin_f32(angle/2.0f);
+  float dq[4] = {ca , sa*dtwx/angle , sa*dtwy/angle , sa*dtwz/angle};
+
+  // rotate the quad's attitude by the delta quaternion vector computed above
+  float tmpq0 = (dq[0]*q[0] - dq[1]*q[1] - dq[2]*q[2] - dq[3]*q[3]);
+  float tmpq1 = (1.0f-ROLLPITCH_ZERO_REVERSION)*(dq[1]*q[0] + dq[0]*q[1] + dq[3]*q[2] - dq[2]*q[3]);
+  float tmpq2 = (1.0f-ROLLPITCH_ZERO_REVERSION)*(dq[2]*q[0] - dq[3]*q[1] + dq[0]*q[2] + dq[1]*q[3]);
+  float tmpq3 = (1.0f-ROLLPITCH_ZERO_REVERSION)*(dq[3]*q[0] + dq[2]*q[1] - dq[1]*q[2] + dq[0]*q[3]);
+
+  // normalize and store the result
+  float norm = arm_sqrt(tmpq0*tmpq0 + tmpq1*tmpq1 + tmpq2*tmpq2 + tmpq3*tmpq3);
+  q[0] = tmpq0/norm; q[1] = tmpq1/norm; q[2] = tmpq2/norm; q[3] = tmpq3/norm;
+  stateEstimatorAssertNotNaN();
+}
+
+static void stateEstimatorAddProcessNoise(float dt)
+{
+  if (dt>0)
+  {
+    P[STATE_X][STATE_X] += powf(procNoiseAcc_xy*dt*dt + procNoiseVel*dt + procNoisePos, 2);  // add process noise on position
+    P[STATE_Y][STATE_Y] += powf(procNoiseAcc_xy*dt*dt + procNoiseVel*dt + procNoisePos, 2);  // add process noise on position
+    P[STATE_Z][STATE_Z] += powf(procNoiseAcc_z*dt*dt + procNoiseVel*dt + procNoisePos, 2);  // add process noise on position
+
+    P[STATE_PX][STATE_PX] += powf(procNoiseAcc_xy*dt + procNoiseVel, 2); // add process noise on velocity
+    P[STATE_PY][STATE_PY] += powf(procNoiseAcc_xy*dt + procNoiseVel, 2); // add process noise on velocity
+    P[STATE_PZ][STATE_PZ] += powf(procNoiseAcc_z*dt + procNoiseVel, 2); // add process noise on velocity
+
+    P[STATE_D0][STATE_D0] += powf(measNoiseGyro_rollpitch * dt + procNoiseAtt, 2);
+    P[STATE_D1][STATE_D1] += powf(measNoiseGyro_rollpitch * dt + procNoiseAtt, 2);
+    P[STATE_D2][STATE_D2] += powf(measNoiseGyro_yaw * dt + procNoiseAtt, 2);
+  }
+
+  for (int i=0; i<STATE_DIM; i++) {
+    for (int j=i; j<STATE_DIM; j++) {
+      float p = 0.5f*P[i][j] + 0.5f*P[j][i];
+      if (isnan(p) || p > MAX_COVARIANCE) {
+        P[i][j] = P[j][i] = MAX_COVARIANCE;
+      } else if ( i==j && p < MIN_COVARIANCE ) {
+        P[i][j] = P[j][i] = MIN_COVARIANCE;
+      } else {
+        P[i][j] = P[j][i] = p;
+      }
+    }
+  }
+
+  stateEstimatorAssertNotNaN();
+}
+
+
+static void stateEstimatorScalarUpdate(arm_matrix_instance_f32 *Hm, float error, float stdMeasNoise)
+{
+  // The Kalman gain as a column vector
+  static float K[STATE_DIM];
+  static arm_matrix_instance_f32 Km = {STATE_DIM, 1, (float *)K};
+
+  // Temporary matrices for the covariance updates
+  static float tmpNN1d[STATE_DIM * STATE_DIM];
+  static arm_matrix_instance_f32 tmpNN1m = {STATE_DIM, STATE_DIM, tmpNN1d};
+
+  static float tmpNN2d[STATE_DIM * STATE_DIM];
+  static arm_matrix_instance_f32 tmpNN2m = {STATE_DIM, STATE_DIM, tmpNN2d};
+
+  static float tmpNN3d[STATE_DIM * STATE_DIM];
+  static arm_matrix_instance_f32 tmpNN3m = {STATE_DIM, STATE_DIM, tmpNN3d};
+
+  static float HTd[STATE_DIM * 1];
+  static arm_matrix_instance_f32 HTm = {STATE_DIM, 1, HTd};
+
+  static float PHTd[STATE_DIM * 1];
+  static arm_matrix_instance_f32 PHTm = {STATE_DIM, 1, PHTd};
+
+  configASSERT(Hm->numRows == 1);
+  configASSERT(Hm->numCols == STATE_DIM);
+
+  // ====== INNOVATION COVARIANCE ======
+
+  mat_trans(Hm, &HTm);
+  mat_mult(&Pm, &HTm, &PHTm); // PH'
+  float R = stdMeasNoise*stdMeasNoise;
+  float HPHR = R; // HPH' + R
+  for (int i=0; i<STATE_DIM; i++) { // Add the element of HPH' to the above
+    HPHR += Hm->pData[i]*PHTd[i]; // this obviously only works if the update is scalar (as in this function)
+  }
+  configASSERT(!isnan(HPHR));
+
+  // ====== MEASUREMENT UPDATE ======
+  // Calculate the Kalman gain and perform the state update
+  for (int i=0; i<STATE_DIM; i++) {
+    K[i] = PHTd[i]/HPHR; // kalman gain = (PH' (HPH' + R )^-1)
+    S[i] = S[i] + K[i] * error; // state update
+  }
+  stateEstimatorAssertNotNaN();
+
+  // ====== COVARIANCE UPDATE ======
+  mat_mult(&Km, Hm, &tmpNN1m); // KH
+  for (int i=0; i<STATE_DIM; i++) { tmpNN1d[STATE_DIM*i+i] -= 1; } // KH - I
+  mat_trans(&tmpNN1m, &tmpNN2m); // (KH - I)'
+  mat_mult(&tmpNN1m, &Pm, &tmpNN3m); // (KH - I)*P
+  mat_mult(&tmpNN3m, &tmpNN2m, &Pm); // (KH - I)*P*(KH - I)'
+  stateEstimatorAssertNotNaN();
+  // add the measurement variance and ensure boundedness and symmetry
+  // TODO: Why would it hit these bounds? Needs to be investigated.
+  for (int i=0; i<STATE_DIM; i++) {
+    for (int j=i; j<STATE_DIM; j++) {
+      float v = K[i] * R * K[j];
+      float p = 0.5f*P[i][j] + 0.5f*P[j][i] + v; // add measurement noise
+      if (isnan(p) || p > MAX_COVARIANCE) {
+        P[i][j] = P[j][i] = MAX_COVARIANCE;
+      } else if ( i==j && p < MIN_COVARIANCE ) {
+        P[i][j] = P[j][i] = MIN_COVARIANCE;
+      } else {
+        P[i][j] = P[j][i] = p;
+      }
+    }
+  }
+
+  stateEstimatorAssertNotNaN();
+}
+
+static void stateEstimatorUpdateWithAccOnGround(Axis3f *acc)
+{
+  // The following code is disabled due to the function not being complete (and that we aim for zero warnings).
+#if 0
+  // This update only makes sense on the ground, when no thrust is being produced,
+  // since the accelerometers can then directly measure the direction of gravity
+  float accMag = sqrtf(acc->x*acc->x + acc->y*acc->y + acc->z*acc->z);
+
+  // Only do the update if the quad isn't flying, and if the accelerometers
+  // are close enough to gravity that we can assume it is the only force
+  if(!quadIsFlying && fabs(1-accMag/GRAVITY_MAGNITUDE) < 0.01) {
+    float h[STATE_DIM] = {0};
+    arm_matrix_instance_f32 H = {1, STATE_DIM, h};
+
+    float gravityInBodyX = GRAVITY_MAGNITUDE * R[2][0];
+    float gravityInBodyY = GRAVITY_MAGNITUDE * R[2][1];
+    float gravityInBodyZ = GRAVITY_MAGNITUDE * R[2][2];
+
+    // TODO: What are the update equations?
+  }
+#endif
+}
+
+#ifdef KALMAN_USE_BARO_UPDATE
+static void stateEstimatorUpdateWithBaro(baro_t *baro)
+{
+  static float baroReferenceHeight = 0;
+
+  float h[STATE_DIM] = {0};
+  arm_matrix_instance_f32 H = {1, STATE_DIM, h};
+
+  h[STATE_Z] = 1;
+
+  if (!quadIsFlying || baroReferenceHeight < 1) {
+    //TODO: maybe we could track the zero height as a state. Would be especially useful if UWB anchors had barometers.
+    baroReferenceHeight = baro->asl;
+  }
+
+  float meas = (baro->asl - baroReferenceHeight);
+  stateEstimatorScalarUpdate(&H, meas - S[STATE_Z], measNoiseBaro);
+}
+#endif
+
+static void stateEstimatorUpdateWithPosition(positionMeasurement_t *xyz)
+{
+  // a direct measurement of states x, y, and z
+  // do a scalar update for each state, since this should be faster than updating all together
+  for (int i=0; i<3; i++) {
+    float h[STATE_DIM] = {0};
+    arm_matrix_instance_f32 H = {1, STATE_DIM, h};
+    h[STATE_X+i] = 1;
+    stateEstimatorScalarUpdate(&H, xyz->pos[i] - S[STATE_X+i], xyz->stdDev);
+  }
+}
+
+static void stateEstimatorUpdateWithDistance(distanceMeasurement_t *d)
+{
+  // a measurement of distance to point (x, y, z)
+  float h[STATE_DIM] = {0};
+  arm_matrix_instance_f32 H = {1, STATE_DIM, h};
+
+  float dx = S[STATE_X] - d->x;
+  float dy = S[STATE_Y] - d->y;
+  float dz = S[STATE_Z] - d->z;
+
+  float predictedDistance = arm_sqrt(powf(dx, 2) + powf(dy, 2) + powf(dz, 2));
+  float measuredDistance = d->distance;
+
+  // The measurement is: z = sqrt(dx^2 + dy^2 + dz^2). The derivative dz/dX gives h.
+  h[STATE_X] = dx/predictedDistance;
+  h[STATE_Y] = dy/predictedDistance;
+  h[STATE_Z] = dz/predictedDistance;
+
+  stateEstimatorScalarUpdate(&H, measuredDistance-predictedDistance, d->stdDev);
+}
+
+static void stateEstimatorUpdateWithTDOA(tdoaMeasurement_t *tdoa)
+{
+  /**
+   * Measurement equation:
+   * dR = dT + d1 - d0
+   */
+
+  float measurement = tdoa->distanceDiff;
+
+  // predict based on current state
+  float x = S[STATE_X];
+  float y = S[STATE_Y];
+  float z = S[STATE_Z];
+
+  float x1 = tdoa->anchorPosition[1].x, y1 = tdoa->anchorPosition[1].y, z1 = tdoa->anchorPosition[1].z;
+  float x0 = tdoa->anchorPosition[0].x, y0 = tdoa->anchorPosition[0].y, z0 = tdoa->anchorPosition[0].z;
+
+  float d1 = sqrtf(powf(x - x1, 2) + powf(y - y1, 2) + powf(z - z1, 2));
+  float d0 = sqrtf(powf(x - x0, 2) + powf(y - y0, 2) + powf(z - z0, 2));
+
+  float predicted = d1 - d0;
+  float error = measurement - predicted;
+
+  if (tdoaCount >= 100)
+  {
+    float h[STATE_DIM] = {0};
+    arm_matrix_instance_f32 H = {1, STATE_DIM, h};
+
+    h[STATE_X] = ((x - x1) / d1 - (x - x0) / d0);
+    h[STATE_Y] = ((y - y1) / d1 - (y - y0) / d0);
+    h[STATE_Z] = ((z - z1) / d1 - (z - z0) / d0);
+
+    stateEstimatorScalarUpdate(&H, error, tdoa->stdDev);
+  }
+
+  tdoaCount++;
+}
+
+static void stateEstimatorUpdateWithTof(tofMeasurement_t *tof)
+{
+  // Updates the filter with a measured distance in the zb direction using the
+  float h[STATE_DIM] = {0};
+  arm_matrix_instance_f32 H = {1, STATE_DIM, h};
+
+  // Only update the filter if the measurement is reliable (\hat{h} -> infty when R[2][2] -> 0)
+  if (fabs(R[2][2]) > 0.1 && R[2][2] > 0){
+    float angleOfApterure = 10 * DEG_TO_RAD; // Half aperture angle radians
+    float alpha = acosf(R[2][2]) - angleOfApterure;
+    if (alpha < 0.0f){
+      alpha = 0.0f;
+    }
+    float predictedDistance = S[STATE_Z] / cosf(alpha);
+    float measuredDistance = tof->distance; // [m]
+
+    //Measurement equation
+    //
+    // h = z/((R*z_b)\dot z_b) = z/cos(alpha)
+    h[STATE_Z] = 1 / cosf(alpha); 
+    
+    // Scalar update
+    stateEstimatorScalarUpdate(&H, measuredDistance-predictedDistance, tof->stdDev);
+  }
+}
+
+static void stateEstimatorFinalize(sensorData_t *sensors, uint32_t tick)
+{
+  // Matrix to rotate the attitude covariances once updated
+  static float A[STATE_DIM][STATE_DIM];
+  static arm_matrix_instance_f32 Am = {STATE_DIM, STATE_DIM, (float *)A};
+
+  // Temporary matrices for the covariance updates
+  static float tmpNN1d[STATE_DIM * STATE_DIM];
+  static arm_matrix_instance_f32 tmpNN1m = {STATE_DIM, STATE_DIM, tmpNN1d};
+
+  static float tmpNN2d[STATE_DIM * STATE_DIM];
+  static arm_matrix_instance_f32 tmpNN2m = {STATE_DIM, STATE_DIM, tmpNN2d};
+
+  // Incorporate the attitude error (Kalman filter state) with the attitude
+  float v0 = S[STATE_D0];
+  float v1 = S[STATE_D1];
+  float v2 = S[STATE_D2];
+
+  // Move attitude error into attitude if any of the angle errors are large enough
+  if ((fabsf(v0) > 0.1e-3 || fabsf(v1) > 0.1e-3 || fabsf(v2) > 0.1e-3) && (fabsf(v0) < 10 && fabsf(v1) < 10 && fabsf(v2) < 10))
+  {
+    float angle = arm_sqrt(v0*v0 + v1*v1 + v2*v2);
+    float ca = arm_cos_f32(angle / 2.0f);
+    float sa = arm_sin_f32(angle / 2.0f);
+    float dq[4] = {ca, sa * v0 / angle, sa * v1 / angle, sa * v2 / angle};
+
+    // rotate the quad's attitude by the delta quaternion vector computed above
+    float tmpq0 = dq[0] * q[0] - dq[1] * q[1] - dq[2] * q[2] - dq[3] * q[3];
+    float tmpq1 = dq[1] * q[0] + dq[0] * q[1] + dq[3] * q[2] - dq[2] * q[3];
+    float tmpq2 = dq[2] * q[0] - dq[3] * q[1] + dq[0] * q[2] + dq[1] * q[3];
+    float tmpq3 = dq[3] * q[0] + dq[2] * q[1] - dq[1] * q[2] + dq[0] * q[3];
+
+    // normalize and store the result
+    float norm = arm_sqrt(tmpq0 * tmpq0 + tmpq1 * tmpq1 + tmpq2 * tmpq2 + tmpq3 * tmpq3);
+    q[0] = tmpq0 / norm;
+    q[1] = tmpq1 / norm;
+    q[2] = tmpq2 / norm;
+    q[3] = tmpq3 / norm;
+
+    /** Rotate the covariance, since we've rotated the body
+     *
+     * This comes from a second order approximation to:
+     * Sigma_post = exps(-d) Sigma_pre exps(-d)'
+     *            ~ (I + [[-d]] + [[-d]]^2 / 2) Sigma_pre (I + [[-d]] + [[-d]]^2 / 2)'
+     * where d is the attitude error expressed as Rodriges parameters, ie. d = tan(|v|/2)*v/|v|
+     *
+     * As derived in the following paper:
+     * TODO: Once it is published, cite the paper Müller, Hehn and D'Andrea, "Kalman Filtering with an Attitude".
+     */
+
+    float d0 = v0/2; // the attitude error vector (v0,v1,v2) is small,
+    float d1 = v1/2; // so we use a first order approximation to d0 = tan(|v0|/2)*v0/|v0|
+    float d2 = v2/2;
+
+    A[STATE_X][STATE_X] = 1;
+    A[STATE_Y][STATE_Y] = 1;
+    A[STATE_Z][STATE_Z] = 1;
+
+    A[STATE_PX][STATE_PX] = 1;
+    A[STATE_PY][STATE_PY] = 1;
+    A[STATE_PZ][STATE_PZ] = 1;
+
+    A[STATE_D0][STATE_D0] =  1 - d1*d1/2 - d2*d2/2;
+    A[STATE_D0][STATE_D1] =  d2 + d0*d1/2;
+    A[STATE_D0][STATE_D2] = -d1 + d0*d2/2;
+
+    A[STATE_D1][STATE_D0] = -d2 + d0*d1/2;
+    A[STATE_D1][STATE_D1] =  1 - d0*d0/2 - d2*d2/2;
+    A[STATE_D1][STATE_D2] =  d0 + d1*d2/2;
+
+    A[STATE_D2][STATE_D0] =  d1 + d0*d2/2;
+    A[STATE_D2][STATE_D1] = -d0 + d1*d2/2;
+    A[STATE_D2][STATE_D2] = 1 - d0*d0/2 - d1*d1/2;
+
+    mat_trans(&Am, &tmpNN1m); // A'
+    mat_mult(&Am, &Pm, &tmpNN2m); // AP
+    mat_mult(&tmpNN2m, &tmpNN1m, &Pm); //APA'
+  }
+
+  // convert the new attitude to a rotation matrix, such that we can rotate body-frame velocity and acc
+  R[0][0] = q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3];
+  R[0][1] = 2 * q[1] * q[2] - 2 * q[0] * q[3];
+  R[0][2] = 2 * q[1] * q[3] + 2 * q[0] * q[2];
+
+  R[1][0] = 2 * q[1] * q[2] + 2 * q[0] * q[3];
+  R[1][1] = q[0] * q[0] - q[1] * q[1] + q[2] * q[2] - q[3] * q[3];
+  R[1][2] = 2 * q[2] * q[3] - 2 * q[0] * q[1];
+
+  R[2][0] = 2 * q[1] * q[3] - 2 * q[0] * q[2];
+  R[2][1] = 2 * q[2] * q[3] + 2 * q[0] * q[1];
+  R[2][2] = q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3];
+
+  // reset the attitude error
+  S[STATE_D0] = 0;
+  S[STATE_D1] = 0;
+  S[STATE_D2] = 0;
+
+  // constrain the states
+  for (int i=0; i<3; i++)
+  {
+    if (S[STATE_X+i] < -MAX_POSITION) { S[STATE_X+i] = -MAX_POSITION; }
+    else if (S[STATE_X+i] > MAX_POSITION) { S[STATE_X+i] = MAX_POSITION; }
+
+    if (S[STATE_PX+i] < -MAX_VELOCITY) { S[STATE_PX+i] = -MAX_VELOCITY; }
+    else if (S[STATE_PX+i] > MAX_VELOCITY) { S[STATE_PX+i] = MAX_VELOCITY; }
+  }
+
+  // enforce symmetry of the covariance matrix, and ensure the values stay bounded
+  for (int i=0; i<STATE_DIM; i++) {
+    for (int j=i; j<STATE_DIM; j++) {
+      float p = 0.5f*P[i][j] + 0.5f*P[j][i];
+      if (isnan(p) || p > MAX_COVARIANCE) {
+        P[i][j] = P[j][i] = MAX_COVARIANCE;
+      } else if ( i==j && p < MIN_COVARIANCE ) {
+        P[i][j] = P[j][i] = MIN_COVARIANCE;
+      } else {
+        P[i][j] = P[j][i] = p;
+      }
+    }
+  }
+
+  stateEstimatorAssertNotNaN();
+}
+
+
+static void stateEstimatorExternalizeState(state_t *state, sensorData_t *sensors, uint32_t tick)
+{
+  // position state is already in world frame
+  state->position = (point_t){
+      .timestamp = tick,
+      .x = S[STATE_X],
+      .y = S[STATE_Y],
+      .z = S[STATE_Z]
+  };
+
+  // velocity is in body frame and needs to be rotated to world frame
+  state->velocity = (velocity_t){
+      .timestamp = tick,
+      .x = R[0][0]*S[STATE_PX] + R[0][1]*S[STATE_PY] + R[0][2]*S[STATE_PZ],
+      .y = R[1][0]*S[STATE_PX] + R[1][1]*S[STATE_PY] + R[1][2]*S[STATE_PZ],
+      .z = R[2][0]*S[STATE_PX] + R[2][1]*S[STATE_PY] + R[2][2]*S[STATE_PZ]
+  };
+
+  // Accelerometer measurements are in the body frame and need to be rotated to world frame.
+  // Furthermore, the legacy code requires acc.z to be acceleration without gravity.
+  // Finally, note that these accelerations are in Gs, and not in m/s^2, hence - 1 for removing gravity
+  state->acc = (acc_t){
+      .timestamp = tick,
+      .x = R[0][0]*sensors->acc.x + R[0][1]*sensors->acc.y + R[0][2]*sensors->acc.z,
+      .y = R[1][0]*sensors->acc.x + R[1][1]*sensors->acc.y + R[1][2]*sensors->acc.z,
+      .z = R[2][0]*sensors->acc.x + R[2][1]*sensors->acc.y + R[2][2]*sensors->acc.z - 1
+  };
+
+  // convert the new attitude into Euler YPR
+  float yaw = atan2f(2*(q[1]*q[2]+q[0]*q[3]) , q[0]*q[0] + q[1]*q[1] - q[2]*q[2] - q[3]*q[3]);
+  float pitch = asinf(-2*(q[1]*q[3] - q[0]*q[2]));
+  float roll = atan2f(2*(q[2]*q[3]+q[0]*q[1]) , q[0]*q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]);
+
+  // Save attitude, adjusted for the legacy CF2 body coordinate system
+  state->attitude = (attitude_t){
+      .timestamp = tick,
+      .roll = roll*RAD_TO_DEG,
+      .pitch = -pitch*RAD_TO_DEG,
+      .yaw = yaw*RAD_TO_DEG
+  };
+
+  // Save quaternion, hopefully one day this could be used in a better controller.
+  // Note that this is not adjusted for the legacy coordinate system
+  state->attitudeQuaternion = (quaternion_t){
+      .timestamp = tick,
+      .w = q[0],
+      .x = q[1],
+      .y = q[2],
+      .z = q[3]
+  };
+}
+
+
+void stateEstimatorInit(void) {
+  if (!isInit)
+  {
+    distDataQueue = xQueueCreate(DIST_QUEUE_LENGTH, sizeof(distanceMeasurement_t));
+    posDataQueue = xQueueCreate(POS_QUEUE_LENGTH, sizeof(positionMeasurement_t));
+    tdoaDataQueue = xQueueCreate(UWB_QUEUE_LENGTH, sizeof(tdoaMeasurement_t));
+    tofDataQueue = xQueueCreate(TOF_QUEUE_LENGTH, sizeof(tofMeasurement_t));
+  }
+  else
+  {
+    xQueueReset(distDataQueue);
+    xQueueReset(posDataQueue);
+    xQueueReset(tdoaDataQueue);
+    xQueueReset(tofDataQueue);
+  }
+
+  lastPrediction = xTaskGetTickCount();
+  lastBaroUpdate = xTaskGetTickCount();
+  lastTDOAUpdate = xTaskGetTickCount();
+  lastPNUpdate = xTaskGetTickCount();
+
+  accAccumulator = (Axis3f){.axis={0}};
+  gyroAccumulator = (Axis3f){.axis={0}};
+  thrustAccumulator = 0;
+  baroAccumulator.asl = 0;
+
+  accAccumulatorCount = 0;
+  gyroAccumulatorCount = 0;
+  thrustAccumulatorCount = 0;
+  baroAccumulatorCount = 0;
+
+  // TODO: Can we initialize this more intelligently?
+  S[STATE_X] = 0.5;
+  S[STATE_Y] = 0.5;
+  S[STATE_Z] = 0;
+  S[STATE_PX] = 0;
+  S[STATE_PY] = 0;
+  S[STATE_PZ] = 0;
+  S[STATE_D0] = 0;
+  S[STATE_D1] = 0;
+  S[STATE_D2] = 0;
+
+  // reset the attitude quaternion
+  q[0] = 1; q[1] = 0; q[2] = 0; q[3] = 0;
+
+  // then set the initial rotation matrix to the identity. This only affects
+  // the first prediction step, since in the finalization, after shifting
+  // attitude errors into the attitude state, the rotation matrix is updated.
+  for(int i=0; i<3; i++) { for(int j=0; j<3; j++) { R[i][j] = i==j ? 1 : 0; }}
+
+  for (int i=0; i< STATE_DIM; i++) {
+    for (int j=0; j < STATE_DIM; j++) {
+      P[i][j] = 0; // set covariances to zero (diagonals will be changed from zero in the next section)
+    }
+  }
+
+  // initialize state variances
+  P[STATE_X][STATE_X]  = powf(stdDevInitialPosition_xy, 2);
+  P[STATE_Y][STATE_Y]  = powf(stdDevInitialPosition_xy, 2);
+  P[STATE_Z][STATE_Z]  = powf(stdDevInitialPosition_z, 2);
+
+  P[STATE_PX][STATE_PX] = powf(stdDevInitialVelocity, 2);
+  P[STATE_PY][STATE_PY] = powf(stdDevInitialVelocity, 2);
+  P[STATE_PZ][STATE_PZ] = powf(stdDevInitialVelocity, 2);
+
+  P[STATE_D0][STATE_D0] = powf(stdDevInitialAttitude_rollpitch, 2);
+  P[STATE_D1][STATE_D1] = powf(stdDevInitialAttitude_rollpitch, 2);
+  P[STATE_D2][STATE_D2] = powf(stdDevInitialAttitude_yaw, 2);
+
+  varSkew = powf(stdDevInitialSkew, 2);
+
+  tdoaCount = 0;
+  isInit = true;
+}
+
+static bool stateEstimatorEnqueueExternalMeasurement(xQueueHandle queue, void *measurement)
+{
+  portBASE_TYPE result;
+  bool isInInterrupt = (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) != 0;
+
+  if (isInInterrupt) {
+    portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
+    result = xQueueSendFromISR(queue, measurement, &xHigherPriorityTaskWoken);
+    if(xHigherPriorityTaskWoken == pdTRUE)
+    {
+      portYIELD();
+    }
+  } else {
+    result = xQueueSend(queue, measurement, 0);
+  }
+  return (result==pdTRUE);
+}
+
+bool stateEstimatorEnqueueTDOA(tdoaMeasurement_t *uwb)
+{
+  return stateEstimatorEnqueueExternalMeasurement(tdoaDataQueue, (void *)uwb);
+}
+
+bool stateEstimatorEnqueuePosition(positionMeasurement_t *pos)
+{
+  return stateEstimatorEnqueueExternalMeasurement(posDataQueue, (void *)pos);
+}
+
+bool stateEstimatorEnqueueDistance(distanceMeasurement_t *dist)
+{
+  return stateEstimatorEnqueueExternalMeasurement(distDataQueue, (void *)dist);
+}
+
+bool stateEstimatorEnqueueTOF(tofMeasurement_t *tof)
+{
+  // A distance (distance) [m] to the ground along the z_B axis.
+  return stateEstimatorEnqueueExternalMeasurement(tofDataQueue, (void *)tof);
+}
+
+bool stateEstimatorTest(void)
+{
+  // TODO: Figure out what we could test?
+  return isInit;
+}
+
+LOG_GROUP_START(kalman)
+  LOG_ADD(LOG_UINT8, inFlight, &quadIsFlying)
+  LOG_ADD(LOG_FLOAT, stateX, &S[STATE_X])
+  LOG_ADD(LOG_FLOAT, stateY, &S[STATE_Y])
+  LOG_ADD(LOG_FLOAT, stateZ, &S[STATE_Z])
+  LOG_ADD(LOG_FLOAT, statePX, &S[STATE_PX])
+  LOG_ADD(LOG_FLOAT, statePY, &S[STATE_PY])
+  LOG_ADD(LOG_FLOAT, statePZ, &S[STATE_PZ])
+  LOG_ADD(LOG_FLOAT, stateD0, &S[STATE_D0])
+  LOG_ADD(LOG_FLOAT, stateD1, &S[STATE_D1])
+  LOG_ADD(LOG_FLOAT, stateD2, &S[STATE_D2])
+  LOG_ADD(LOG_FLOAT, stateSkew, &stateSkew)
+  LOG_ADD(LOG_FLOAT, varX, &P[STATE_X][STATE_X])
+  LOG_ADD(LOG_FLOAT, varY, &P[STATE_Y][STATE_Y])
+  LOG_ADD(LOG_FLOAT, varZ, &P[STATE_Z][STATE_Z])
+  LOG_ADD(LOG_FLOAT, varPX, &P[STATE_PX][STATE_PX])
+  LOG_ADD(LOG_FLOAT, varPY, &P[STATE_PY][STATE_PY])
+  LOG_ADD(LOG_FLOAT, varPZ, &P[STATE_PZ][STATE_PZ])
+  LOG_ADD(LOG_FLOAT, varD0, &P[STATE_D0][STATE_D0])
+  LOG_ADD(LOG_FLOAT, varD1, &P[STATE_D1][STATE_D1])
+  LOG_ADD(LOG_FLOAT, varD2, &P[STATE_D2][STATE_D2])
+  LOG_ADD(LOG_FLOAT, varSkew, &varSkew)
+  LOG_ADD(LOG_FLOAT, q0, &q[0])
+  LOG_ADD(LOG_FLOAT, q1, &q[1])
+  LOG_ADD(LOG_FLOAT, q2, &q[2])
+  LOG_ADD(LOG_FLOAT, q3, &q[3])
+LOG_GROUP_STOP(kalman)
+
+PARAM_GROUP_START(kalman)
+  PARAM_ADD(PARAM_UINT8, resetEstimation, &resetEstimation)
+  PARAM_ADD(PARAM_UINT8, quadIsFlying, &quadIsFlying)
+  PARAM_ADD(PARAM_FLOAT, pNAcc_xy, &procNoiseAcc_xy)
+  PARAM_ADD(PARAM_FLOAT, pNAcc_z, &procNoiseAcc_z)
+  PARAM_ADD(PARAM_FLOAT, pNVel, &procNoiseVel)
+  PARAM_ADD(PARAM_FLOAT, pNPos, &procNoisePos)
+  PARAM_ADD(PARAM_FLOAT, pNAtt, &procNoiseAtt)
+  PARAM_ADD(PARAM_FLOAT, pNSkew, &procNoiseSkew)
+  PARAM_ADD(PARAM_FLOAT, mNBaro, &measNoiseBaro)
+  PARAM_ADD(PARAM_FLOAT, mNGyro_rollpitch, &measNoiseGyro_rollpitch)
+  PARAM_ADD(PARAM_FLOAT, mNGyro_yaw, &measNoiseGyro_yaw)
+PARAM_GROUP_STOP(kalman)
diff --git a/crazyflie-firmware-src/src/modules/src/ext_position.c b/crazyflie-firmware-src/src/modules/src/ext_position.c
new file mode 100644
index 0000000000000000000000000000000000000000..7677075624c3c933789ba0c5c2d3f13f685ec084
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/ext_position.c
@@ -0,0 +1,95 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ */
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "ext_position.h"
+#include "crtp.h"
+#include "log.h"
+
+#ifdef ESTIMATOR_TYPE_kalman
+#include "estimator_kalman.h"
+#endif
+
+/**
+ * Position data cache
+ */
+typedef struct
+{
+  struct CrtpExtPosition targetVal[2];
+  bool activeSide;
+  uint32_t timestamp; // FreeRTOS ticks
+} ExtPositionCache;
+
+// Struct for logging position information
+static positionMeasurement_t ext_pos;
+static ExtPositionCache crtpExtPosCache;
+static void extPositionCrtpCB(CRTPPacket* pk);
+
+static bool isInit = false;
+
+void extPositionInit()
+{
+  if (isInit) {
+    return;
+  }
+
+  crtpRegisterPortCB(CRTP_PORT_POSITION, extPositionCrtpCB);
+  isInit = true;
+}
+
+static void extPositionCrtpCB(CRTPPacket* pk)
+{
+  crtpExtPosCache.targetVal[!crtpExtPosCache.activeSide] = *((struct CrtpExtPosition*)pk->data);
+  crtpExtPosCache.activeSide = !crtpExtPosCache.activeSide;
+  crtpExtPosCache.timestamp = xTaskGetTickCount();
+}
+
+
+bool getExtPosition(state_t *state)
+{
+  // Only use position information if it's valid and recent
+  if ((xTaskGetTickCount() - crtpExtPosCache.timestamp) < M2T(5)) {
+    // Get the updated position from the mocap
+    ext_pos.x = crtpExtPosCache.targetVal[crtpExtPosCache.activeSide].x;
+    ext_pos.y = crtpExtPosCache.targetVal[crtpExtPosCache.activeSide].y;
+    ext_pos.z = crtpExtPosCache.targetVal[crtpExtPosCache.activeSide].z;
+    ext_pos.stdDev = 0.01;
+#ifdef ESTIMATOR_TYPE_kalman
+    stateEstimatorEnqueuePosition(&ext_pos);
+#endif
+    return true;
+  }
+  return false;
+}
+
+LOG_GROUP_START(ext_pos)
+  LOG_ADD(LOG_FLOAT, X, &ext_pos.x)
+  LOG_ADD(LOG_FLOAT, Y, &ext_pos.y)
+  LOG_ADD(LOG_FLOAT, Z, &ext_pos.z)
+LOG_GROUP_STOP(ext_pos)
+
diff --git a/crazyflie-firmware-src/src/modules/src/extrx.c b/crazyflie-firmware-src/src/modules/src/extrx.c
new file mode 100644
index 0000000000000000000000000000000000000000..b583b5ec7f787771a3c1e2640b63496638bd82f3
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/extrx.c
@@ -0,0 +1,187 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2013 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * extrx.c - Module to handle external receiver inputs
+ */
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+
+#include "stm32fxxx.h"
+#include "config.h"
+#include "system.h"
+#include "nvicconf.h"
+#include "commander.h"
+#include "uart1.h"
+#include "cppm.h"
+
+#define DEBUG_MODULE  "EXTRX"
+#include "debug.h"
+#include "log.h"
+
+#define ENABLE_CPPM
+#define ENABLE_EXTRX_LOG
+
+
+#define EXTRX_NR_CHANNELS  8
+
+#define EXTRX_CH_TRUST     2
+#define EXTRX_CH_ROLL      0
+#define EXTRX_CH_PITCH     1
+#define EXTRX_CH_YAW       3
+
+#define EXTRX_SIGN_ROLL    (-1)
+#define EXTRX_SIGN_PITCH   (-1)
+#define EXTRX_SIGN_YAW     (-1)
+
+#define EXTRX_SCALE_ROLL   (40.0f)
+#define EXTRX_SCALE_PITCH  (40.0f)
+#define EXTRX_SCALE_YAW    (400.0f)
+
+static struct CommanderCrtpValues commanderPacket;
+static uint16_t ch[EXTRX_NR_CHANNELS];
+
+static void extRxTask(void *param);
+static void extRxDecodeCppm(void);
+static void extRxDecodeChannels(void);
+
+void extRxInit(void)
+{
+
+#ifdef ENABLE_CPPM
+  cppmInit();
+#endif
+
+#ifdef ENABLE_SPEKTRUM
+  uart1Init();
+#endif
+
+
+  xTaskCreate(extRxTask, EXTRX_TASK_NAME,
+              EXTRX_TASK_STACKSIZE, NULL, EXTRX_TASK_PRI, NULL);
+}
+
+static void extRxTask(void *param)
+{
+
+  //Wait for the system to be fully started
+  systemWaitStart();
+
+  while (true)
+  {
+    extRxDecodeCppm();
+  }
+}
+
+static void extRxDecodeChannels(void)
+{
+  commanderPacket.thrust = cppmConvert2uint16(ch[EXTRX_CH_TRUST]);
+  commanderPacket.roll = EXTRX_SIGN_ROLL * cppmConvert2Float(ch[EXTRX_CH_ROLL], -EXTRX_SCALE_ROLL, EXTRX_SCALE_ROLL);
+  commanderPacket.pitch = EXTRX_SIGN_PITCH * cppmConvert2Float(ch[EXTRX_CH_PITCH], -EXTRX_SCALE_PITCH, EXTRX_SCALE_PITCH);
+  commanderPacket.yaw = EXTRX_SIGN_YAW * cppmConvert2Float(ch[EXTRX_CH_YAW], -EXTRX_SCALE_YAW, EXTRX_SCALE_YAW);
+  commanderExtrxSet(&commanderPacket);
+}
+
+static void extRxDecodeCppm(void)
+{
+  uint16_t ppm;
+  static uint8_t currChannel = 0;
+
+  if (cppmGetTimestamp(&ppm) == pdTRUE)
+  {
+    if (cppmIsAvailible() && ppm < 2100)
+    {
+      if (currChannel < EXTRX_NR_CHANNELS)
+      {
+        ch[currChannel] = ppm;
+      }
+      currChannel++;
+    }
+    else
+    {
+      extRxDecodeChannels();
+      currChannel = 0;
+    }
+  }
+}
+
+#if 0
+static void extRxDecodeSpektrum(void)
+{
+  while (SerialAvailable(SPEK_SERIAL_PORT) > SPEK_FRAME_SIZE)
+  { // More than a frame?  More bytes implies we weren't called for multiple frame times.  We do not want to process 'old' frames in the buffer.
+    for (uint8_t i = 0; i < SPEK_FRAME_SIZE; i++)
+    {
+      SerialRead(SPEK_SERIAL_PORT);
+    }  //Toss one full frame of bytes.
+  }
+  if (spekFrameFlags == 0x01)
+  { //The interrupt handler saw at least one valid frame start since we were last here.
+    if (SerialAvailable(SPEK_SERIAL_PORT) == SPEK_FRAME_SIZE)
+    {  //A complete frame? If not, we'll catch it next time we are called.
+      SerialRead(SPEK_SERIAL_PORT);
+      SerialRead(SPEK_SERIAL_PORT);        //Eat the header bytes
+      for (uint8_t b = 2; b < SPEK_FRAME_SIZE; b += 2)
+      {
+        uint8_t bh = SerialRead(SPEK_SERIAL_PORT);
+        uint8_t bl = SerialRead(SPEK_SERIAL_PORT);
+        uint8_t spekChannel = 0x0F & (bh >> SPEK_CHAN_SHIFT);
+      if (spekChannel < RC_CHANS) rcValue[spekChannel] = 988 + ((((uint16_t)(bh & SPEK_CHAN_MASK) << 8) + bl) SPEK_DATA_SHIFT);
+    }
+    spekFrameFlags = 0x00;
+    spekFrameData = 0x01;
+#if defined(FAILSAFE)
+    if(failsafeCnt > 20) failsafeCnt -= 20;
+    else failsafeCnt = 0;   // Valid frame, clear FailSafe counter
+#endif
+  }
+  else
+  { //Start flag is on, but not enough bytes means there is an incomplete frame in buffer.  This could be OK, if we happened to be called in the middle of a frame.  Or not, if it has been a while since the start flag was set.
+    uint32_t spekInterval = (timer0_overflow_count << 8)
+        * (64 / clockCyclesPerMicrosecond()) - spekTimeLast;
+    if (spekInterval > 2500)
+    {
+      spekFrameFlags = 0;
+    }  //If it has been a while, make the interrupt handler start over.
+  }
+}
+#endif
+
+/* Loggable variables */
+#ifdef ENABLE_EXTRX_LOG
+LOG_GROUP_START(extrx)
+LOG_ADD(LOG_UINT16, ch0, &ch[0])
+LOG_ADD(LOG_UINT16, ch1, &ch[1])
+LOG_ADD(LOG_UINT16, ch2, &ch[2])
+LOG_ADD(LOG_UINT16, ch3, &ch[3])
+LOG_ADD(LOG_UINT16, thrust, &commanderPacket.thrust)
+LOG_ADD(LOG_FLOAT, roll, &commanderPacket.roll)
+LOG_ADD(LOG_FLOAT, pitch, &commanderPacket.pitch)
+LOG_ADD(LOG_FLOAT, yaw, &commanderPacket.yaw)
+LOG_GROUP_STOP(extrx)
+#endif
+
+
diff --git a/crazyflie-firmware-src/src/modules/src/info.c b/crazyflie-firmware-src/src/modules/src/info.c
new file mode 100644
index 0000000000000000000000000000000000000000..e52b36a538ca162ab4676c08926c05cfb6e34a5e
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/info.c
@@ -0,0 +1,176 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * info.c - Receive information requests and send them back to the client
+ */
+
+#include <string.h>
+#include <math.h>
+
+/*FreeRtos includes*/
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "crtp.h"
+#include "info.h"
+#include "version.h"
+#include "pm.h"
+
+//CPUID access
+static const unsigned int * CpuId = (unsigned int*)0x1FFFF7E8; 
+
+typedef enum {
+  infoCopterNr = 0x00,
+  infoBatteryNr = 0x01,
+  infoWarningNr = 0x03
+} InfoNbr;
+
+typedef enum {
+  infoName = 0x00,
+  infoVersion = 0x01,
+  infoCpuId = 0x02
+} infoId;
+
+typedef enum {
+  batteryVoltage = 0x00,
+  batteryMin = 0x01,
+  batteryMax = 0x02
+} batteryId;
+
+typedef enum {
+  warningBattery = 0x00
+} warningId;
+
+
+void infoTask(void *param);
+
+void infoInit()
+{
+  xTaskCreate(infoTask, INFO_TASK_NAME,
+              INFO_TASK_STACKSIZE, NULL, INFO_TASK_PRI, NULL);
+  crtpInitTaskQueue(crtpInfo);
+}
+
+void infoTask(void *param)
+{
+  CRTPPacket p;
+  int i;
+  static int ctr=0;
+
+  while (TRUE)
+  {
+    if (crtpReceivePacketWait(crtpInfo, &p, 1000) == pdTRUE)
+    {
+      InfoNbr infoNbr = CRTP_GET_NBR(p.port);
+
+      switch (infoNbr)
+      {
+        case infoCopterNr:
+          if (p.data[0] == infoName)
+          {
+            p.data[1] = 0x90;
+            p.data[2] = 0x00;   //Version 0.9.0 (Crazyflie)
+            strcpy((char*)&p.data[3], "CrazyFlie");
+            
+            p.size = 3+strlen("CrazyFlie");
+            crtpSendPacket(&p);
+          } else if (p.data[0] == infoVersion) {
+            i=1;
+            
+            strncpy((char*)&p.data[i], V_SLOCAL_REVISION, 31-i);
+            i += strlen(V_SLOCAL_REVISION);
+            
+            if (i<31) p.data[i++] = ',';
+            
+            strncpy((char*)&p.data[i], V_SREVISION, 31-i);
+            i += strlen(V_SREVISION);
+            
+            if (i<31) p.data[i++] = ',';
+            
+            strncpy((char*)&p.data[i], V_STAG, 31-i);
+            i += strlen(V_STAG);
+            
+            if (i<31) p.data[i++] = ',';
+            if (i<31) p.data[i++] = V_MODIFIED?'M':'C';
+            
+            p.size = (i<31)?i:31;
+            crtpSendPacket(&p);
+          } else if (p.data[0] == infoCpuId) {
+            memcpy((char*)&p.data[1], (char*)CpuId, 12);
+            
+            p.size = 13;
+            crtpSendPacket(&p);
+          }
+             
+          break;
+        case infoBatteryNr:
+          if (p.data[0] == batteryVoltage)
+          {
+            float value = pmGetBatteryVoltage();
+            
+            memcpy(&p.data[1], (char*)&value, 4);
+            
+            p.size = 5;
+            crtpSendPacket(&p);
+          } else if (p.data[0] == batteryMax) {
+            float value = pmGetBatteryVoltageMax();
+            
+            memcpy(&p.data[1], (char*)&value, 4);
+            
+            p.size = 5;
+            crtpSendPacket(&p);
+          } else if (p.data[0] == batteryMin) {
+            float value = pmGetBatteryVoltageMin();
+            
+            memcpy(&p.data[1], (char*)&value, 4);
+            
+            p.size = 5;
+            crtpSendPacket(&p);
+          }
+          break;
+        default:
+          break;
+      }
+    }
+    
+    // Send a warning message if the battery voltage drops under 3.3V
+    // This is sent every 5 info transaction or every 5 seconds
+    if (ctr++>5) {
+      ctr=0;
+      
+      if (pmGetBatteryVoltageMin() < INFO_BAT_WARNING)
+      {
+        float value = pmGetBatteryVoltage();
+        
+        p.port = CRTP_PORT(0,8,3);
+        p.data[0] = 0;
+        memcpy(&p.data[1], (char*)&value, 4);
+        
+        p.size = 5;
+        crtpSendPacket(&p);
+      }
+    }
+    
+  }
+}
+
diff --git a/crazyflie-firmware-src/src/modules/src/log.c b/crazyflie-firmware-src/src/modules/src/log.c
new file mode 100644
index 0000000000000000000000000000000000000000..2bc547fdb93c35a15313e1a1c30ebc16f7dc898b
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/log.c
@@ -0,0 +1,743 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * log.c: Dynamic log system
+ */
+
+/* The TOC logic is mainly based on param.c
+ * FIXME: See if we can factorise the TOC code */
+
+#include <string.h>
+#include <errno.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "timers.h"
+#include "semphr.h"
+
+#include "config.h"
+#include "crtp.h"
+#include "log.h"
+#include "crc.h"
+#include "worker.h"
+#include "num.h"
+
+#include "console.h"
+#include "cfassert.h"
+
+#if 0
+#define LOG_DEBUG(fmt, ...) DEBUG_PRINT("D/log " fmt, ## __VA_ARGS__)
+#define LOG_ERROR(fmt, ...) DEBUG_PRINT("E/log " fmt, ## __VA_ARGS__)
+#else
+#define LOG_DEBUG(...)
+#define LOG_ERROR(...)
+#endif
+
+
+static const uint8_t typeLength[] = {
+  [LOG_UINT8]  = 1,
+  [LOG_UINT16] = 2,
+  [LOG_UINT32] = 4,
+  [LOG_INT8]   = 1,
+  [LOG_INT16]  = 2,
+  [LOG_INT32]  = 4,
+  [LOG_FLOAT]  = 4,
+  [LOG_FP16]   = 2,
+};
+
+// Maximum log payload length (4 bytes are used for block id and timestamp)
+#define LOG_MAX_LEN 26
+
+/* Log packet parameters storage */
+#define LOG_MAX_OPS 64
+#define LOG_MAX_BLOCKS 8
+struct log_ops {
+  struct log_ops * next;
+  uint8_t storageType : 4;
+  uint8_t logType     : 4;
+  void * variable;
+};
+
+struct log_block {
+  int id;
+  xTimerHandle timer;
+  struct log_ops * ops;
+};
+
+static struct log_ops logOps[LOG_MAX_OPS];
+static struct log_block logBlocks[LOG_MAX_BLOCKS];
+static xSemaphoreHandle logLock;
+
+struct ops_setting {
+    uint8_t logType;
+    uint8_t id;
+} __attribute__((packed));
+
+
+#define TOC_CH      0
+#define CONTROL_CH  1
+#define LOG_CH      2
+
+#define CMD_GET_ITEM 0
+#define CMD_GET_INFO 1
+
+#define CONTROL_CREATE_BLOCK 0
+#define CONTROL_APPEND_BLOCK 1
+#define CONTROL_DELETE_BLOCK 2
+#define CONTROL_START_BLOCK  3
+#define CONTROL_STOP_BLOCK   4
+#define CONTROL_RESET        5
+
+#define BLOCK_ID_FREE -1
+
+//Private functions
+static void logTask(void * prm);
+static void logTOCProcess(int command);
+static void logControlProcess(void);
+
+void logRunBlock(void * arg);
+void logBlockTimed(xTimerHandle timer);
+
+//These are set by the Linker
+extern struct log_s _log_start;
+extern struct log_s _log_stop;
+
+//Pointer to the logeters list and length of it
+static struct log_s * logs;
+static int logsLen;
+static uint32_t logsCrc;
+static int logsCount = 0;
+
+static bool isInit = false;
+
+/* Log management functions */
+static int logAppendBlock(int id, struct ops_setting * settings, int len);
+static int logCreateBlock(unsigned char id, struct ops_setting * settings, int len);
+static int logDeleteBlock(int id);
+static int logStartBlock(int id, unsigned int period);
+static int logStopBlock(int id);
+static void logReset();
+
+void logInit(void)
+{
+  int i;
+
+  if(isInit)
+    return;
+
+  logs = &_log_start;
+  logsLen = &_log_stop - &_log_start;
+  logsCrc = crcSlow(logs, logsLen*sizeof(logs[0]));
+
+  // Big lock that protects the log datastructures
+  logLock = xSemaphoreCreateMutex();
+
+  for (i=0; i<logsLen; i++)
+  {
+    if(!(logs[i].type & LOG_GROUP))
+      logsCount++;
+  }
+
+  //Manually free all log blocks
+  for(i=0; i<LOG_MAX_BLOCKS; i++)
+    logBlocks[i].id = BLOCK_ID_FREE;
+
+  //Init data structures and set the log subsystem in a known state
+  logReset();
+
+  //Start the log task
+  xTaskCreate(logTask, LOG_TASK_NAME,
+              LOG_TASK_STACKSIZE, NULL, LOG_TASK_PRI, NULL);
+
+  isInit = true;
+}
+
+bool logTest(void)
+{
+  return isInit;
+}
+
+static CRTPPacket p;
+
+void logTask(void * prm)
+{
+	crtpInitTaskQueue(CRTP_PORT_LOG);
+
+	while(1) {
+		crtpReceivePacketBlock(CRTP_PORT_LOG, &p);
+
+		xSemaphoreTake(logLock, portMAX_DELAY);
+		if (p.channel==TOC_CH)
+		  logTOCProcess(p.data[0]);
+		if (p.channel==CONTROL_CH)
+		  logControlProcess();
+		xSemaphoreGive(logLock);
+	}
+}
+
+void logTOCProcess(int command)
+{
+  int ptr = 0;
+  char * group = "plop";
+  int n=0;
+
+  switch (command)
+  {
+  case CMD_GET_INFO: //Get info packet about the log implementation
+    LOG_DEBUG("Packet is TOC_GET_INFO\n");
+    ptr = 0;
+    group = "";
+    p.header=CRTP_HEADER(CRTP_PORT_LOG, TOC_CH);
+    p.size=8;
+    p.data[0]=CMD_GET_INFO;
+    p.data[1]=logsCount;
+    memcpy(&p.data[2], &logsCrc, 4);
+    p.data[6]=LOG_MAX_BLOCKS;
+    p.data[7]=LOG_MAX_OPS;
+    crtpSendPacket(&p);
+    break;
+  case CMD_GET_ITEM:  //Get log variable
+    LOG_DEBUG("Packet is TOC_GET_ITEM Id: %d\n", p.data[1]);
+    for (ptr=0; ptr<logsLen; ptr++) //Ptr points a group
+    {
+      if (logs[ptr].type & LOG_GROUP)
+      {
+        if (logs[ptr].type & LOG_START)
+          group = logs[ptr].name;
+        else
+          group = "";
+      }
+      else                          //Ptr points a variable
+      {
+        if (n==p.data[1])
+          break;
+        n++;
+      }
+    }
+
+    if (ptr<logsLen)
+    {
+      LOG_DEBUG("    Item is \"%s\":\"%s\"\n", group, logs[ptr].name);
+      p.header=CRTP_HEADER(CRTP_PORT_LOG, TOC_CH);
+      p.data[0]=CMD_GET_ITEM;
+      p.data[1]=n;
+      p.data[2]=logs[ptr].type;
+      memcpy(p.data+3, group, strlen(group)+1);
+      memcpy(p.data+3+strlen(group)+1, logs[ptr].name, strlen(logs[ptr].name)+1);
+      p.size=3+2+strlen(group)+strlen(logs[ptr].name);
+      crtpSendPacket(&p);
+    } else {
+      LOG_DEBUG("    Index out of range!");
+      p.header=CRTP_HEADER(CRTP_PORT_LOG, TOC_CH);
+      p.data[0]=CMD_GET_ITEM;
+      p.size=1;
+      crtpSendPacket(&p);
+    }
+    break;
+  }
+}
+
+void logControlProcess()
+{
+  int ret = ENOEXEC;
+
+  switch(p.data[0])
+  {
+    case CONTROL_CREATE_BLOCK:
+      ret = logCreateBlock( p.data[1],
+                            (struct ops_setting*)&p.data[2],
+                            (p.size-2)/sizeof(struct ops_setting) );
+      break;
+    case CONTROL_APPEND_BLOCK:
+      ret = logAppendBlock( p.data[1],
+                            (struct ops_setting*)&p.data[2],
+                            (p.size-2)/sizeof(struct ops_setting) );
+      break;
+    case CONTROL_DELETE_BLOCK:
+      ret = logDeleteBlock( p.data[1] );
+      break;
+    case CONTROL_START_BLOCK:
+      ret = logStartBlock( p.data[1], p.data[2]*10);
+      break;
+    case CONTROL_STOP_BLOCK:
+      ret = logStopBlock( p.data[1] );
+      break;
+    case CONTROL_RESET:
+      logReset();
+      ret = 0;
+      break;
+  }
+
+  //Commands answer
+  p.data[2] = ret;
+  p.size = 3;
+  crtpSendPacket(&p);
+}
+
+static int logCreateBlock(unsigned char id, struct ops_setting * settings, int len)
+{
+  int i;
+
+  for (i=0; i<LOG_MAX_BLOCKS; i++)
+    if (id == logBlocks[i].id) return EEXIST;
+
+  for (i=0; i<LOG_MAX_BLOCKS; i++)
+    if (logBlocks[i].id == BLOCK_ID_FREE) break;
+
+  if (i == LOG_MAX_BLOCKS)
+    return ENOMEM;
+
+  logBlocks[i].id = id;
+  logBlocks[i].timer = xTimerCreate( "logTimer", M2T(1000),
+                                     pdTRUE, &logBlocks[i], logBlockTimed );
+  logBlocks[i].ops = NULL;
+
+  if (logBlocks[i].timer == NULL)
+  {
+	logBlocks[i].id = BLOCK_ID_FREE;
+	return ENOMEM;
+  }
+
+  LOG_DEBUG("Added block ID %d\n", id);
+
+  return logAppendBlock(id, settings, len);
+}
+
+static int blockCalcLength(struct log_block * block);
+static struct log_ops * opsMalloc();
+static void opsFree(struct log_ops * ops);
+static void blockAppendOps(struct log_block * block, struct log_ops * ops);
+static int variableGetIndex(int id);
+
+static int logAppendBlock(int id, struct ops_setting * settings, int len)
+{
+  int i;
+  struct log_block * block;
+
+  LOG_DEBUG("Appending %d variable to block %d\n", len, id);
+
+  for (i=0; i<LOG_MAX_BLOCKS; i++)
+    if (logBlocks[i].id == id) break;
+
+  if (i >= LOG_MAX_BLOCKS) {
+    LOG_ERROR("Trying to append block id %d that doesn't exist.", id);
+    return ENOENT;
+  }
+
+  block = &logBlocks[i];
+
+  for (i=0; i<len; i++)
+  {
+    int currentLength = blockCalcLength(block);
+    struct log_ops * ops;
+    int varId;
+
+    if ((currentLength + typeLength[settings[i].logType&0x0F])>LOG_MAX_LEN) {
+      LOG_ERROR("Trying to append a full block. Block id %d.\n", id);
+      return E2BIG;
+    }
+
+    ops = opsMalloc();
+
+    if(!ops) {
+      LOG_ERROR("No more ops memory free!\n");
+      return ENOMEM;
+    }
+
+    if (settings[i].id != 255)  //TOC variable
+    {
+      varId = variableGetIndex(settings[i].id);
+
+      if (varId<0) {
+        LOG_ERROR("Trying to add variable Id %d that does not exists.", settings[i].id);
+        return ENOENT;
+      }
+
+      ops->variable    = logs[varId].address;
+      ops->storageType = logs[varId].type;
+      ops->logType     = settings[i].logType&0x0F;
+
+      LOG_DEBUG("Appended variable %d to block %d\n", settings[i].id, id);
+    } else {                     //Memory variable
+      //TODO: Check that the address is in ram
+      ops->variable    = (void*)(&settings[i]+1);
+      ops->storageType = (settings[i].logType>>4)&0x0F;
+      ops->logType     = settings[i].logType&0x0F;
+      i += 2;
+
+      LOG_DEBUG("Appended var addr 0x%x to block %d\n", (int)ops->variable, id);
+    }
+    blockAppendOps(block, ops);
+
+    LOG_DEBUG("   Now lenght %d\n", blockCalcLength(block));
+  }
+
+  return 0;
+}
+
+static int logDeleteBlock(int id)
+{
+  int i;
+  struct log_ops * ops;
+  struct log_ops * opsNext;
+
+  for (i=0; i<LOG_MAX_BLOCKS; i++)
+    if (logBlocks[i].id == id) break;
+
+  if (i >= LOG_MAX_BLOCKS) {
+    LOG_ERROR("trying to delete block id %d that doesn't exist.", id);
+    return ENOENT;
+  }
+
+  ops = logBlocks[i].ops;
+  while (ops)
+  {
+    opsNext = ops->next;
+    opsFree(ops);
+    ops = opsNext;
+  }
+
+  if (logBlocks[i].timer != 0) {
+    xTimerStop(logBlocks[i].timer, portMAX_DELAY);
+    xTimerDelete(logBlocks[i].timer, portMAX_DELAY);
+    logBlocks[i].timer = 0;
+  }
+
+  logBlocks[i].id = BLOCK_ID_FREE;
+  return 0;
+}
+
+static int logStartBlock(int id, unsigned int period)
+{
+  int i;
+
+  for (i=0; i<LOG_MAX_BLOCKS; i++)
+    if (logBlocks[i].id == id) break;
+
+  if (i >= LOG_MAX_BLOCKS) {
+    LOG_ERROR("Trying to start block id %d that doesn't exist.", id);
+    return ENOENT;
+  }
+
+  LOG_DEBUG("Starting block %d with period %dms\n", id, period);
+
+  if (period>0)
+  {
+    xTimerChangePeriod(logBlocks[i].timer, M2T(period), 100);
+    xTimerStart(logBlocks[i].timer, 100);
+  } else {
+    // single-shoot run
+    workerSchedule(logRunBlock, &logBlocks[i]);
+  }
+
+  return 0;
+}
+
+static int logStopBlock(int id)
+{
+  int i;
+
+  for (i=0; i<LOG_MAX_BLOCKS; i++)
+    if (logBlocks[i].id == id) break;
+
+  if (i >= LOG_MAX_BLOCKS) {
+    LOG_ERROR("Trying to stop block id %d that doesn't exist.\n", id);
+    return ENOENT;
+  }
+
+  xTimerStop(logBlocks[i].timer, portMAX_DELAY);
+
+  return 0;
+}
+
+/* This function is called by the timer subsystem */
+void logBlockTimed(xTimerHandle timer)
+{
+  workerSchedule(logRunBlock, pvTimerGetTimerID(timer));
+}
+
+/* Appends data to a packet if space is available; returns false on failure. */
+static bool appendToPacket(CRTPPacket * pk, const void * data, size_t n) {
+  if (pk->size <= CRTP_MAX_DATA_SIZE - n)
+  {
+    memcpy(&pk->data[pk->size], data, n);
+    pk->size += n;
+    return true;
+  }
+  else return false;
+}
+
+/* This function is usually called by the worker subsystem */
+void logRunBlock(void * arg)
+{
+  struct log_block *blk = arg;
+  struct log_ops *ops = blk->ops;
+  static CRTPPacket pk;
+  unsigned int timestamp;
+
+  xSemaphoreTake(logLock, portMAX_DELAY);
+
+  timestamp = ((long long)xTaskGetTickCount())/portTICK_RATE_MS;
+
+  pk.header = CRTP_HEADER(CRTP_PORT_LOG, LOG_CH);
+  pk.size = 4;
+  pk.data[0] = blk->id;
+  pk.data[1] = timestamp&0x0ff;
+  pk.data[2] = (timestamp>>8)&0x0ff;
+  pk.data[3] = (timestamp>>16)&0x0ff;
+
+  while (ops)
+  {
+    float variable;
+    int valuei = 0;
+    float valuef = 0;
+
+    // FPU instructions must run on aligned data. Make sure it is.
+    variable = *(float *)ops->variable;
+
+    switch(ops->storageType)
+    {
+      case LOG_UINT8:
+        valuei = *(uint8_t *)&variable;
+        break;
+      case LOG_INT8:
+        valuei = *(int8_t *)&variable;
+        break;
+      case LOG_UINT16:
+        valuei = *(uint16_t *)&variable;
+        break;
+      case LOG_INT16:
+        valuei = *(int16_t *)&variable;
+        break;
+      case LOG_UINT32:
+        valuei = *(uint32_t *)&variable;
+        break;
+      case LOG_INT32:
+        valuei = *(int32_t *)&variable;
+        break;
+      case LOG_FLOAT:
+        valuei = *(float *)&variable;
+        break;
+    }
+
+    if (ops->logType == LOG_FLOAT || ops->logType == LOG_FP16)
+    {
+      if (ops->storageType == LOG_FLOAT)
+        valuef = *(float *)&variable;
+      else
+        valuef = valuei;
+
+      // Try to append the next item to the packet.  If we run out of space,
+      // drop this and subsequent items.
+      if (ops->logType == LOG_FLOAT)
+      {
+        if (!appendToPacket(&pk, &valuef, 4)) break;
+      }
+      else
+      {
+        valuei = single2half(valuef);
+        if (!appendToPacket(&pk, &valuei, 2)) break;
+      }
+    }
+    else  //logType is an integer
+    {
+      if (!appendToPacket(&pk, &valuei, typeLength[ops->logType])) break;
+    }
+
+    ops = ops->next;
+  }
+
+  xSemaphoreGive(logLock);
+
+  // Check if the connection is still up, oherwise disable
+  // all the logging and flush all the CRTP queues.
+  if (!crtpIsConnected())
+  {
+    logReset();
+    crtpReset();
+  }
+  else
+  {
+    crtpSendPacket(&pk);
+  }
+}
+
+static int variableGetIndex(int id)
+{
+  int i;
+  int n=0;
+
+  for (i=0; i<logsLen; i++)
+  {
+    if(!(logs[i].type & LOG_GROUP))
+    {
+      if(n==id)
+        break;
+      n++;
+    }
+  }
+
+  if (i>=logsLen)
+    return -1;
+
+  return i;
+}
+
+static struct log_ops * opsMalloc()
+{
+  int i;
+
+  for (i=0;i<LOG_MAX_OPS; i++)
+      if (logOps[i].variable == NULL) break;
+
+  if (i >= LOG_MAX_OPS)
+      return NULL;
+
+  return &logOps[i];
+}
+
+static void opsFree(struct log_ops * ops)
+{
+  ops->variable = NULL;
+}
+
+static int blockCalcLength(struct log_block * block)
+{
+  struct log_ops * ops;
+  int len = 0;
+
+  for (ops = block->ops; ops; ops = ops->next)
+    len += typeLength[ops->logType];
+
+  return len;
+}
+
+void blockAppendOps(struct log_block * block, struct log_ops * ops)
+{
+  struct log_ops * o;
+
+  ops->next = NULL;
+
+  if (block->ops == NULL)
+    block->ops = ops;
+  else
+  {
+    for (o = block->ops; o->next; o = o->next);
+
+    o->next = ops;
+  }
+}
+
+static void logReset(void)
+{
+  int i;
+
+  if (isInit)
+  {
+    //Stop and delete all started log blocks
+    for(i=0; i<LOG_MAX_BLOCKS; i++)
+      if (logBlocks[i].id != -1)
+      {
+        logStopBlock(logBlocks[i].id);
+        logDeleteBlock(logBlocks[i].id);
+      }
+  }
+
+  //Force free all the log block objects
+  for(i=0; i<LOG_MAX_BLOCKS; i++)
+    logBlocks[i].id = BLOCK_ID_FREE;
+
+  //Force free the log ops
+  for (i=0; i<LOG_MAX_OPS; i++)
+    logOps[i].variable = NULL;
+}
+
+/* Public API to access log TOC from within the copter */
+int logGetVarId(char* group, char* name)
+{
+  int i;
+  char * currgroup = "";
+
+  for(i=0; i<logsLen; i++)
+  {
+    if (logs[i].type & LOG_GROUP) {
+      if (logs[i].type & LOG_START)
+        currgroup = logs[i].name;
+    } if ((!strcmp(group, currgroup)) && (!strcmp(name, logs[i].name)))
+      return i;
+  }
+
+  return -1;
+}
+
+int logGetInt(int varid)
+{
+  int valuei = 0;
+
+  ASSERT(varid >= 0);
+
+  switch(logs[varid].type)
+  {
+    case LOG_UINT8:
+      valuei = *(uint8_t *)logs[varid].address;
+      break;
+    case LOG_INT8:
+      valuei = *(int8_t *)logs[varid].address;
+      break;
+    case LOG_UINT16:
+      valuei = *(uint16_t *)logs[varid].address;
+      break;
+    case LOG_INT16:
+      valuei = *(int16_t *)logs[varid].address;
+      break;
+    case LOG_UINT32:
+      valuei = *(uint32_t *)logs[varid].address;
+      break;
+    case LOG_INT32:
+      valuei = *(int32_t *)logs[varid].address;
+      break;
+    case LOG_FLOAT:
+      valuei = *(float *)logs[varid].address;
+      break;
+  }
+
+  return valuei;
+}
+
+float logGetFloat(int varid)
+{
+  ASSERT(varid >= 0);
+
+  if (logs[varid].type == LOG_FLOAT)
+    return *(float *)logs[varid].address;
+
+  return logGetInt(varid);
+}
+
+unsigned int logGetUint(int varid)
+{
+  return (unsigned int)logGetInt(varid);
+}
diff --git a/crazyflie-firmware-src/src/modules/src/mem.c b/crazyflie-firmware-src/src/modules/src/mem.c
new file mode 100644
index 0000000000000000000000000000000000000000..a80fa3ae687c717612a5d8d2a2b6af1d62d95d22
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/mem.c
@@ -0,0 +1,328 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012 BitCraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * mem.c: Memory module. Handles one-wire and eeprom memory functions over crtp link.
+ */
+
+#include <string.h>
+#include <errno.h>
+#include <stdint.h>
+#include <stdbool.h>
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "timers.h"
+#include "semphr.h"
+
+#include "config.h"
+#include "crtp.h"
+#include "mem.h"
+#include "ow.h"
+#include "eeprom.h"
+#ifdef PLATFORM_CF2
+#include "ledring12.h"
+#endif
+
+
+#include "console.h"
+#include "cfassert.h"
+#include "debug.h"
+
+#if 0
+#define MEM_DEBUG(fmt, ...) DEBUG_PRINT("D/log " fmt, ## __VA_ARGS__)
+#define MEM_ERROR(fmt, ...) DEBUG_PRINT("E/log " fmt, ## __VA_ARGS__)
+#else
+#define MEM_DEBUG(...)
+#define MEM_ERROR(...)
+#endif
+
+
+// Maximum log payload length
+#define MEM_MAX_LEN 30
+
+#define SETTINGS_CH     0
+#define READ_CH         1
+#define WRITE_CH        2
+
+#define CMD_GET_NBR     1
+#define CMD_GET_INFO    2
+
+#ifdef PLATFORM_CF1
+#define NBR_EEPROM      0
+#else
+#define NBR_EEPROM      1
+#endif
+
+#define EEPROM_ID       0x00
+#ifdef PLATFORM_CF1
+  #define NBR_LEDMEM      0
+  uint8_t ledringmem[1];
+#else
+  #define NBR_LEDMEM      1
+#endif
+#define LEDMEM_ID       0x01
+
+#define NBR_STATIC_MEM  (NBR_EEPROM + NBR_LEDMEM)
+
+#define MEM_TYPE_EEPROM 0x00
+#define MEM_TYPE_OW     0x01
+#define MEM_TYPE_LED12  0x10
+
+
+//Private functions
+static void memTask(void * prm);
+static void memSettingsProcess(int command);
+static void memWriteProcess(void);
+static void memReadProcess(void);
+
+
+static bool isInit = false;
+
+static uint8_t nbrOwMems = 0;
+static OwSerialNum serialNbr;
+static const OwSerialNum eepromSerialNum =
+{
+  .data = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, EEPROM_I2C_ADDR}
+};
+static uint32_t memSize;
+static CRTPPacket p;
+
+void memInit(void)
+{
+  if(isInit)
+    return;
+
+  if (owScan(&nbrOwMems))
+    isInit = true;
+  else
+    isInit = false;
+  
+  //Start the mem task
+  xTaskCreate(memTask, MEM_TASK_NAME,
+              MEM_TASK_STACKSIZE, NULL, MEM_TASK_PRI, NULL);
+}
+
+bool memTest(void)
+{
+  return isInit;
+}
+
+void memTask(void * param)
+{
+	crtpInitTaskQueue(CRTP_PORT_MEM);
+	
+	while(1)
+	{
+		crtpReceivePacketBlock(CRTP_PORT_MEM, &p);
+
+		switch (p.channel)
+		{
+      case SETTINGS_CH:
+        memSettingsProcess(p.data[0]);
+        break;
+      case READ_CH:
+        memReadProcess();
+        break;
+      case WRITE_CH:
+        memWriteProcess();
+        break;
+      default:
+        break;
+		}
+	}
+}
+
+void memSettingsProcess(int command)
+{
+  uint8_t memId;
+  
+  switch (command)
+  {
+    case CMD_GET_NBR:
+      p.header = CRTP_HEADER(CRTP_PORT_MEM, SETTINGS_CH);
+      p.size = 2;
+      p.data[0] = CMD_GET_NBR;
+      p.data[1] = nbrOwMems + NBR_STATIC_MEM;
+      crtpSendPacket(&p);
+      break;
+
+    case CMD_GET_INFO:
+      memId = p.data[1];
+      p.header = CRTP_HEADER(CRTP_PORT_MEM, SETTINGS_CH);
+      p.size = 2;
+      p.data[0] = CMD_GET_INFO;
+      p.data[1] = memId;
+      // No error code if we fail, just send an empty packet back
+      if (memId == EEPROM_ID)
+      {
+        // Memory type (eeprom)
+        p.data[2] = MEM_TYPE_EEPROM;
+        p.size += 1;
+        // Size of the memory
+        memSize = EEPROM_SIZE;
+        memcpy(&p.data[3], &memSize, 4);
+        p.size += 4;
+        memcpy(&p.data[7], eepromSerialNum.data, 8);
+        p.size += 8;
+      }
+      else if (memId == LEDMEM_ID)
+      {
+        // Memory type virtual ledring mem
+        p.data[2] = MEM_TYPE_LED12;
+        p.size += 1;
+        // Size of the memory
+        memSize = sizeof(ledringmem);
+        memcpy(&p.data[3], &memSize, 4);
+        p.size += 4;
+        memcpy(&p.data[7], eepromSerialNum.data, 8); //TODO
+        p.size += 8;
+      }
+      else
+      {
+        if (owGetinfo(memId - NBR_STATIC_MEM, &serialNbr))
+        {
+          // Memory type (1-wire)
+          p.data[2] = MEM_TYPE_OW;
+          p.size += 1;
+          // Size of the memory TODO: Define length type
+          memSize = OW_MAX_SIZE;
+          memcpy(&p.data[3], &memSize, 4);
+          p.size += 4;
+          memcpy(&p.data[7], serialNbr.data, 8);
+          p.size += 8;
+        }
+      }
+      crtpSendPacket(&p);
+
+      break;
+  }
+}
+
+void memReadProcess()
+{
+  uint8_t memId = p.data[0];
+  uint8_t readLen = p.data[5];
+  uint32_t memAddr;
+  uint8_t status = 0;
+
+  memcpy(&memAddr, &p.data[1], 4);
+
+  MEM_DEBUG("Packet is MEM READ\n");
+  p.header = CRTP_HEADER(CRTP_PORT_MEM, READ_CH);
+  // Dont' touch the first 5 bytes, they will be the same.
+
+  if (memId == EEPROM_ID)
+  {
+    if (memAddr + readLen <= EEPROM_SIZE &&
+        eepromReadBuffer(&p.data[6], memAddr, readLen))
+      status = 0;
+    else
+      status = EIO;
+  }
+  else if (memId == LEDMEM_ID)
+  {
+    if (memAddr + readLen <= sizeof(ledringmem) &&
+        memcpy(&p.data[6], &(ledringmem[memAddr]), readLen))
+      status = 0;
+    else
+      status = EIO;
+  }
+  else
+  {
+    memId = memId - NBR_STATIC_MEM;
+    if (memAddr + readLen <= OW_MAX_SIZE &&
+        owRead(memId, memAddr, readLen, &p.data[6]))
+      status = 0;
+    else
+      status = EIO;
+  }
+
+#if 0
+  {
+    int i;
+    for (i = 0; i < readLen; i++)
+      consolePrintf("%X ", p.data[i+6]);
+
+    consolePrintf("\nStatus %i\n", status);
+  }
+#endif
+
+  p.data[5] = status;
+  if (status == 0)
+    p.size = 6 + readLen;
+  else
+    p.size = 6;
+
+
+  crtpSendPacket(&p);
+}
+
+void memWriteProcess()
+{
+  uint8_t memId = p.data[0];
+  uint8_t writeLen;
+  uint32_t memAddr;
+  uint8_t status = 0;
+
+  memcpy(&memAddr, &p.data[1], 4);
+  writeLen = p.size - 5;
+
+  MEM_DEBUG("Packet is MEM WRITE\n");
+  p.header = CRTP_HEADER(CRTP_PORT_MEM, WRITE_CH);
+  // Dont' touch the first 5 bytes, they will be the same.
+  if (memId == EEPROM_ID)
+  {
+    if (memAddr + writeLen <= EEPROM_SIZE &&
+        eepromWriteBuffer(&p.data[5], memAddr, writeLen))
+      status = 0;
+    else
+      status = EIO;
+  }
+  else if(memId == LEDMEM_ID)
+  {
+    if ((memAddr + writeLen) <= sizeof(ledringmem))
+    {
+      memcpy(&(ledringmem[memAddr]), &p.data[5], writeLen);
+      MEM_DEBUG("LED write addr:%i, led:%i\n", memAddr, writeLen);
+    }
+    else
+    {
+      MEM_DEBUG("\LED write failed! addr:%i, led:%i\n", memAddr, writeLen);
+    }
+  }
+  else
+  {
+    memId = memId - NBR_STATIC_MEM;
+    if (memAddr + writeLen <= OW_MAX_SIZE &&
+        owWrite(memId, memAddr, writeLen, &p.data[5]))
+      status = 0;
+    else
+      status = EIO;
+  }
+
+  p.data[5] = status;
+  p.size = 6;
+
+  crtpSendPacket(&p);
+}
diff --git a/crazyflie-firmware-src/src/modules/src/param.c b/crazyflie-firmware-src/src/modules/src/param.c
new file mode 100644
index 0000000000000000000000000000000000000000..24fff9b20f29a24e413d544245460e0680b329b0
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/param.c
@@ -0,0 +1,361 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * param.h - Crazy parameter system source file.
+ */
+#include <string.h>
+#include <errno.h>
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "config.h"
+#include "crtp.h"
+#include "param.h"
+#include "crc.h"
+#include "console.h"
+
+
+#define TOC_CH 0
+#define READ_CH 1
+#define WRITE_CH 2
+#define MISC_CH 3
+
+#define CMD_RESET 0
+#define CMD_GET_NEXT 1
+#define CMD_GET_CRC 2
+
+#define CMD_GET_ITEM 0
+#define CMD_GET_INFO 1
+
+#define MISC_SETBYNAME 0
+
+//Private functions
+static void paramTask(void * prm);
+void paramTOCProcess(int command);
+
+
+//These are set by the Linker
+extern struct param_s _param_start;
+extern struct param_s _param_stop;
+
+//The following two function SHALL NOT be called outside paramTask!
+static void paramWriteProcess(int id, void*);
+static void paramReadProcess(int id);
+static int variableGetIndex(int id);
+static char paramWriteByNameProcess(char* group, char* name, int type, void *valptr);
+
+//Pointer to the parameters list and length of it
+static struct param_s * params;
+static int paramsLen;
+static uint32_t paramsCrc;
+static int paramsCount = 0;
+
+static bool isInit = false;
+
+void paramInit(void)
+{
+  int i;
+
+  if(isInit)
+    return;
+
+  params = &_param_start;
+  paramsLen = &_param_stop - &_param_start;
+  paramsCrc = crcSlow(params, paramsLen*sizeof(params[0]));
+
+  for (i=0; i<paramsLen; i++)
+  {
+    if(!(params[i].type & PARAM_GROUP))
+      paramsCount++;
+  }
+
+
+  //Start the param task
+	xTaskCreate(paramTask, PARAM_TASK_NAME,
+	            PARAM_TASK_STACKSIZE, NULL, PARAM_TASK_PRI, NULL);
+
+  //TODO: Handle stored parameters!
+
+  isInit = true;
+}
+
+bool paramTest(void)
+{
+  return isInit;
+}
+
+CRTPPacket p;
+
+void paramTask(void * prm)
+{
+	crtpInitTaskQueue(CRTP_PORT_PARAM);
+
+	while(1) {
+		crtpReceivePacketBlock(CRTP_PORT_PARAM, &p);
+
+		if (p.channel==TOC_CH)
+		  paramTOCProcess(p.data[0]);
+	  else if (p.channel==READ_CH)
+		  paramReadProcess(p.data[0]);
+		else if (p.channel==WRITE_CH)
+		  paramWriteProcess(p.data[0], &p.data[1]);
+    else if (p.channel==MISC_CH) {
+      if (p.data[0] == MISC_SETBYNAME) {
+        int i, nzero = 0;
+        char *group;
+        char *name;
+        uint8_t type;
+        void * valPtr;
+        int error;
+
+        // If the packet contains at least 2 zeros in the first 28 bytes
+        // The packet decoding algorithm will not crash
+        for (i=0; i<CRTP_MAX_DATA_SIZE; i++) {
+          if (p.data[i] == '\0') nzero++;
+        }
+
+        if (nzero < 2) return;
+
+        group = (char*)&p.data[1];
+        name = (char*)&p.data[1+strlen(group)+1];
+        type = p.data[1+strlen(group)+1+strlen(name)+1];
+        valPtr = &p.data[1+strlen(group)+1+strlen(name)+2];
+
+        error = paramWriteByNameProcess(group, name, type, valPtr);
+
+        p.data[1+strlen(group)+1+strlen(name)+1] = error;
+        p.size = 1+strlen(group)+1+strlen(name)+1+1;
+        crtpSendPacket(&p);
+      }
+    }
+	}
+}
+
+void paramTOCProcess(int command)
+{
+  int ptr = 0;
+  char * group = "";
+  int n=0;
+
+  switch (command)
+  {
+  case CMD_GET_INFO: //Get info packet about the param implementation
+    ptr = 0;
+    group = "";
+    p.header=CRTP_HEADER(CRTP_PORT_PARAM, TOC_CH);
+    p.size=6;
+    p.data[0]=CMD_GET_INFO;
+    p.data[1]=paramsCount;
+    memcpy(&p.data[2], &paramsCrc, 4);
+    crtpSendPacket(&p);
+    break;
+  case CMD_GET_ITEM:  //Get param variable
+    for (ptr=0; ptr<paramsLen; ptr++) //Ptr points a group
+    {
+      if (params[ptr].type & PARAM_GROUP)
+      {
+        if (params[ptr].type & PARAM_START)
+          group = params[ptr].name;
+        else
+          group = "";
+      }
+      else                          //Ptr points a variable
+      {
+        if (n==p.data[1])
+          break;
+        n++;
+      }
+    }
+
+    if (ptr<paramsLen)
+    {
+      p.header=CRTP_HEADER(CRTP_PORT_PARAM, TOC_CH);
+      p.data[0]=CMD_GET_ITEM;
+      p.data[1]=n;
+      p.data[2]=params[ptr].type;
+      p.size=3+2+strlen(group)+strlen(params[ptr].name);
+      ASSERT(p.size <= CRTP_MAX_DATA_SIZE); // Too long! The name of the group or the parameter may be too long.
+      memcpy(p.data+3, group, strlen(group)+1);
+      memcpy(p.data+3+strlen(group)+1, params[ptr].name, strlen(params[ptr].name)+1);
+      crtpSendPacket(&p);
+    } else {
+      p.header=CRTP_HEADER(CRTP_PORT_PARAM, TOC_CH);
+      p.data[0]=CMD_GET_ITEM;
+      p.size=1;
+      crtpSendPacket(&p);
+    }
+    break;
+  }
+}
+
+static void paramWriteProcess(int ident, void* valptr)
+{
+  int id;
+
+  id = variableGetIndex(ident);
+
+  if (id<0) {
+    p.data[0] = -1;
+    p.data[1] = ident;
+    p.data[2] = ENOENT;
+    p.size = 3;
+
+    crtpSendPacket(&p);
+    return;
+  }
+
+	if (params[id].type & PARAM_RONLY)
+		return;
+
+  switch (params[id].type & PARAM_BYTES_MASK)
+  {
+ 	case PARAM_1BYTE:
+ 		*(uint8_t*)params[id].address = *(uint8_t*)valptr;
+ 		break;
+    case PARAM_2BYTES:
+  	  *(uint16_t*)params[id].address = *(uint16_t*)valptr;
+      break;
+ 	case PARAM_4BYTES:
+      *(uint32_t*)params[id].address = *(uint32_t*)valptr;
+      break;
+ 	case PARAM_8BYTES:
+      *(uint64_t*)params[id].address = *(uint64_t*)valptr;
+      break;
+  }
+
+  crtpSendPacket(&p);
+}
+
+static char paramWriteByNameProcess(char* group, char* name, int type, void *valptr) {
+  int ptr;
+  char *pgroup = "";
+
+  for (ptr=0; ptr<paramsLen; ptr++) //Ptr points a group
+  {
+    if (params[ptr].type & PARAM_GROUP)
+    {
+      if (params[ptr].type & PARAM_START)
+        pgroup = params[ptr].name;
+      else
+        pgroup = "";
+    }
+    else                          //Ptr points a variable
+    {
+      if (!strcmp(params[ptr].name, name) && !strcmp(pgroup, group))
+        break;
+    }
+  }
+
+  if (ptr >= paramsLen) {
+    return ENOENT;
+  }
+
+  if (type != params[ptr].type) {
+    return EINVAL;
+  }
+
+  if (params[ptr].type & PARAM_RONLY) {
+    return EACCES;
+  }
+
+  switch (params[ptr].type & PARAM_BYTES_MASK)
+  {
+ 	case PARAM_1BYTE:
+ 		*(uint8_t*)params[ptr].address = *(uint8_t*)valptr;
+ 		break;
+    case PARAM_2BYTES:
+  	  *(uint16_t*)params[ptr].address = *(uint16_t*)valptr;
+      break;
+ 	case PARAM_4BYTES:
+      *(uint32_t*)params[ptr].address = *(uint32_t*)valptr;
+      break;
+ 	case PARAM_8BYTES:
+      *(uint64_t*)params[ptr].address = *(uint64_t*)valptr;
+      break;
+  }
+
+  return 0;
+}
+
+static void paramReadProcess(int ident)
+{
+  int id;
+
+  id = variableGetIndex(ident);
+
+  if (id<0) {
+    p.data[0] = -1;
+    p.data[1] = ident;
+    p.data[2] = ENOENT;
+    p.size = 3;
+
+    crtpSendPacket(&p);
+    return;
+  }
+
+  switch (params[id].type & PARAM_BYTES_MASK)
+  {
+ 	case PARAM_1BYTE:
+   		memcpy(&p.data[1], params[id].address, sizeof(uint8_t));
+   		p.size = 1+sizeof(uint8_t);
+   		break;
+ 		break;
+    case PARAM_2BYTES:
+   		memcpy(&p.data[1], params[id].address, sizeof(uint16_t));
+   		p.size = 1+sizeof(uint16_t);
+   		break;
+    case PARAM_4BYTES:
+      memcpy(&p.data[1], params[id].address, sizeof(uint32_t));
+   		p.size = 1+sizeof(uint32_t);
+   		break;
+ 	  case PARAM_8BYTES:
+      memcpy(&p.data[1], params[id].address, sizeof(uint64_t));
+   		p.size = 1+sizeof(uint64_t);
+   		break;
+  }
+
+  crtpSendPacket(&p);
+}
+
+static int variableGetIndex(int id)
+{
+  int i;
+  int n=0;
+
+  for (i=0; i<paramsLen; i++)
+  {
+    if(!(params[i].type & PARAM_GROUP))
+    {
+      if(n==id)
+        break;
+      n++;
+    }
+  }
+
+  if (i>=paramsLen)
+    return -1;
+
+  return i;
+}
diff --git a/crazyflie-firmware-src/src/modules/src/pid.c b/crazyflie-firmware-src/src/modules/src/pid.c
new file mode 100644
index 0000000000000000000000000000000000000000..c82a0e0a25f46cfbac23cdd00c339ad11f12764d
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/pid.c
@@ -0,0 +1,152 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * pid.c - implementation of the PID regulator
+ */
+
+#include "pid.h"
+#include "num.h"
+#include <float.h>
+
+void pidInit(PidObject* pid, const float desired, const float kp,
+             const float ki, const float kd, const float dt,
+             const float samplingRate, const float cutoffFreq,
+             bool enableDFilter)
+{
+  pid->error         = 0;
+  pid->prevError     = 0;
+  pid->integ         = 0;
+  pid->deriv         = 0;
+  pid->desired       = desired;
+  pid->kp            = kp;
+  pid->ki            = ki;
+  pid->kd            = kd;
+  pid->iLimit        = DEFAULT_PID_INTEGRATION_LIMIT;
+  pid->outputLimit   = DEFAULT_PID_INTEGRATION_LIMIT;
+  pid->dt            = dt;
+  pid->enableDFilter = enableDFilter;
+  if (pid->enableDFilter)
+  {
+    lpf2pInit(&pid->dFilter, samplingRate, cutoffFreq);
+  }
+}
+
+float pidUpdate(PidObject* pid, const float measured, const bool updateError)
+{
+    float output = 0.0f;
+
+    if (updateError)
+    {
+        pid->error = pid->desired - measured;
+    }
+
+    pid->outP = pid->kp * pid->error;
+    output += pid->outP;
+
+    float deriv = (pid->error - pid->prevError) / pid->dt;
+    if (pid->enableDFilter)
+    {
+      pid->deriv = lpf2pApply(&pid->dFilter, deriv);
+    } else {
+      pid->deriv = deriv;
+    }
+    if (isnan(pid->deriv)) {
+      pid->deriv = 0;
+    }
+    pid->outD = pid->kd * pid->deriv;
+    output += pid->outD;
+
+    float i = pid->integ + pid->error * pid->dt;
+    // Check if integral is saturated
+    if (abs(i) <= pid->iLimit || abs(pid->ki * i + output) <= pid->outputLimit) {
+      pid->integ = i;
+    }
+
+    pid->outI = pid->ki * pid->integ;
+    output += pid->outI;
+
+    output = constrain(output, -pid->outputLimit, pid->outputLimit);
+
+    pid->prevError = pid->error;
+
+    return output;
+}
+
+void pidSetIntegralLimit(PidObject* pid, const float limit) {
+    pid->iLimit = limit;
+}
+
+
+void pidReset(PidObject* pid)
+{
+  pid->error     = 0;
+  pid->prevError = 0;
+  pid->integ     = 0;
+  pid->deriv     = 0;
+}
+
+void pidSetError(PidObject* pid, const float error)
+{
+  pid->error = error;
+}
+
+void pidSetDesired(PidObject* pid, const float desired)
+{
+  pid->desired = desired;
+}
+
+float pidGetDesired(PidObject* pid)
+{
+  return pid->desired;
+}
+
+bool pidIsActive(PidObject* pid)
+{
+  bool isActive = true;
+
+  if (pid->kp < 0.0001 && pid->ki < 0.0001 && pid->kd < 0.0001)
+  {
+    isActive = false;
+  }
+
+  return isActive;
+}
+
+void pidSetKp(PidObject* pid, const float kp)
+{
+  pid->kp = kp;
+}
+
+void pidSetKi(PidObject* pid, const float ki)
+{
+  pid->ki = ki;
+}
+
+void pidSetKd(PidObject* pid, const float kd)
+{
+  pid->kd = kd;
+}
+void pidSetDt(PidObject* pid, const float dt) {
+    pid->dt = dt;
+}
diff --git a/crazyflie-firmware-src/src/modules/src/pidctrl.c b/crazyflie-firmware-src/src/modules/src/pidctrl.c
new file mode 100644
index 0000000000000000000000000000000000000000..65536dd795733da1d7e8b8d8f181a76c07138abf
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/pidctrl.c
@@ -0,0 +1,111 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * pidctrl.c - Used to receive/answer requests from client and to receive updated PID values from client
+ */
+ 
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "crtp.h"
+#include "pidctrl.h"
+#include "pid.h"
+
+typedef enum {
+  pidCtrlValues = 0x00,
+} PIDCrtlNbr;
+
+void pidCrtlTask(void *param);
+
+void pidCtrlInit()
+{
+  xTaskCreate(pidCrtlTask, PID_CTRL_TASK_NAME,
+              PID_CTRL_TASK_STACKSIZE, NULL, PID_CTRL_TASK_PRI, NULL);
+  crtpInitTaskQueue(6);
+}
+
+void pidCrtlTask(void *param)
+{
+  CRTPPacket p;
+  extern PidObject pidRollRate;
+  extern PidObject pidPitchRate;
+  extern PidObject pidYawRate;
+  extern PidObject pidRoll;
+  extern PidObject pidPitch;
+  extern PidObject pidYaw;
+  struct pidValues
+  {
+    uint16_t rateKpRP;
+    uint16_t rateKiRP;
+    uint16_t rateKdRP;
+    uint16_t attKpRP;
+    uint16_t attKiRP;
+    uint16_t attKdRP;
+    uint16_t rateKpY;
+    uint16_t rateKiY;
+    uint16_t rateKdY;
+    uint16_t attKpY;
+    uint16_t attKiY;
+    uint16_t attKdY;
+  }  __attribute__((packed));
+  struct pidValues *pPid;
+
+  while (TRUE)
+  {
+    if (crtpReceivePacketBlock(6, &p) == pdTRUE)
+    {
+      PIDCrtlNbr pidNbr = p.channel;
+      
+      switch (pidNbr)
+      {
+        case pidCtrlValues:
+          pPid = (struct pidValues *)p.data;
+          {
+            pidSetKp(&pidRollRate, (float)pPid->rateKpRP/100.0);
+            pidSetKi(&pidRollRate, (float)pPid->rateKiRP/100.0);
+            pidSetKd(&pidRollRate, (float)pPid->rateKdRP/100.0);
+            pidSetKp(&pidRoll, (float)pPid->attKpRP/100.0);
+            pidSetKi(&pidRoll, (float)pPid->attKiRP/100.0);
+            pidSetKd(&pidRoll, (float)pPid->attKdRP/100.0);
+            pidSetKp(&pidPitchRate, (float)pPid->rateKpRP/100.0);
+            pidSetKi(&pidPitchRate, (float)pPid->rateKiRP/100.0);
+            pidSetKd(&pidPitchRate, (float)pPid->rateKdRP/100.0);
+            pidSetKp(&pidPitch, (float)pPid->attKpRP/100.0);
+            pidSetKi(&pidPitch, (float)pPid->attKiRP/100.0);
+            pidSetKd(&pidPitch, (float)pPid->attKdRP/100.0);
+            pidSetKp(&pidYawRate, (float)pPid->rateKpY/100.0);
+            pidSetKi(&pidYawRate, (float)pPid->rateKiY/100.0);
+            pidSetKd(&pidYawRate, (float)pPid->rateKdY/100.0);
+            pidSetKp(&pidYaw, (float)pPid->attKpY/100.0);
+            pidSetKi(&pidYaw, (float)pPid->attKiY/100.0);
+            pidSetKd(&pidYaw, (float)pPid->attKdY/100.0);
+          }
+          break;
+        default:
+          break;
+      } 
+    }
+  }
+}
+
diff --git a/crazyflie-firmware-src/src/modules/src/platformservice.c b/crazyflie-firmware-src/src/modules/src/platformservice.c
new file mode 100644
index 0000000000000000000000000000000000000000..43bf9d4294fcba75fcb6581a2fdb8fb5e69eb001
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/platformservice.c
@@ -0,0 +1,123 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * crtpservice.c - Implements low level services for CRTP
+ */
+
+#include <stdbool.h>
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include <stdint.h>
+#include <string.h>
+
+#include "config.h"
+#include "crtp.h"
+#include "platformservice.h"
+#include "syslink.h"
+#include "version.h"
+
+static bool isInit=false;
+
+typedef enum {
+  platformCommand   = 0x00,
+  versionCommand    = 0x01,
+} Channel;
+
+typedef enum {
+  setContinousWave   = 0x00,
+} PlatformCommand;
+
+typedef enum {
+  getProtocolVersion = 0x00,
+  getFirmwareVersion = 0x01,
+} VersionCommand;
+
+void platformserviceHandler(CRTPPacket *p);
+static void platformCommandProcess(uint8_t command, uint8_t *data);
+static void versionCommandProcess(CRTPPacket *p);
+
+void platformserviceInit(void)
+{
+  if (isInit)
+    return;
+
+  // Register a callback to service the Platform port
+  crtpRegisterPortCB(CRTP_PORT_PLATFORM, platformserviceHandler);
+
+  isInit = true;
+}
+
+bool platformserviceTest(void)
+{
+  return isInit;
+}
+
+void platformserviceHandler(CRTPPacket *p)
+{
+  switch (p->channel)
+  {
+    case platformCommand:
+      platformCommandProcess(p->data[0], &p->data[1]);
+      crtpSendPacket(p);
+      break;
+    case versionCommand:
+      versionCommandProcess(p);
+    default:
+      break;
+  }
+}
+
+static void platformCommandProcess(uint8_t command, uint8_t *data)
+{
+  SyslinkPacket slp;
+
+  switch (command) {
+    case setContinousWave:
+      slp.type = SYSLINK_RADIO_CONTWAVE;
+      slp.length = 1;
+      slp.data[0] = data[0];
+      syslinkSendPacket(&slp);
+      break;
+    default:
+      break;
+  }
+}
+
+static void versionCommandProcess(CRTPPacket *p)
+{
+  switch (p->data[0]) {
+    case getProtocolVersion:
+      *(int*)&p->data[1] = PROTOCOL_VERSION;
+      p->size = 5;
+      crtpSendPacket(p);
+      break;
+    case getFirmwareVersion:
+      strncpy((char*)&p->data[1], V_STAG, CRTP_MAX_DATA_SIZE-1);
+      p->size = (strlen(V_STAG)>CRTP_MAX_DATA_SIZE-1)?CRTP_MAX_DATA_SIZE:strlen(V_STAG)+1;
+      crtpSendPacket(p);
+      break;
+    default:
+      break;
+  }
+}
diff --git a/crazyflie-firmware-src/src/modules/src/position_controller_pid.c b/crazyflie-firmware-src/src/modules/src/position_controller_pid.c
new file mode 100644
index 0000000000000000000000000000000000000000..9df5ea908a6e2f9715f78e36e48e1c59c0c6f5ad
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/position_controller_pid.c
@@ -0,0 +1,290 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * position_estimator_pid.c: PID-based implementation of the position controller
+ */
+
+#include <math.h>
+#include "num.h"
+
+#include "commander.h"
+#include "log.h"
+#include "param.h"
+#include "pid.h"
+#include "num.h"
+#include "position_controller.h"
+
+struct pidInit_s {
+  float kp;
+  float ki;
+  float kd;
+};
+
+struct pidAxis_s {
+  PidObject pid;
+
+  struct pidInit_s init;
+  mode_t previousMode;
+  float setpoint;
+
+  float output;
+};
+
+struct this_s {
+  struct pidAxis_s pidVX;
+  struct pidAxis_s pidVY;
+  struct pidAxis_s pidVZ;
+
+  struct pidAxis_s pidX;
+  struct pidAxis_s pidY;
+  struct pidAxis_s pidZ;
+
+  uint16_t thrustBase; // approximate throttle needed when in perfect hover. More weight/older battery can use a higher value
+  uint16_t thrustMin;  // Minimum thrust value to output
+};
+
+// Maximum roll/pitch angle permited
+static float rpLimit  = 20;
+static float rpLimitOverhead = 1.10f;
+// Velocity maximums
+static float xyVelMax = 1.0f;
+static float zVelMax  = 1.0f;
+static float velMaxOverhead = 1.10f;
+static const float thrustScale = 1000.0f;
+
+#define DT (float)(1.0f/POSITION_RATE)
+#define POSITION_LPF_CUTOFF_FREQ 20.0f
+#define POSITION_LPF_ENABLE true
+
+#ifndef UNIT_TEST
+static struct this_s this = {
+  .pidVX = {
+    .init = {
+      .kp = 25.0f,
+      .ki = 1.0f,
+      .kd = 0.0f,
+    },
+    .pid.dt = DT,
+  },
+
+  .pidVY = {
+    .init = {
+      .kp = 25.0f,
+      .ki = 1.0f,
+      .kd = 0.0f,
+    },
+    .pid.dt = DT,
+  },
+
+  .pidVZ = {
+    .init = {
+      .kp = 25,
+      .ki = 15,
+      .kd = 0,
+    },
+    .pid.dt = DT,
+  },
+
+  .pidX = {
+    .init = {
+      .kp = 2.0f,
+      .ki = 0,
+      .kd = 0,
+    },
+    .pid.dt = DT,
+  },
+
+  .pidY = {
+    .init = {
+      .kp = 2.0f,
+      .ki = 0,
+      .kd = 0,
+    },
+    .pid.dt = DT,
+  },
+
+  .pidZ = {
+    .init = {
+      .kp = 2.0f,
+      .ki = 0,
+      .kd = 0,
+    },
+    .pid.dt = DT,
+  },
+
+  .thrustBase = 36000,
+  .thrustMin  = 20000,
+};
+#endif
+
+void positionControllerInit()
+{
+  pidInit(&this.pidX.pid, this.pidX.setpoint, this.pidX.init.kp, this.pidX.init.ki, this.pidX.init.kd,
+      this.pidX.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
+  pidInit(&this.pidY.pid, this.pidY.setpoint, this.pidY.init.kp, this.pidY.init.ki, this.pidY.init.kd,
+      this.pidY.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
+  pidInit(&this.pidZ.pid, this.pidZ.setpoint, this.pidZ.init.kp, this.pidZ.init.ki, this.pidZ.init.kd,
+      this.pidZ.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
+
+  pidInit(&this.pidVX.pid, this.pidVX.setpoint, this.pidVX.init.kp, this.pidVX.init.ki, this.pidVX.init.kd,
+      this.pidVX.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
+  pidInit(&this.pidVY.pid, this.pidVY.setpoint, this.pidVY.init.kp, this.pidVY.init.ki, this.pidVY.init.kd,
+      this.pidVY.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
+  pidInit(&this.pidVZ.pid, this.pidVZ.setpoint, this.pidVZ.init.kp, this.pidVZ.init.ki, this.pidVZ.init.kd,
+      this.pidVZ.pid.dt, POSITION_RATE, POSITION_LPF_CUTOFF_FREQ, POSITION_LPF_ENABLE);
+}
+
+static float runPid(float input, struct pidAxis_s *axis, float setpoint, float dt) {
+  axis->setpoint = setpoint;
+
+  pidSetDesired(&axis->pid, axis->setpoint);
+  return pidUpdate(&axis->pid, input, true);
+}
+
+void positionController(float* thrust, attitude_t *attitude, setpoint_t *setpoint,
+                                                             const state_t *state)
+{
+  this.pidX.pid.outputLimit = xyVelMax * velMaxOverhead;
+  this.pidY.pid.outputLimit = xyVelMax * velMaxOverhead;
+  // The ROS landing detector will prematurely trip if
+  // this value is below 0.5
+  this.pidZ.pid.outputLimit = max(zVelMax, 0.5)  * velMaxOverhead;
+
+  // X, Y
+  setpoint->velocity.x = runPid(state->position.x, &this.pidX, setpoint->position.x, DT);
+  setpoint->velocity.y = runPid(state->position.y, &this.pidY, setpoint->position.y, DT);
+  setpoint->velocity.z = runPid(state->position.z, &this.pidZ, setpoint->position.z, DT);
+
+  velocityController(thrust, attitude, setpoint, state);
+}
+
+void velocityController(float* thrust, attitude_t *attitude, setpoint_t *setpoint,
+                                                             const state_t *state)
+{
+  this.pidVX.pid.outputLimit = rpLimit * rpLimitOverhead;
+  this.pidVY.pid.outputLimit = rpLimit * rpLimitOverhead;
+  // Set the output limit to the maximum thrust range
+  this.pidVZ.pid.outputLimit = (UINT16_MAX / 2 / thrustScale);
+  //this.pidVZ.pid.outputLimit = (this.thrustBase - this.thrustMin) / thrustScale;
+
+  // Roll and Pitch
+  float rollRaw  = runPid(state->velocity.x, &this.pidVX, setpoint->velocity.x, DT);
+  float pitchRaw = runPid(state->velocity.y, &this.pidVY, setpoint->velocity.y, DT);
+
+  float yawRad = state->attitude.yaw * (float)M_PI / 180;
+  attitude->pitch = -(rollRaw  * cosf(yawRad)) - (pitchRaw * sinf(yawRad));
+  attitude->roll  = -(pitchRaw * cosf(yawRad)) + (rollRaw  * sinf(yawRad));
+
+  attitude->roll  = constrain(attitude->roll,  -rpLimit, rpLimit);
+  attitude->pitch = constrain(attitude->pitch, -rpLimit, rpLimit);
+
+  // Thrust
+  float thrustRaw = runPid(state->velocity.z, &this.pidVZ, setpoint->velocity.z, DT);
+  // Scale the thrust and add feed forward term
+  *thrust = thrustRaw*thrustScale + this.thrustBase;
+  // Check for minimum thrust
+  if (*thrust < this.thrustMin) {
+    *thrust = this.thrustMin;
+  }
+}
+
+void positionControllerResetAllPID()
+{
+  pidReset(&this.pidX.pid);
+  pidReset(&this.pidY.pid);
+  pidReset(&this.pidZ.pid);
+  pidReset(&this.pidVX.pid);
+  pidReset(&this.pidVY.pid);
+  pidReset(&this.pidVZ.pid);
+}
+
+LOG_GROUP_START(posCtl)
+
+LOG_ADD(LOG_FLOAT, targetVX, &this.pidVX.pid.desired)
+LOG_ADD(LOG_FLOAT, targetVY, &this.pidVY.pid.desired)
+LOG_ADD(LOG_FLOAT, targetVZ, &this.pidVZ.pid.desired)
+
+LOG_ADD(LOG_FLOAT, targetX, &this.pidX.pid.desired)
+LOG_ADD(LOG_FLOAT, targetY, &this.pidY.pid.desired)
+LOG_ADD(LOG_FLOAT, targetZ, &this.pidZ.pid.desired)
+
+LOG_ADD(LOG_FLOAT, Xp, &this.pidX.pid.outP)
+LOG_ADD(LOG_FLOAT, Xi, &this.pidX.pid.outI)
+LOG_ADD(LOG_FLOAT, Xd, &this.pidX.pid.outD)
+
+LOG_ADD(LOG_FLOAT, Yp, &this.pidY.pid.outP)
+LOG_ADD(LOG_FLOAT, Yi, &this.pidY.pid.outI)
+LOG_ADD(LOG_FLOAT, Yd, &this.pidY.pid.outD)
+
+LOG_ADD(LOG_FLOAT, Zp, &this.pidZ.pid.outP)
+LOG_ADD(LOG_FLOAT, Zi, &this.pidZ.pid.outI)
+LOG_ADD(LOG_FLOAT, Zd, &this.pidZ.pid.outD)
+
+LOG_ADD(LOG_FLOAT, VXp, &this.pidVX.pid.outP)
+LOG_ADD(LOG_FLOAT, VXi, &this.pidVX.pid.outI)
+LOG_ADD(LOG_FLOAT, VXd, &this.pidVX.pid.outD)
+
+LOG_ADD(LOG_FLOAT, VZp, &this.pidVZ.pid.outP)
+LOG_ADD(LOG_FLOAT, VZi, &this.pidVZ.pid.outI)
+LOG_ADD(LOG_FLOAT, VZd, &this.pidVZ.pid.outD)
+
+LOG_GROUP_STOP(posCtl)
+
+PARAM_GROUP_START(velCtlPid)
+
+PARAM_ADD(PARAM_FLOAT, vxKp, &this.pidVX.pid.kp)
+PARAM_ADD(PARAM_FLOAT, vxKi, &this.pidVX.pid.ki)
+PARAM_ADD(PARAM_FLOAT, vxKd, &this.pidVX.pid.kd)
+
+PARAM_ADD(PARAM_FLOAT, vyKp, &this.pidVY.pid.kp)
+PARAM_ADD(PARAM_FLOAT, vyKi, &this.pidVY.pid.ki)
+PARAM_ADD(PARAM_FLOAT, vyKd, &this.pidVY.pid.kd)
+
+PARAM_ADD(PARAM_FLOAT, vzKp, &this.pidVZ.pid.kp)
+PARAM_ADD(PARAM_FLOAT, vzKi, &this.pidVZ.pid.ki)
+PARAM_ADD(PARAM_FLOAT, vzKd, &this.pidVZ.pid.kd)
+
+PARAM_GROUP_STOP(velCtlPid)
+
+PARAM_GROUP_START(posCtlPid)
+
+PARAM_ADD(PARAM_FLOAT, xKp, &this.pidX.pid.kp)
+PARAM_ADD(PARAM_FLOAT, xKi, &this.pidX.pid.ki)
+PARAM_ADD(PARAM_FLOAT, xKd, &this.pidX.pid.kd)
+
+PARAM_ADD(PARAM_FLOAT, yKp, &this.pidY.pid.kp)
+PARAM_ADD(PARAM_FLOAT, yKi, &this.pidY.pid.ki)
+PARAM_ADD(PARAM_FLOAT, yKd, &this.pidY.pid.kd)
+
+PARAM_ADD(PARAM_FLOAT, zKp, &this.pidZ.pid.kp)
+PARAM_ADD(PARAM_FLOAT, zKi, &this.pidZ.pid.ki)
+PARAM_ADD(PARAM_FLOAT, zKd, &this.pidZ.pid.kd)
+
+PARAM_ADD(PARAM_UINT16, thrustBase, &this.thrustBase)
+PARAM_ADD(PARAM_UINT16, thrustMin, &this.thrustMin)
+
+PARAM_ADD(PARAM_FLOAT, rpLimit,  &rpLimit)
+PARAM_ADD(PARAM_FLOAT, xyVelMax, &xyVelMax)
+PARAM_ADD(PARAM_FLOAT, zVelMax,  &zVelMax)
+
+PARAM_GROUP_STOP(posCtlPid)
diff --git a/crazyflie-firmware-src/src/modules/src/position_estimator_altitude.c b/crazyflie-firmware-src/src/modules/src/position_estimator_altitude.c
new file mode 100644
index 0000000000000000000000000000000000000000..69b0f7241346166b1996c5fcab7d30d6b6beff7b
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/position_estimator_altitude.c
@@ -0,0 +1,95 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * position_estimator_altitude.c: Altitude-only position estimator
+ */
+
+#include "log.h"
+#include "param.h"
+#include "num.h"
+#include "position_estimator.h"
+
+#define G 9.81;
+
+struct selfState_s {
+  float estimatedZ; // The current Z estimate, has same offset as asl
+  float velocityZ; // Vertical speed (world frame) integrated from vertical acceleration (m/s)
+  float estAlpha;
+  float velocityFactor;
+  float vAccDeadband; // Vertical acceleration deadband
+  float velZAlpha;   // Blending factor to avoid vertical speed to accumulate error
+  float estimatedVZ;
+};
+
+static struct selfState_s state = {
+  .estimatedZ = 0.0,
+  .velocityZ = 0.0,
+  .estAlpha = 0.997,
+  .velocityFactor = 1.0,
+  .vAccDeadband = 0.04,
+  .velZAlpha = 0.995,
+  .estimatedVZ = 0.0,
+};
+
+static void positionEstimateInternal(state_t* estimate, float asl, float dt, struct selfState_s* state);
+static void positionUpdateVelocityInternal(float accWZ, float dt, struct selfState_s* state);
+
+void positionEstimate(state_t* estimate, float asl, float dt) {
+  positionEstimateInternal(estimate, asl, dt, &state);
+}
+
+void positionUpdateVelocity(float accWZ, float dt) {
+  positionUpdateVelocityInternal(accWZ, dt, &state);
+}
+
+static void positionEstimateInternal(state_t* estimate, float asl, float dt, struct selfState_s* state) {
+  static float prev_estimatedZ = 0;
+  state->estimatedZ = state->estAlpha * state->estimatedZ +
+                     (1.0 - state->estAlpha) * asl +
+                     state->velocityFactor * state->velocityZ * dt;
+
+  estimate->position.x = 0.0;
+  estimate->position.y = 0.0;
+  estimate->position.z = state->estimatedZ;
+  estimate->velocity.z = (state->estimatedZ - prev_estimatedZ) / dt;
+  state->estimatedVZ = estimate->velocity.z;
+  prev_estimatedZ = state->estimatedZ;
+}
+
+static void positionUpdateVelocityInternal(float accWZ, float dt, struct selfState_s* state) {
+  state->velocityZ += deadband(accWZ, state->vAccDeadband) * dt * G;
+  state->velocityZ *= state->velZAlpha;
+}
+
+LOG_GROUP_START(posEstimatorAlt)
+LOG_ADD(LOG_FLOAT, estimatedZ, &state.estimatedZ)
+LOG_ADD(LOG_FLOAT, estVZ, &state.estimatedVZ)
+LOG_ADD(LOG_FLOAT, velocityZ, &state.velocityZ)
+LOG_GROUP_STOP(posEstimatorAlt)
+
+PARAM_GROUP_START(posEst)
+PARAM_ADD(PARAM_FLOAT, estAlpha, &state.estAlpha)
+PARAM_ADD(PARAM_FLOAT, velFactor, &state.velocityFactor)
+PARAM_ADD(PARAM_FLOAT, velZAlpha, &state.velZAlpha)
+PARAM_ADD(PARAM_FLOAT, vAccDeadband, &state.vAccDeadband)
+PARAM_GROUP_STOP(posEstimatorAlt)
diff --git a/crazyflie-firmware-src/src/modules/src/power_distribution_stock.c b/crazyflie-firmware-src/src/modules/src/power_distribution_stock.c
new file mode 100644
index 0000000000000000000000000000000000000000..c7127502eb2213eaad999ea397287c337fce0673
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/power_distribution_stock.c
@@ -0,0 +1,99 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * power_distribution_stock.c - Crazyflie stock power distribution code
+ */
+#include "power_distribution.h"
+
+#include "log.h"
+#include "param.h"
+#include "num.h"
+
+#include "motors.h"
+
+static bool motorSetEnable = false;
+
+static struct {
+  uint32_t m1;
+  uint32_t m2;
+  uint32_t m3;
+  uint32_t m4;
+} motorPower;
+
+static struct {
+  uint16_t m1;
+  uint16_t m2;
+  uint16_t m3;
+  uint16_t m4;
+} motorPowerSet;
+
+void powerDistributionInit(void)
+{
+  motorsInit(motorMapDefaultBrushed);
+}
+
+bool powerDistributionTest(void)
+{
+  bool pass = true;
+
+  pass &= motorsTest();
+
+  return pass;
+}
+
+#define limitThrust(VAL) limitUint16(VAL)
+
+void powerDistribution(const control_t *control)
+{
+    int16_t r = control->roll / 2.0f;
+    int16_t p = control->pitch / 2.0f;
+//    motorPower.m1 = limitThrust(control->thrust - r + p + control->yaw);
+//    motorPower.m2 = limitThrust(control->thrust - r - p - control->yaw);
+//    motorPower.m3 =  limitThrust(control->thrust + r - p + control->yaw);
+//    motorPower.m4 =  limitThrust(control->thrust + r + p - control->yaw);
+    motorPower.m1 = limitThrust(control->cmd1 - r + p + control->yaw);
+    motorPower.m2 = limitThrust(control->cmd2 - r - p - control->yaw);
+    motorPower.m3 =  limitThrust(control->cmd3 + r - p + control->yaw);
+    motorPower.m4 =  limitThrust(control->cmd4 + r + p - control->yaw);
+
+    motorsSetRatio(MOTOR_M1, motorPower.m1);
+    motorsSetRatio(MOTOR_M2, motorPower.m2);
+    motorsSetRatio(MOTOR_M3, motorPower.m3);
+    motorsSetRatio(MOTOR_M4, motorPower.m4);
+  
+}
+
+PARAM_GROUP_START(motorPowerSet)
+PARAM_ADD(PARAM_UINT8, enable, &motorSetEnable)
+PARAM_ADD(PARAM_UINT16, m1, &motorPowerSet.m1)
+PARAM_ADD(PARAM_UINT16, m2, &motorPowerSet.m2)
+PARAM_ADD(PARAM_UINT16, m3, &motorPowerSet.m3)
+PARAM_ADD(PARAM_UINT16, m4, &motorPowerSet.m4)
+PARAM_GROUP_STOP(ring)
+
+LOG_GROUP_START(motor)
+LOG_ADD(LOG_INT32, m4, &motorPower.m4)
+LOG_ADD(LOG_INT32, m1, &motorPower.m1)
+LOG_ADD(LOG_INT32, m2, &motorPower.m2)
+LOG_ADD(LOG_INT32, m3, &motorPower.m3)
+LOG_GROUP_STOP(motor)
diff --git a/crazyflie-firmware-src/src/modules/src/queuemonitor.c b/crazyflie-firmware-src/src/modules/src/queuemonitor.c
new file mode 100644
index 0000000000000000000000000000000000000000..961851cec4c5745394dca3ea0f05bd5a92ba78ab
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/queuemonitor.c
@@ -0,0 +1,173 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ * queuemonitor.c - Monitoring functionality for queues
+ */
+#define DEBUG_MODULE "QM"
+
+#include "queuemonitor.h"
+
+#ifdef DEBUG_QUEUE_MONITOR
+
+#include <stdbool.h>
+#include "timers.h"
+#include "debug.h"
+#include "cfassert.h"
+
+#define MAX_NR_OF_QUEUES 20
+#define TIMER_PERIOD M2T(10000)
+
+#define RESET_COUNTERS_AFTER_DISPLAY true
+#define DISPLAY_ONLY_OVERFLOW_QUEUES true
+
+typedef struct
+{
+  char* fileName;
+  char* queueName;
+  int sendCount;
+  int maxWaiting;
+  int fullCount;
+} Data;
+
+static Data data[MAX_NR_OF_QUEUES];
+
+static xTimerHandle timer;
+static unsigned char nrOfQueues = 1; // Unregistered queues will end up at 0
+static bool initialized = false;
+
+static void timerHandler(xTimerHandle timer);
+static void debugPrint();
+static bool filter(Data* queueData);
+static void debugPrintQueue(Data* queueData);
+static Data* getQueueData(xQueueHandle* xQueue);
+static int getMaxWaiting(xQueueHandle* xQueue, int prevPeak);
+static void resetCounters();
+
+unsigned char ucQueueGetQueueNumber( xQueueHandle xQueue );
+
+
+void queueMonitorInit() {
+  ASSERT(!initialized);
+  timer = xTimerCreate( "queueMonitorTimer", TIMER_PERIOD,
+    pdTRUE, NULL, timerHandler );
+  xTimerStart(timer, 100);
+
+  data[0].fileName = "Na";
+  data[0].queueName = "Na";
+
+  initialized = true;
+}
+
+void qm_traceQUEUE_SEND(void* xQueue) {
+  if(initialized) {
+    Data* queueData = getQueueData(xQueue);
+
+    queueData->sendCount++;
+    queueData->maxWaiting = getMaxWaiting(xQueue, queueData->maxWaiting);
+  }
+}
+
+void qm_traceQUEUE_SEND_FAILED(void* xQueue) {
+  if(initialized) {
+    Data* queueData = getQueueData(xQueue);
+
+    queueData->fullCount++;
+  }
+}
+
+void qmRegisterQueue(xQueueHandle* xQueue, char* fileName, char* queueName) {
+  ASSERT(initialized);
+  ASSERT(nrOfQueues < MAX_NR_OF_QUEUES);
+  Data* queueData = &data[nrOfQueues];
+
+  queueData->fileName = fileName;
+  queueData->queueName = queueName;
+  vQueueSetQueueNumber(xQueue, nrOfQueues);
+
+  nrOfQueues++;
+}
+
+static Data* getQueueData(xQueueHandle* xQueue) {
+  unsigned char number = uxQueueGetQueueNumber(xQueue);
+  ASSERT(number < MAX_NR_OF_QUEUES);
+  return &data[number];
+}
+
+static int getMaxWaiting(xQueueHandle* xQueue, int prevPeak) {
+  // We get here before the current item is added to the queue.
+  // Must add 1 to get the peak value.
+  unsigned portBASE_TYPE waiting = uxQueueMessagesWaitingFromISR(xQueue) + 1;
+
+  if (waiting > prevPeak) {
+    return waiting;
+  }
+  return prevPeak;
+}
+
+static void debugPrint() {
+  int i = 0;
+  for (i = 0; i < nrOfQueues; i++) {
+    Data* queueData = &data[i];
+    if (filter(queueData)) {
+      debugPrintQueue(queueData);
+    }
+  }
+
+  if (RESET_COUNTERS_AFTER_DISPLAY) {
+    resetCounters();
+  }
+}
+
+static bool filter(Data* queueData) {
+  bool doDisplay = false;
+  if (DISPLAY_ONLY_OVERFLOW_QUEUES) {
+    doDisplay = (queueData->fullCount != 0);
+  } else {
+    doDisplay = true;
+  }
+  return doDisplay;
+}
+
+static void debugPrintQueue(Data* queueData) {
+  DEBUG_PRINT("%s:%s, sent: %i, peak: %i, full: %i\n",
+    queueData->fileName, queueData->queueName, queueData->sendCount,
+    queueData->maxWaiting, queueData->fullCount);
+}
+
+static void resetCounters() {
+  int i = 0;
+  for (i = 0; i < nrOfQueues; i++) {
+    Data* queueData = &data[i];
+
+    queueData->sendCount = 0;
+    queueData->maxWaiting = 0;
+    queueData->fullCount = 0;
+  }
+}
+
+static void timerHandler(xTimerHandle timer) {
+  debugPrint();
+}
+
+#endif // DEBUG_QUEUE_MONITOR
diff --git a/crazyflie-firmware-src/src/modules/src/sensfusion6.c b/crazyflie-firmware-src/src/modules/src/sensfusion6.c
new file mode 100644
index 0000000000000000000000000000000000000000..7dd1d83e5c297de91635869b088effaa837c02a7
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/sensfusion6.c
@@ -0,0 +1,331 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ */
+#include <math.h>
+
+#include "sensfusion6.h"
+#include "log.h"
+#include "param.h"
+
+#define M_PI_F ((float) M_PI)
+
+//#define MADWICK_QUATERNION_IMU
+
+#ifdef MADWICK_QUATERNION_IMU
+  #define BETA_DEF     0.01f    // 2 * proportional gain
+#else // MAHONY_QUATERNION_IMU
+    #define TWO_KP_DEF  (2.0f * 0.4f) // 2 * proportional gain
+    #define TWO_KI_DEF  (2.0f * 0.001f) // 2 * integral gain
+#endif
+
+#ifdef MADWICK_QUATERNION_IMU
+  float beta = BETA_DEF;     // 2 * proportional gain (Kp)
+#else // MAHONY_QUATERNION_IMU
+  float twoKp = TWO_KP_DEF;    // 2 * proportional gain (Kp)
+  float twoKi = TWO_KI_DEF;    // 2 * integral gain (Ki)
+  float integralFBx = 0.0f;
+  float integralFBy = 0.0f;
+  float integralFBz = 0.0f;  // integral error terms scaled by Ki
+#endif
+
+float q0 = 1.0f;
+float q1 = 0.0f;
+float q2 = 0.0f;
+float q3 = 0.0f;  // quaternion of sensor frame relative to auxiliary frame
+
+static float gravX, gravY, gravZ; // Unit vector in the estimated gravity direction
+
+// The acc in Z for static position (g)
+// Set on first update, assuming we are in a static position since the sensors were just calibrates.
+// This value will be better the more level the copter is at calibration time
+static float baseZacc = 1.0;
+
+static bool isInit;
+
+static bool isCalibrated = false;
+
+static void sensfusion6UpdateQImpl(float gx, float gy, float gz, float ax, float ay, float az, float dt);
+static float sensfusion6GetAccZ(const float ax, const float ay, const float az);
+static void estimatedGravityDirection(float* gx, float* gy, float* gz);
+
+// TODO: Make math util file
+static float invSqrt(float x);
+
+void sensfusion6Init()
+{
+  if(isInit)
+    return;
+
+  isInit = true;
+}
+
+bool sensfusion6Test(void)
+{
+  return isInit;
+}
+
+void sensfusion6UpdateQ(float gx, float gy, float gz, float ax, float ay, float az, float dt)
+{
+  sensfusion6UpdateQImpl(gx, gy, gz, ax, ay, az, dt);
+  estimatedGravityDirection(&gravX, &gravY, &gravZ);
+
+  if (!isCalibrated) {
+    baseZacc = sensfusion6GetAccZ(ax, ay, az);
+    isCalibrated = true;
+  }
+}
+
+#ifdef MADWICK_QUATERNION_IMU
+// Implementation of Madgwick's IMU and AHRS algorithms.
+// See: http://www.x-io.co.uk/open-source-ahrs-with-x-imu
+//
+// Date     Author          Notes
+// 29/09/2011 SOH Madgwick    Initial release
+// 02/10/2011 SOH Madgwick  Optimised for reduced CPU load
+static void sensfusion6UpdateQImpl(float gx, float gy, float gz, float ax, float ay, float az, float dt)
+{
+  float recipNorm;
+  float s0, s1, s2, s3;
+  float qDot1, qDot2, qDot3, qDot4;
+  float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2 ,_8q1, _8q2, q0q0, q1q1, q2q2, q3q3;
+
+  // Rate of change of quaternion from gyroscope
+  qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz);
+  qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy);
+  qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx);
+  qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx);
+
+  // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
+  if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f)))
+  {
+    // Normalise accelerometer measurement
+    recipNorm = invSqrt(ax * ax + ay * ay + az * az);
+    ax *= recipNorm;
+    ay *= recipNorm;
+    az *= recipNorm;
+
+    // Auxiliary variables to avoid repeated arithmetic
+    _2q0 = 2.0f * q0;
+    _2q1 = 2.0f * q1;
+    _2q2 = 2.0f * q2;
+    _2q3 = 2.0f * q3;
+    _4q0 = 4.0f * q0;
+    _4q1 = 4.0f * q1;
+    _4q2 = 4.0f * q2;
+    _8q1 = 8.0f * q1;
+    _8q2 = 8.0f * q2;
+    q0q0 = q0 * q0;
+    q1q1 = q1 * q1;
+    q2q2 = q2 * q2;
+    q3q3 = q3 * q3;
+
+    // Gradient decent algorithm corrective step
+    s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay;
+    s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + _8q1 * q2q2 + _4q1 * az;
+    s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + _8q2 * q2q2 + _4q2 * az;
+    s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay;
+    recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
+    s0 *= recipNorm;
+    s1 *= recipNorm;
+    s2 *= recipNorm;
+    s3 *= recipNorm;
+
+    // Apply feedback step
+    qDot1 -= beta * s0;
+    qDot2 -= beta * s1;
+    qDot3 -= beta * s2;
+    qDot4 -= beta * s3;
+  }
+
+  // Integrate rate of change of quaternion to yield quaternion
+  q0 += qDot1 * dt;
+  q1 += qDot2 * dt;
+  q2 += qDot3 * dt;
+  q3 += qDot4 * dt;
+
+  // Normalise quaternion
+  recipNorm = invSqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3);
+  q0 *= recipNorm;
+  q1 *= recipNorm;
+  q2 *= recipNorm;
+  q3 *= recipNorm;
+}
+#else // MAHONY_QUATERNION_IMU
+// Madgwick's implementation of Mayhony's AHRS algorithm.
+// See: http://www.x-io.co.uk/open-source-ahrs-with-x-imu
+//
+// Date     Author      Notes
+// 29/09/2011 SOH Madgwick    Initial release
+// 02/10/2011 SOH Madgwick  Optimised for reduced CPU load
+static void sensfusion6UpdateQImpl(float gx, float gy, float gz, float ax, float ay, float az, float dt)
+{
+  float recipNorm;
+  float halfvx, halfvy, halfvz;
+  float halfex, halfey, halfez;
+  float qa, qb, qc;
+
+  gx = gx * M_PI_F / 180;
+  gy = gy * M_PI_F / 180;
+  gz = gz * M_PI_F / 180;
+
+  // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
+  if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f)))
+  {
+    // Normalise accelerometer measurement
+    recipNorm = invSqrt(ax * ax + ay * ay + az * az);
+    ax *= recipNorm;
+    ay *= recipNorm;
+    az *= recipNorm;
+
+    // Estimated direction of gravity and vector perpendicular to magnetic flux
+    halfvx = q1 * q3 - q0 * q2;
+    halfvy = q0 * q1 + q2 * q3;
+    halfvz = q0 * q0 - 0.5f + q3 * q3;
+
+    // Error is sum of cross product between estimated and measured direction of gravity
+    halfex = (ay * halfvz - az * halfvy);
+    halfey = (az * halfvx - ax * halfvz);
+    halfez = (ax * halfvy - ay * halfvx);
+
+    // Compute and apply integral feedback if enabled
+    if(twoKi > 0.0f)
+    {
+      integralFBx += twoKi * halfex * dt;  // integral error scaled by Ki
+      integralFBy += twoKi * halfey * dt;
+      integralFBz += twoKi * halfez * dt;
+      gx += integralFBx;  // apply integral feedback
+      gy += integralFBy;
+      gz += integralFBz;
+    }
+    else
+    {
+      integralFBx = 0.0f; // prevent integral windup
+      integralFBy = 0.0f;
+      integralFBz = 0.0f;
+    }
+
+    // Apply proportional feedback
+    gx += twoKp * halfex;
+    gy += twoKp * halfey;
+    gz += twoKp * halfez;
+  }
+
+  // Integrate rate of change of quaternion
+  gx *= (0.5f * dt);   // pre-multiply common factors
+  gy *= (0.5f * dt);
+  gz *= (0.5f * dt);
+  qa = q0;
+  qb = q1;
+  qc = q2;
+  q0 += (-qb * gx - qc * gy - q3 * gz);
+  q1 += (qa * gx + qc * gz - q3 * gy);
+  q2 += (qa * gy - qb * gz + q3 * gx);
+  q3 += (qa * gz + qb * gy - qc * gx);
+
+  // Normalise quaternion
+  recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
+  q0 *= recipNorm;
+  q1 *= recipNorm;
+  q2 *= recipNorm;
+  q3 *= recipNorm;
+}
+#endif
+
+void sensfusion6GetEulerRPY(float* roll, float* pitch, float* yaw)
+{
+  float gx = gravX;
+  float gy = gravY;
+  float gz = gravZ;
+
+  if (gx>1) gx=1;
+  if (gx<-1) gx=-1;
+
+  *yaw = atan2f(2*(q0*q3 + q1*q2), q0*q0 + q1*q1 - q2*q2 - q3*q3) * 180 / M_PI_F;
+  *pitch = asinf(gx) * 180 / M_PI_F; //Pitch seems to be inverted
+  *roll = atan2f(gy, gz) * 180 / M_PI_F;
+}
+
+float sensfusion6GetAccZWithoutGravity(const float ax, const float ay, const float az)
+{
+  return sensfusion6GetAccZ(ax, ay, az) - baseZacc;
+}
+
+float sensfusion6GetInvThrustCompensationForTilt()
+{
+  // Return the z component of the estimated gravity direction
+  // (0, 0, 1) dot G
+  return gravZ;
+}
+
+//---------------------------------------------------------------------------------------------------
+// Fast inverse square-root
+// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
+float invSqrt(float x)
+{
+  float halfx = 0.5f * x;
+  float y = x;
+  long i = *(long*)&y;
+  i = 0x5f3759df - (i>>1);
+  y = *(float*)&i;
+  y = y * (1.5f - (halfx * y * y));
+  return y;
+}
+
+static float sensfusion6GetAccZ(const float ax, const float ay, const float az)
+{
+  // return vertical acceleration
+  // (A dot G) / |G|,  (|G| = 1) -> (A dot G)
+  return (ax * gravX + ay * gravY + az * gravZ);
+}
+
+static void estimatedGravityDirection(float* gx, float* gy, float* gz)
+{
+  *gx = 2 * (q1 * q3 - q0 * q2);
+  *gy = 2 * (q0 * q1 + q2 * q3);
+  *gz = q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3;
+}
+
+LOG_GROUP_START(sensorfusion6)
+  LOG_ADD(LOG_FLOAT, qw, &q0)
+  LOG_ADD(LOG_FLOAT, qx, &q1)
+  LOG_ADD(LOG_FLOAT, qy, &q2)
+  LOG_ADD(LOG_FLOAT, qz, &q3)
+  LOG_ADD(LOG_FLOAT, gravityX, &gravX)
+  LOG_ADD(LOG_FLOAT, gravityY, &gravY)
+  LOG_ADD(LOG_FLOAT, gravityZ, &gravZ)
+  LOG_ADD(LOG_FLOAT, accZbase, &baseZacc)
+  LOG_ADD(LOG_UINT8, isInit, &isInit)
+  LOG_ADD(LOG_UINT8, isCalibrated, &isCalibrated)
+LOG_GROUP_STOP(sensorfusion6)
+
+PARAM_GROUP_START(sensorfusion6)
+#ifdef MADWICK_QUATERNION_IMU
+PARAM_ADD(PARAM_FLOAT, beta, &beta)
+#else // MAHONY_QUATERNION_IMU
+PARAM_ADD(PARAM_FLOAT, kp, &twoKp)
+PARAM_ADD(PARAM_FLOAT, ki, &twoKi)
+#endif
+PARAM_ADD(PARAM_FLOAT, baseZacc, &baseZacc)
+PARAM_GROUP_STOP(sensorfusion6)
diff --git a/crazyflie-firmware-src/src/modules/src/sensors_stock.c b/crazyflie-firmware-src/src/modules/src/sensors_stock.c
new file mode 100644
index 0000000000000000000000000000000000000000..4f1df9106f51e5e6c91b4bd255ec39630d5cc074
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/sensors_stock.c
@@ -0,0 +1,91 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sensors_stock.c - Crazyflie stock sensor acquisition function
+ */
+#include "sensors.h"
+
+#include "imu.h"
+#ifdef PLATFORM_CF1
+  #include "ms5611.h"
+#else
+  #include "lps25h.h"
+#endif
+
+#include "param.h"
+
+static point_t position;
+
+#define IMU_RATE RATE_500_HZ
+#define BARO_RATE RATE_100_HZ
+
+void sensorsInit(void)
+{
+ imu6Init();
+}
+
+bool sensorsTest(void)
+{
+ bool pass = true;
+
+ pass &= imu6Test();
+
+ return pass;
+}
+
+void sensorsAcquire(sensorData_t *sensors, const uint32_t tick)
+{
+  if (RATE_DO_EXECUTE(IMU_RATE, tick)) {
+    imu9Read(&sensors->gyro, &sensors->acc, &sensors->mag);
+  }
+
+ if (RATE_DO_EXECUTE(BARO_RATE, tick) && imuHasBarometer()) {
+#ifdef PLATFORM_CF1
+    ms5611GetData(&sensors->baro.pressure,
+                 &sensors->baro.temperature,
+                 &sensors->baro.asl);
+#else
+    lps25hGetData(&sensors->baro.pressure,
+                 &sensors->baro.temperature,
+                 &sensors->baro.asl);
+#endif
+    // Experimental: receive the position from parameters
+    if (position.timestamp) {
+      sensors->position = position;
+    }
+  }
+}
+
+bool sensorsAreCalibrated()
+{
+  Axis3f dummyData;
+  imu6Read(&dummyData, &dummyData);
+  return imu6IsCalibrated();
+}
+
+PARAM_GROUP_START(lps)
+PARAM_ADD(PARAM_UINT32, t, &position.timestamp)
+PARAM_ADD(PARAM_FLOAT, x, &position.x)
+PARAM_ADD(PARAM_FLOAT, y, &position.y)
+PARAM_ADD(PARAM_FLOAT, z, &position.z)
+PARAM_GROUP_STOP(lps)
diff --git a/crazyflie-firmware-src/src/modules/src/sitaw.c b/crazyflie-firmware-src/src/modules/src/sitaw.c
new file mode 100644
index 0000000000000000000000000000000000000000..5b2c568fabc20957006738edbe55242155c47350
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/sitaw.c
@@ -0,0 +1,328 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sitAw.h - Implementation of situation awareness.
+ */
+
+#include <stddef.h>
+#include <stdlib.h>
+#include <math.h>
+
+#include "log.h"
+#include "param.h"
+#include "trigger.h"
+#include "sitaw.h"
+#include "commander.h"
+
+/* Trigger object used to detect Free Fall situation. */
+static trigger_t sitAwFFAccWZ;
+
+/* Trigger object used to detect At Rest situation. */
+static trigger_t sitAwARAccZ;
+
+/* Trigger object used to detect Tumbled situation. */
+static trigger_t sitAwTuAngle;
+
+#if defined(SITAW_ENABLED)
+
+#if defined(SITAW_LOG_ENABLED) /* Enable the log group. */
+LOG_GROUP_START(sitAw)
+#if defined(SITAW_FF_LOG_ENABLED) /* Log trigger variables for Free Fall detection. */
+LOG_ADD(LOG_UINT32, FFAccWZTestCounter, &sitAwFFAccWZ.testCounter)
+LOG_ADD(LOG_UINT8, FFAccWZDetected, &sitAwFFAccWZ.released)
+#endif
+#if defined(SITAW_AR_LOG_ENABLED) /* Log trigger variables for At Rest detection. */
+LOG_ADD(LOG_UINT32, ARTestCounter, &sitAwARAccZ.testCounter)
+LOG_ADD(LOG_UINT8, ARDetected, &sitAwARAccZ.released)
+#endif
+#if defined(SITAW_TU_LOG_ENABLED) /* Log trigger variables for Tumbled detection. */
+LOG_ADD(LOG_UINT32, TuTestCounter, &sitAwTuAngle.testCounter)
+LOG_ADD(LOG_UINT8, TuDetected, &sitAwTuAngle.released)
+#endif
+#if defined(SITAW_LOG_ALL_DETECT_ENABLED) /* Log all the 'Detected' flags. */
+LOG_ADD(LOG_UINT8, FFAccWZDetected, &sitAwFFAccWZ.released)
+LOG_ADD(LOG_UINT8, ARDetected, &sitAwARAccZ.released)
+LOG_ADD(LOG_UINT8, TuDetected, &sitAwTuAngle.released)
+#endif
+LOG_GROUP_STOP(sitAw)
+#endif /* SITAW_LOG_ENABLED */
+
+#if defined(SITAW_PARAM_ENABLED) /* Enable the param group. */
+PARAM_GROUP_START(sitAw)
+#if defined(SITAW_FF_PARAM_ENABLED) /* Param variables for Free Fall detection. */
+PARAM_ADD(PARAM_UINT8, FFActive, &sitAwFFAccWZ.active)
+PARAM_ADD(PARAM_UINT32, FFTriggerCount, &sitAwFFAccWZ.triggerCount)
+PARAM_ADD(PARAM_FLOAT, FFaccWZ, &sitAwFFAccWZ.threshold)
+#endif
+#if defined(SITAW_AR_PARAM_ENABLED) /* Param variables for At Rest detection. */
+PARAM_ADD(PARAM_UINT8, ARActive, &sitAwARAccZ.active)
+PARAM_ADD(PARAM_UINT32, ARTriggerCount, &sitAwARAccZ.triggerCount)
+PARAM_ADD(PARAM_FLOAT, ARaccZ, &sitAwARAccZ.threshold)
+#endif
+#if defined(SITAW_TU_PARAM_ENABLED) /* Param variables for Tumbled detection. */
+PARAM_ADD(PARAM_UINT8, TuActive, &sitAwTuAngle.active)
+PARAM_ADD(PARAM_UINT32, TuTriggerCount, &sitAwTuAngle.triggerCount)
+PARAM_ADD(PARAM_FLOAT, TuAngle, &sitAwTuAngle.threshold)
+#endif
+PARAM_GROUP_STOP(sitAw)
+#endif /* SITAW_PARAM_ENABLED */
+
+#endif /* SITAW_ENABLED */
+
+/**
+ * Initialize the Free Fall detection.
+ *
+ * See the sitAwFFTest() function for details.
+ */
+void sitAwFFInit(void)
+{
+  triggerInit(&sitAwFFAccWZ, triggerFuncIsLE, SITAW_FF_THRESHOLD, SITAW_FF_TRIGGER_COUNT);
+  triggerActivate(&sitAwFFAccWZ, true);
+}
+
+
+static void sitAwPostStateUpdateCallOut(const sensorData_t *sensorData,
+                                        const state_t *state)
+{
+  /* Code that shall run AFTER each attitude update, should be placed here. */
+
+#if defined(SITAW_ENABLED)
+  float accMAG = (sensorData->acc.x*sensorData->acc.x) +
+                 (sensorData->acc.y*sensorData->acc.y) +
+                 (sensorData->acc.z*sensorData->acc.z);
+
+  /* Test values for Free Fall detection. */
+  sitAwFFTest(state->acc.z, accMAG);
+
+  /* Test values for Tumbled detection. */
+  sitAwTuTest(state->attitude.roll, state->attitude.pitch);
+
+  /* Test values for At Rest detection. */
+  sitAwARTest(sensorData->acc.x, sensorData->acc.y, sensorData->acc.z);
+#endif
+}
+
+static void sitAwPreThrustUpdateCallOut(setpoint_t *setpoint)
+{
+  /* Code that shall run BEFORE each thrust distribution update, should be placed here. */
+
+#if defined(SITAW_ENABLED)
+      if(sitAwTuDetected()) {
+        /* Kill the thrust to the motors if a Tumbled situation is detected. */
+        setpoint->thrust = 0;
+      }
+
+      /* Force altHold mode if free fall is detected.
+         FIXME: Needs a flying/landing state (as soon as althold is enabled,
+                                              we are not freefalling anymore)
+       */
+      if(sitAwFFDetected() && !sitAwTuDetected()) {
+        setpoint->mode.z = modeVelocity;
+        setpoint->velocity.z = 0;
+      }
+#endif
+}
+
+/**
+ * Update setpoint according to current situation
+ *
+ * Called by the stabilizer after state and setpoint update. This function
+ * should update the setpoint accordig to the current state situation
+ */
+void sitAwUpdateSetpoint(setpoint_t *setpoint, const sensorData_t *sensorData,
+                                               const state_t *state)
+{
+  sitAwPostStateUpdateCallOut(sensorData, state);
+  sitAwPreThrustUpdateCallOut(setpoint);
+}
+
+/**
+ * Test values for a Free Fall situation.
+ *
+ * A free fall situation is considered identified when the vertical
+ * acceleration of the crazyflie (regardless of orientation - given by
+ * AccWZ) is approaching -1 (AccWZ is 0 when crazyflie is at rest). We
+ * will look for when AccWZ is within SITAW_FF_THRESHOLD of -1.
+ *
+ * At the same time, there should be no other accelerations experienced
+ * by the crazyflie.
+
+ * This can be checked by looking at the accMAG (total acceleration). If
+ * the accMAG is approaching 0, there are no other accelerations than accWZ.
+ * This helps to distinguish free fall situations from other movements
+ * such as shaking.
+ *
+ * @param accWZ  Vertical acceleration (regardless of orientation)
+ * @param accMAG All experienced accelerations.
+ *
+ * @return True if the situation has been detected, otherwise false.
+ */
+bool sitAwFFTest(float accWZ, float accMAG)
+{
+  /* Check that the total acceleration is close to zero. */
+  if(fabs(accMAG) > SITAW_FF_THRESHOLD) {
+    /* If the total acceleration deviates from 0, this is not a free fall situation. */
+    triggerReset(&sitAwFFAccWZ);
+    return false;
+  }
+
+  /**
+   * AccWZ approaches -1 in free fall. Check that the value stays within
+   * SITAW_FF_THRESHOLD of -1 for the triggerCount specified.
+   */
+  return(triggerTestValue(&sitAwFFAccWZ, fabs(accWZ + 1)));
+}
+
+/**
+ * Check if a Free Fall situation has been detected.
+ *
+ * @return True if the situation has been detected, otherwise false.
+ */
+bool sitAwFFDetected(void)
+{
+  return sitAwFFAccWZ.released;
+}
+
+/**
+ * Initialize the At Rest detection.
+ *
+ * See the sitAwARTest() function for details.
+ */
+void sitAwARInit(void)
+{
+  triggerInit(&sitAwARAccZ, triggerFuncIsLE, SITAW_AR_THRESHOLD, SITAW_AR_TRIGGER_COUNT);
+  triggerActivate(&sitAwARAccZ, true);
+}
+
+/**
+ * Test values for an At Rest situation.
+ *
+ * An At Rest situation is considered identified when the crazyflie is
+ * placed on its feet (accZ = 1) and with no horizontal accelerations
+ * (accX = accY = 0).
+ *
+ * Since there is always some minor noise in the measurements, we use
+ * a margin of SITAW_AR_THRESHOLD from the ideal values. Since this function
+ * does not check for thrust, the SITAW_AR_THRESHOLD is assumed to be set
+ * sufficiently close to the absolute resting values so that these values cannot
+ * be achieved (over time) during hovering or flight.
+ *
+ * @param accX   Horizontal X acceleration (when crazyflie is placed on its feet)
+ * @param accY   Horizontal Y acceleration (when crazyflie is placed on its feet)
+ * @param accZ   Vertical Z acceleration (when crazyflie is placed on its feet)
+ *
+ * @return True if the situation has been detected, otherwise false.
+ */
+bool sitAwARTest(float accX, float accY, float accZ)
+{
+  /* Check that there are no horizontal accelerations. At rest, these are 0. */
+  if((fabs(accX) > SITAW_AR_THRESHOLD) || (fabs(accY) > SITAW_AR_THRESHOLD)) {
+    /* If the X or Y accelerations are different than 0, the crazyflie is not at rest. */
+    triggerReset(&sitAwARAccZ);
+    return(false);
+  }
+
+  /**
+   * If the test above indicates that there are no horizontal movements, test the
+   * vertical acceleration value against the trigger.
+   *
+   * The vertical acceleration must be close to 1, but is allowed to oscillate slightly
+   * around 1. Testing that the deviation from 1 stays within SITAW_AR_THRESHOLD.
+   */
+  return(triggerTestValue(&sitAwARAccZ, fabs(accZ - 1)));
+}
+
+/**
+ * Check if an At Rest situation has been detected.
+ *
+ * @return True if the situation has been detected, otherwise false.
+ */
+bool sitAwARDetected(void)
+{
+  return sitAwARAccZ.released;
+}
+
+/**
+ * Initialize the Tumbled detection.
+ *
+ * See the sitAwTuTest() function for details.
+ */
+void sitAwTuInit(void)
+{
+  triggerInit(&sitAwTuAngle, triggerFuncIsGE, SITAW_TU_THRESHOLD, SITAW_TU_TRIGGER_COUNT);
+  triggerActivate(&sitAwTuAngle, true);
+}
+
+/**
+ * Test values for a Tumbled situation.
+ *
+ * A tumbled situation is considered identified when the roll or pitch has
+ * exceeded +/- SITAW_TU_THRESHOLD degrees.
+ *
+ * For thresholds beyond +/- 90 degrees, this is only reported by the roll
+ * value. The roll value is thus the only one of roll, pitch and yaw values
+ * which can detect upside down situations.
+ *
+ * Once a tumbled situation is identified, this can be used for instance to
+ * cut the thrust to the motors, avoiding the crazyflie from running
+ * propellers at significant thrust when accidentially crashing into walls
+ * or the ground.
+
+ * @param The actual roll in degrees. +180/-180 degrees means upside down.
+ * @param The actual pitch in degrees. 0 degrees means horizontal.
+ *
+ * @return True if the situation has been detected, otherwise false.
+ */
+bool sitAwTuTest(float eulerRollActual, float eulerPitchActual)
+{
+  /*
+   * It is sufficient to use a single trigger object, we simply pass the
+   * greatest of the roll and pitch absolute values to the trigger object
+   * at any given time.
+   */
+  float fAbsRoll  = fabs(eulerRollActual);
+  float fAbsPitch = fabs(eulerPitchActual);
+
+  /* Only the roll value will report if the crazyflie is turning upside down. */
+  return(triggerTestValue(&sitAwTuAngle, fAbsRoll >= fAbsPitch ? fAbsRoll : fAbsPitch));
+}
+
+/**
+ * Check if a Tumbled situation has been detected.
+ *
+ * @return True if the situation has been detected, otherwise false.
+ */
+bool sitAwTuDetected(void)
+{
+  return sitAwTuAngle.released;
+}
+
+/**
+ * Initialize the situation awareness subsystem.
+ */
+void sitAwInit(void)
+{
+  sitAwFFInit();
+  sitAwARInit();
+  sitAwTuInit();
+}
diff --git a/crazyflie-firmware-src/src/modules/src/sound_cf1.c b/crazyflie-firmware-src/src/modules/src/sound_cf1.c
new file mode 100644
index 0000000000000000000000000000000000000000..7dc93d23d1eb44f688de3dde4663008ffc0a3f41
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/sound_cf1.c
@@ -0,0 +1,52 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sound_cf1.c - Empty module used on Crazyflie 2.0 to play melodies and
+ *               system sounds
+ */
+
+#include <stdbool.h>
+#include <stdint.h>
+
+static bool isInit=false;
+
+void soundInit(void)
+{
+  if (isInit)
+    return;
+
+  isInit = true;
+}
+
+bool soundTest(void)
+{
+  return isInit;
+}
+
+void soundSetEffect(uint32_t effect)
+{
+}
+
+void soundSetFreq(uint32_t freq)
+{
+}
diff --git a/crazyflie-firmware-src/src/modules/src/sound_cf2.c b/crazyflie-firmware-src/src/modules/src/sound_cf2.c
new file mode 100644
index 0000000000000000000000000000000000000000..7e226750faa5cbd6106a7aad55e430455fcd1f97
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/sound_cf2.c
@@ -0,0 +1,371 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * sound_cf2.c - Module used to play melodies and system sounds though a buzzer
+ */
+
+#include <stdbool.h>
+
+/* FreeRtos includes */
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+
+#include "FreeRTOS.h"
+#include "timers.h"
+
+#include "config.h"
+#include "param.h"
+#include "log.h"
+#include "sound.h"
+#include "buzzer.h"
+
+/**
+ * Credit to http://tny.cz/e525c1b2 for supplying the tones
+ */
+#define OFF 0
+#define C0 16
+#define Db0 17
+#define D0  18
+#define Eb0 19
+#define E0  20
+#define F0  21
+#define Gb0 23
+#define G0  24
+#define Ab0 25
+#define A0 27
+#define Bb0 29
+#define B0  30
+#define C1  32
+#define Db1 34
+#define D1  36
+#define Eb1 38
+#define E1  41
+#define F1  43
+#define Gb1 46
+#define G1  49
+#define Ab1 51
+#define A1 55
+#define Bb1 58
+#define B1  61
+#define C2  65
+#define Db2 69
+#define D2  73
+#define Eb2 77
+#define E2  82
+#define F2  87
+#define Gb2 92
+#define G2  98
+#define Ab2 103
+#define A2 110
+#define Bb2 116
+#define B2  123
+#define C3  130
+#define Db3 138
+#define D3  146
+#define Eb3 155
+#define E3  164
+#define F3  174
+#define Gb3 185
+#define G3  196
+#define Ab3 207
+#define A3 220
+#define Bb3 233
+#define B3  246
+#define C4  261
+#define Db4 277
+#define D4  293
+#define Eb4 311
+#define E4  329
+#define F4  349
+#define Gb4 369
+#define G4  392
+#define Ab4 415
+#define A4 440
+#define Bb4 466
+#define B4  493
+#define C5  523
+#define Db5 554
+#define D5  587
+#define Eb5 622
+#define E5  659
+#define F5  698
+#define Gb5 739
+#define G5  783
+#define Ab5 830
+#define A5 880
+#define Bb5 932
+#define B5  987
+#define C6  1046
+#define Db6 1108
+#define D6  1174
+#define Eb6 1244
+#define E6  1318
+#define F6  1396
+#define Gb6 1479
+#define G6  1567
+#define Ab6 1661
+#define A6 1760
+#define Bb6 1864
+#define B6  1975
+#define C7  2093
+#define Db7 2217
+#define D7  2349
+#define Eb7 2489
+#define E7  2637
+#define F7  2793
+#define Gb7 2959
+#define G7  3135
+#define Ab7 3322
+#define A7 3520
+#define Bb7 3729
+#define B7  3951
+#define C8  4186
+#define Db8 4434
+#define D8  4698
+#define Eb8 4978
+/* Duration of notes */
+#define W  1  // 1/1
+#define H  2  // 1/2
+#define Q  4  // 1/4
+#define E  8  // 1/8
+#define S  16 // 1/16
+#define ES 6
+/* End markers */
+#define STOP {0xFE, 0}
+#define REPEAT {0xFF, 0}
+
+#define MAX_NOTE_LENGTH 80
+
+static bool isInit=false;
+
+typedef const struct {
+  uint16_t tone;
+  uint16_t duration;
+} Note;
+
+typedef const struct {
+  uint32_t bpm;
+  uint32_t delay;
+  Note notes[MAX_NOTE_LENGTH];
+} Melody;
+
+static uint32_t neffect = 0;
+static uint32_t sys_effect = 0;
+static uint32_t user_effect = 0;
+
+static Melody range_slow = {.bpm = 120, .delay = 1, .notes = {{C4, H}, {D4, H}, {E4, H}, {F4, H}, {G4, H}, {A4, H}, {B4, H}, REPEAT}};
+static Melody range_fast = {.bpm = 120, .delay = 1, .notes = {{C4, S}, {D4, S}, {E4, S}, {F4, S}, {G4, S}, {A4, S}, {B4, S}, REPEAT}};
+static Melody startup = {.bpm = 120, .delay = 1, .notes = {{C6, S}, {C6, S}, STOP}};
+static Melody calibrated = {.bpm = 120, .delay = 1, .notes = {{C4, S}, {E4, S}, {G4, S}, {C5, E}, STOP}};
+static Melody chg_done = {.bpm = 120, .delay = 1, .notes = {{D4, Q}, {A4, Q}, STOP}};
+static Melody lowbatt = {.bpm = 120, .delay = 1, .notes = {{D4, E}, {A4, E}, {D4, E}, REPEAT}};
+static Melody usb_disconnect = {.bpm = 120, .delay = 1, .notes = {{C4, E}, STOP}};
+static Melody usb_connect = {.bpm = 120, .delay = 1, .notes = {{A4, E}, STOP}};
+static Melody factory_test = {.bpm = 120, .delay = 1, .notes = {{A1, Q}, {OFF, S}, {A2, Q}, {OFF, S}, REPEAT}};
+static Melody starwars = {.bpm = 120, .delay = 1, .notes = {{A3, Q}, {A3, Q}, {A3, Q}, {F3, ES}, {C4, S},
+    {A3, Q}, {F3, ES}, {C4, S}, {A3, H},
+    {E4, Q}, {E4, Q}, {E4, Q}, {F4, ES}, {C4, S},
+    {Ab3, Q}, {F3, ES}, {C4, S}, {A3, H},
+    {A4, Q}, {A3, ES}, {A3, S}, {A4, Q}, {Ab4, ES}, {G4, S},
+    {Gb4, S}, {E4, S}, {F4, E}, {0, E}, {Bb3, E}, {Eb4, Q}, {D4, ES}, {Db4, S},
+    {C4, S}, {B3, S}, {C4, E}, {0, E}, {F3, E}, {Ab3, Q}, {F3, ES}, {A3, S},
+    {C4, Q}, {A3, ES}, {C4, S}, {E4, H},
+    {A4, Q}, {A3, ES}, {A3, S}, {A4, Q}, {Ab4, ES}, {G4, S},
+    {Gb4, S}, {E4, S}, {F4, E}, {0, E}, {Bb3, E}, {Eb4, Q}, {D4, ES}, {Db4, S},
+    {Gb4, S}, {E4, S}, {F4, E}, {0, E}, {Bb3, E}, {Eb4, Q}, {D4, ES}, {Db4, S},
+    {C4,S}, {B3, S}, {C4, E}, {0, E}, {F3, E}, {Ab3, Q}, {F3, ES}, {C4, S},
+    {A3, Q}, {F3, ES}, {C4, S}, {A3, H}, {0, H},
+    REPEAT}};
+static Melody valkyries = {.bpm = 140, .delay = 1, .notes = {{Gb3, Q}, {B3, Q},
+    {Gb3, S}, {B3, E},  {D4, Q}, {B3, Q}, {D4, Q}, {B3, S}, {D4, E}, {Gb4, Q},  
+    {D4, Q}, {Gb4, Q}, {D4, S}, {Gb4, E}, {A4, Q}, {A3, Q}, {D4, Q}, {A3, S},  
+    {D4, E}, {Gb4, H}, 
+    REPEAT}};
+
+typedef void (*BuzzerEffect)(uint32_t timer, uint32_t * mi, Melody * melody);
+
+static void off(uint32_t counter, uint32_t * mi, Melody * m) {
+  buzzerOff();
+}
+
+static void turnCurrentEffectOff() {
+  if (sys_effect != 0) {
+    sys_effect = 0;
+  } else {
+    user_effect = 0;
+  }
+}
+
+static uint32_t mcounter = 0;
+static void melodyplayer(uint32_t counter, uint32_t * mi, Melody * m) {
+  uint16_t tone = m->notes[(*mi)].tone;
+  uint16_t duration = m->notes[(*mi)].duration;
+
+  if (mcounter == 0) {
+    if (tone == 0xFE) {
+      // Turn off buzzer since we're at the end
+      (*mi) = 0;
+      turnCurrentEffectOff();
+    } else if (tone == 0xFF) {
+      // Loop the melody
+      (*mi) = 0;
+    } else {
+      // Play current note
+      buzzerOn(tone);
+      mcounter = (100 * 4 * 60) / (m->bpm * duration) - 1;
+      (*mi)++;
+    }
+  } else {
+    if (mcounter == 1) {
+        buzzerOff();
+    }
+    mcounter--;
+  }
+}
+
+static uint8_t static_ratio = 0;
+static uint16_t static_freq = 4000;
+static void bypass(uint32_t counter, uint32_t * mi, Melody * melody)
+{
+  buzzerOn(static_freq);
+}
+
+static uint16_t siren_start = 2000;
+static uint16_t siren_freq = 2000;
+static uint16_t siren_stop = 4000;
+static int16_t siren_step = 40;
+static void siren(uint32_t counter, uint32_t * mi, Melody * melody)
+{
+  siren_freq += siren_step;
+  if (siren_freq > siren_stop) {
+    siren_step *= -1;
+    siren_freq = siren_stop;
+  }
+  if (siren_freq < siren_start) {
+    siren_step *= -1;
+    siren_freq = siren_start;
+  }
+  buzzerOn(siren_freq);
+}
+
+static int pitchid;
+static int rollid;
+static int pitch;
+static int roll;
+static int tilt_freq;
+static int tilt_ratio;
+static void tilt(uint32_t counter, uint32_t * mi, Melody * melody)
+{
+  pitchid = logGetVarId("stabilizer", "pitch");
+  rollid = logGetVarId("stabilizer", "roll");
+
+  pitch = logGetInt(pitchid);
+  roll = logGetInt(rollid);
+  tilt_freq = 0;
+  tilt_ratio = 127;
+
+  if (abs(pitch) > 5) {
+    tilt_freq = 3000 - 50 * pitch;
+  }
+
+  buzzerOn(tilt_freq);
+}
+
+typedef struct {
+  BuzzerEffect call;
+  uint32_t mi;
+  Melody * melody;
+} EffectCall;
+
+static EffectCall effects[] = {
+    [SND_OFF] = {.call = &off},
+    [FACTORY_TEST] = {.call = &melodyplayer, .melody = &factory_test},
+    [SND_USB_CONN] = {.call = &melodyplayer, .melody = &usb_connect},
+    [SND_USB_DISC] = {.call = &melodyplayer, .melody = &usb_disconnect},
+    [SND_BAT_FULL] = {.call = &melodyplayer, .melody = &chg_done},
+    [SND_BAT_LOW] = {.call = &melodyplayer, .melody = &lowbatt},
+    [SND_STARTUP] = {.call = &melodyplayer, .melody = &startup},
+    [SND_CALIB] = {.call = &melodyplayer, .melody = &calibrated},
+    {.call = &melodyplayer, .melody = &range_slow},
+    {.call = &melodyplayer, .melody = &range_fast},
+    {.call = &melodyplayer, .melody = &starwars},
+    {.call = &melodyplayer, .melody = &valkyries},
+    {.call = &bypass},
+    {.call = &siren},
+    {.call = &tilt}
+};
+
+static xTimerHandle timer;
+static uint32_t counter = 0;
+
+static void soundTimer(xTimerHandle timer)
+{
+  int effect;
+  counter++;
+
+  if (sys_effect != 0) {
+    effect = sys_effect;
+  } else {
+    effect = user_effect;
+  }
+
+  if (effects[effect].call != 0) {
+    effects[effect].call(counter * 10, &effects[effect].mi, effects[effect].melody);
+  }
+}
+
+void soundInit(void)
+{
+  if (isInit) {
+    return;
+  }
+
+  neffect = sizeof(effects) / sizeof(effects[0]) - 1;
+
+  timer = xTimerCreate("SoundTimer", M2T(10), pdTRUE, NULL, soundTimer);
+  xTimerStart(timer, 100);
+
+  isInit = true;
+}
+
+bool soundTest(void)
+{
+  return isInit;
+}
+
+void soundSetEffect(uint32_t effect)
+{
+  sys_effect = effect;
+}
+
+void soundSetFreq(uint32_t freq) {
+
+}
+
+PARAM_GROUP_START(sound)
+PARAM_ADD(PARAM_UINT8, effect, &user_effect)
+PARAM_ADD(PARAM_UINT32 | PARAM_RONLY, neffect, &neffect)
+PARAM_ADD(PARAM_UINT16, freq, &static_freq)
+PARAM_ADD(PARAM_UINT8, ratio, &static_ratio)
+PARAM_GROUP_STOP(sound)
diff --git a/crazyflie-firmware-src/src/modules/src/stabilizer.c b/crazyflie-firmware-src/src/modules/src/stabilizer.c
new file mode 100644
index 0000000000000000000000000000000000000000..701c0985a753f1713c0588b9427c1eea84765da3
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/stabilizer.c
@@ -0,0 +1,172 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie Firmware
+ *
+ * Copyright (C) 2011-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ *
+ */
+#include <math.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "system.h"
+#include "log.h"
+#include "param.h"
+
+#include "stabilizer.h"
+
+#include "sensors.h"
+#include "commander.h"
+#include "ext_position.h"
+#include "sitaw.h"
+#include "controller.h"
+#include "power_distribution.h"
+
+#ifdef ESTIMATOR_TYPE_kalman
+#include "estimator_kalman.h"
+#else
+#include "estimator.h"
+#endif
+
+static bool isInit;
+
+// State variables for the stabilizer
+static setpoint_t setpoint;
+static sensorData_t sensorData;
+static state_t state;
+static control_t control;
+
+static void stabilizerTask(void* param);
+
+void stabilizerInit(void)
+{
+  if(isInit)
+    return;
+
+  sensorsInit();
+  stateEstimatorInit();
+  stateControllerInit();
+  powerDistributionInit();
+#if defined(SITAW_ENABLED)
+  sitAwInit();
+#endif
+
+  xTaskCreate(stabilizerTask, STABILIZER_TASK_NAME,
+              STABILIZER_TASK_STACKSIZE, NULL, STABILIZER_TASK_PRI, NULL);
+
+  isInit = true;
+}
+
+bool stabilizerTest(void)
+{
+  bool pass = true;
+
+  pass &= sensorsTest();
+  pass &= stateEstimatorTest();
+  pass &= stateControllerTest();
+  pass &= powerDistributionTest();
+
+  return pass;
+}
+
+/* The stabilizer loop runs at 1kHz (stock) or 500Hz (kalman). It is the
+ * responsibility of the different functions to run slower by skipping call
+ * (ie. returning without modifying the output structure).
+ */
+
+static void stabilizerTask(void* param)
+{
+  uint32_t tick = 0;
+  uint32_t lastWakeTime;
+  vTaskSetApplicationTaskTag(0, (void*)TASK_STABILIZER_ID_NBR);
+
+  //Wait for the system to be fully started to start stabilization loop
+  systemWaitStart();
+
+  // Wait for sensors to be calibrated
+  lastWakeTime = xTaskGetTickCount ();
+  while(!sensorsAreCalibrated()) {
+    vTaskDelayUntil(&lastWakeTime, F2T(RATE_MAIN_LOOP));
+  }
+
+  while(1) {
+    vTaskDelayUntil(&lastWakeTime, F2T(RATE_MAIN_LOOP));
+
+    getExtPosition(&state);
+#ifdef ESTIMATOR_TYPE_kalman
+    stateEstimatorUpdate(&state, &sensorData, &control);
+#else
+    sensorsAcquire(&sensorData, tick);
+    stateEstimator(&state, &sensorData, tick);
+#endif
+
+    commanderGetSetpoint(&setpoint, &state);
+
+    // sitAwUpdateSetpoint(&setpoint, &sensorData, &state);
+
+    stateController(&control, &setpoint, &sensorData, &state, tick);
+    powerDistribution(&control);
+
+    tick++;
+  }
+}
+
+LOG_GROUP_START(ctrltarget)
+LOG_ADD(LOG_FLOAT, roll, &setpoint.attitude.roll)
+LOG_ADD(LOG_FLOAT, pitch, &setpoint.attitude.pitch)
+LOG_ADD(LOG_FLOAT, yaw, &setpoint.attitudeRate.yaw)
+LOG_GROUP_STOP(ctrltarget)
+
+LOG_GROUP_START(stabilizer)
+LOG_ADD(LOG_FLOAT, roll, &state.attitude.roll)
+LOG_ADD(LOG_FLOAT, pitch, &state.attitude.pitch)
+LOG_ADD(LOG_FLOAT, yaw, &state.attitude.yaw)
+LOG_ADD(LOG_UINT16, thrust, &control.thrust)
+LOG_GROUP_STOP(stabilizer)
+
+LOG_GROUP_START(acc)
+LOG_ADD(LOG_FLOAT, x, &sensorData.acc.x)
+LOG_ADD(LOG_FLOAT, y, &sensorData.acc.y)
+LOG_ADD(LOG_FLOAT, z, &sensorData.acc.z)
+LOG_GROUP_STOP(acc)
+
+LOG_GROUP_START(baro)
+LOG_ADD(LOG_FLOAT, asl, &sensorData.baro.asl)
+LOG_ADD(LOG_FLOAT, temp, &sensorData.baro.temperature)
+LOG_ADD(LOG_FLOAT, pressure, &sensorData.baro.pressure)
+LOG_GROUP_STOP(baro)
+
+LOG_GROUP_START(gyro)
+LOG_ADD(LOG_FLOAT, x, &sensorData.gyro.x)
+LOG_ADD(LOG_FLOAT, y, &sensorData.gyro.y)
+LOG_ADD(LOG_FLOAT, z, &sensorData.gyro.z)
+LOG_GROUP_STOP(gyro)
+
+LOG_GROUP_START(mag)
+LOG_ADD(LOG_FLOAT, x, &sensorData.mag.x)
+LOG_ADD(LOG_FLOAT, y, &sensorData.mag.y)
+LOG_ADD(LOG_FLOAT, z, &sensorData.mag.z)
+LOG_GROUP_STOP(mag)
+
+LOG_GROUP_START(controller)
+LOG_ADD(LOG_INT16, ctr_yaw, &control.yaw)
+LOG_GROUP_STOP(controller)
diff --git a/crazyflie-firmware-src/src/modules/src/system.c b/crazyflie-firmware-src/src/modules/src/system.c
new file mode 100644
index 0000000000000000000000000000000000000000..fb05c8eabbdbf638d7c54f1580b7ac6f4fc3fc2d
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/system.c
@@ -0,0 +1,312 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * system.c - Top level module implementation
+ */
+#define DEBUG_MODULE "SYS"
+
+#include <stdbool.h>
+
+/* FreeRtos includes */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "semphr.h"
+
+#include "debug.h"
+#include "version.h"
+#include "config.h"
+#include "param.h"
+#include "log.h"
+#include "ledseq.h"
+#include "pm.h"
+
+#include "config.h"
+#include "system.h"
+#include "configblock.h"
+#include "worker.h"
+#include "freeRTOSdebug.h"
+#include "uart_syslink.h"
+#include "uart1.h"
+#include "uart2.h"
+#include "comm.h"
+#include "stabilizer.h"
+#include "commander.h"
+#include "console.h"
+#include "usblink.h"
+#include "mem.h"
+#include "proximity.h"
+#include "watchdog.h"
+#include "queuemonitor.h"
+#include "buzzer.h"
+#include "sound.h"
+
+#ifdef PLATFORM_CF1
+#include "uart.h"
+#endif
+
+#ifdef PLATFORM_CF2
+#include "deck.h"
+#endif
+
+
+#include "extrx.h"
+
+/* Private variable */
+static bool selftestPassed;
+static bool canFly;
+static bool isInit;
+
+/* System wide synchronisation */
+xSemaphoreHandle canStartMutex;
+
+/* Private functions */
+static void systemTask(void *arg);
+
+/* Public functions */
+void systemLaunch(void)
+{
+  xTaskCreate(systemTask, SYSTEM_TASK_NAME,
+              SYSTEM_TASK_STACKSIZE, NULL,
+              SYSTEM_TASK_PRI, NULL);
+
+}
+
+// This must be the first module to be initialized!
+void systemInit(void)
+{
+  if(isInit)
+    return;
+
+  canStartMutex = xSemaphoreCreateMutex();
+  xSemaphoreTake(canStartMutex, portMAX_DELAY);
+
+#ifdef PLATFORM_CF2
+  usblinkInit();
+#endif
+
+  /* Initialized hear and early so that DEBUG_PRINT (buffered) can be used early */
+  crtpInit();
+  consoleInit();
+
+  DEBUG_PRINT("----------------------------\n");
+  DEBUG_PRINT(P_NAME " is up and running!\n");
+  DEBUG_PRINT("Build %s:%s (%s) %s\n", V_SLOCAL_REVISION,
+              V_SREVISION, V_STAG, (V_MODIFIED)?"MODIFIED":"CLEAN");
+  DEBUG_PRINT("I am 0x%X%X%X and I have %dKB of flash!\n",
+              *((int*)(MCU_ID_ADDRESS+8)), *((int*)(MCU_ID_ADDRESS+4)),
+              *((int*)(MCU_ID_ADDRESS+0)), *((short*)(MCU_FLASH_SIZE_ADDRESS)));
+
+  configblockInit();
+  workerInit();
+  adcInit();
+  ledseqInit();
+  pmInit();
+  buzzerInit();
+
+  isInit = true;
+}
+
+bool systemTest()
+{
+  bool pass=isInit;
+
+#ifdef PLATFORM_CF1
+  pass &= adcTest();
+#endif
+  pass &= ledseqTest();
+  pass &= pmTest();
+  pass &= workerTest();
+  pass &= buzzerTest();
+  return pass;
+}
+
+/* Private functions implementation */
+
+void systemTask(void *arg)
+{
+  bool pass = true;
+
+  ledInit();
+  ledSet(CHG_LED, 1);
+
+#ifdef DEBUG_QUEUE_MONITOR
+  queueMonitorInit();
+#endif
+
+#ifdef PLATFORM_CF1
+  uartInit();
+#endif
+
+#ifdef ENABLE_UART1
+  uart1Init();
+#endif
+#ifdef ENABLE_UART2
+  uart2Init();
+#endif
+
+  //Init the high-levels modules
+  systemInit();
+
+#ifndef USE_RADIOLINK_CRTP
+#ifdef UART_OUTPUT_TRACE_DATA
+  //debugInitTrace();
+#endif
+#ifdef ENABLE_UART
+//  uartInit();
+#endif
+#endif //ndef USE_RADIOLINK_CRTP
+
+  commInit();
+  commanderInit();
+  stabilizerInit();
+#ifdef PLATFORM_CF2
+  deckInit();
+  #endif
+  soundInit();
+  memInit();
+
+#ifdef PROXIMITY_ENABLED
+  proximityInit();
+#endif
+
+  //Test the modules
+  pass &= systemTest();
+  pass &= configblockTest();
+  pass &= commTest();
+  pass &= commanderTest();
+  pass &= stabilizerTest();
+#ifdef PLATFORM_CF2
+  pass &= deckTest();
+  #endif
+  pass &= soundTest();
+  pass &= memTest();
+  pass &= watchdogNormalStartTest();
+
+  //Start the firmware
+  if(pass)
+  {
+    selftestPassed = 1;
+    systemStart();
+    soundSetEffect(SND_STARTUP);
+    ledseqRun(SYS_LED, seq_alive);
+    ledseqRun(LINK_LED, seq_testPassed);
+  }
+  else
+  {
+    selftestPassed = 0;
+    if (systemTest())
+    {
+      while(1)
+      {
+        ledseqRun(SYS_LED, seq_testPassed); //Red passed == not passed!
+        vTaskDelay(M2T(2000));
+        // System can be forced to start by setting the param to 1 from the cfclient
+        if (selftestPassed)
+        {
+	        DEBUG_PRINT("Start forced.\n");
+          systemStart();
+          break;
+        }
+      }
+    }
+    else
+    {
+      ledInit();
+      ledSet(SYS_LED, true);
+    }
+  }
+  DEBUG_PRINT("Free heap: %d bytes\n", xPortGetFreeHeapSize());
+
+  workerLoop();
+
+  //Should never reach this point!
+  while(1)
+    vTaskDelay(portMAX_DELAY);
+}
+
+
+/* Global system variables */
+void systemStart()
+{
+  xSemaphoreGive(canStartMutex);
+#ifndef DEBUG
+  watchdogInit();
+#endif
+}
+
+void systemWaitStart(void)
+{
+  //This permits to guarantee that the system task is initialized before other
+  //tasks waits for the start event.
+  while(!isInit)
+    vTaskDelay(2);
+
+  xSemaphoreTake(canStartMutex, portMAX_DELAY);
+  xSemaphoreGive(canStartMutex);
+}
+
+void systemSetCanFly(bool val)
+{
+  canFly = val;
+}
+
+bool systemCanFly(void)
+{
+  return canFly;
+}
+
+void vApplicationIdleHook( void )
+{
+  static uint32_t tickOfLatestWatchdogReset = M2T(0);
+
+  portTickType tickCount = xTaskGetTickCount();
+
+  if (tickCount - tickOfLatestWatchdogReset > M2T(WATCHDOG_RESET_PERIOD_MS))
+  {
+    tickOfLatestWatchdogReset = tickCount;
+    watchdogReset();
+  }
+
+  // Enter sleep mode. Does not work when debugging chip with SWD.
+  // Currently saves about 20mA STM32F405 current consumption (~30%).
+#ifndef DEBUG
+  { __asm volatile ("wfi"); }
+#endif
+}
+
+/*System parameters (mostly for test, should be removed from here) */
+PARAM_GROUP_START(cpu)
+PARAM_ADD(PARAM_UINT16 | PARAM_RONLY, flash, MCU_FLASH_SIZE_ADDRESS)
+PARAM_ADD(PARAM_UINT32 | PARAM_RONLY, id0, MCU_ID_ADDRESS+0)
+PARAM_ADD(PARAM_UINT32 | PARAM_RONLY, id1, MCU_ID_ADDRESS+4)
+PARAM_ADD(PARAM_UINT32 | PARAM_RONLY, id2, MCU_ID_ADDRESS+8)
+PARAM_GROUP_STOP(cpu)
+
+PARAM_GROUP_START(system)
+PARAM_ADD(PARAM_INT8, selftestPassed, &selftestPassed)
+PARAM_GROUP_STOP(sytem)
+
+/* Loggable variables */
+LOG_GROUP_START(sys)
+LOG_ADD(LOG_INT8, canfly, &canFly)
+LOG_GROUP_STOP(sys)
diff --git a/crazyflie-firmware-src/src/modules/src/trigger.c b/crazyflie-firmware-src/src/modules/src/trigger.c
new file mode 100644
index 0000000000000000000000000000000000000000..9eac37f69519a465a2dc55becc419ac06e592899
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/trigger.c
@@ -0,0 +1,214 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2015 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * trigger.c - Implementation of trigger mechanism.
+ */
+
+#include <stddef.h>
+#include <stdlib.h>
+#include "stm32fxxx.h"
+#include "trigger.h"
+
+/**
+ * Initialize a trigger object.
+ *
+ * Note that to activate the trigger, the triggerActivate() function must be called after
+ * calling triggerInit().
+ *
+ * @param trigger      The trigger object.
+ * @param func         The trigger function type.
+ * @param threshold    The threshold to use with the trigger function.
+ * @param triggerCount When testCounter reaches this value, a trigger is reported.
+ */
+void triggerInit(trigger_t *trigger, triggerFunc_t func, float threshold, uint32_t triggerCount)
+{
+  assert_param(trigger != NULL);
+  assert_param(func != triggerFuncNone);
+
+  trigger->active = false;
+  trigger->func = func;
+  trigger->threshold = threshold;
+  trigger->triggerCount = triggerCount;
+
+  triggerReset(trigger);
+}
+
+/**
+ * Register a trigger handler.
+ *
+ * @param trigger      The trigger object.
+ * @param handler      If a handler is registered, this handler function is called when the trigger is released. Otherwise NULL.
+ * @param handlerArg   Argument to pass to the handler function. NULL if not used.
+ */
+void triggerRegisterHandler(trigger_t *trigger, triggerHandler_t handler, void *handlerArg)
+{
+  assert_param(trigger != NULL);
+  assert_param(handler != NULL);
+
+  trigger->handler = handler;
+  trigger->handlerArg = handlerArg;
+  trigger->handlerCalled = false;
+}
+
+/**
+ * DeInitialize a trigger object.
+ *
+ * @param trigger The trigger object.
+ */
+void triggerDeInit(trigger_t *trigger)
+{
+  assert_param(trigger != NULL);
+
+  triggerInit(trigger, triggerFuncNone, 0, 0);
+  triggerRegisterHandler(trigger, NULL, NULL);
+  triggerReset(trigger);
+}
+
+/**
+ * Activate or deactivate a trigger object.
+ *
+ * This function does not influence the attributes of the trigger object as initialized by
+ * triggerInitialize() or triggerRegisterHandler() functions.
+ *
+ * Calling this function will reset all counters and flags, in addition to activating or
+ * deactivating the trigger.
+ *
+ * @param trigger The trigger object.
+ * @param active  Set the trigger active (true) or deactive (false).
+ */
+void triggerActivate(trigger_t *trigger, bool active)
+{
+  assert_param(trigger != NULL);
+
+  triggerReset(trigger);
+  trigger->active = active;
+}
+
+/**
+ * Reset a trigger object.
+ *
+ * This function does not influence the attributes of the trigger object as initialized by
+ * triggerInitialize(), triggerRegisterHandler() or triggerActivate() functions.
+ *
+ * Calling this function will reset all other counters and flags.
+ *
+ * @param trigger The trigger object.
+ */
+void triggerReset(trigger_t *trigger)
+{
+  assert_param(trigger != NULL);
+
+  trigger->testCounter = 0;
+  trigger->released = false;
+  trigger->handlerCalled = false;
+}
+
+/**
+ * Internal function incrementing the testCounter, but never further than the triggerCount value.
+ *
+  * @param trigger The trigger object.
+ */
+static void triggerIncTestCounter(trigger_t *trigger)
+{
+  assert_param(trigger != NULL);
+
+   if(trigger->testCounter < trigger->triggerCount) {
+     trigger->testCounter++;
+   }
+}
+
+/**
+ * Test a value against the trigger.
+ *
+ * Note that this function will call the registered handler function synchronously. The handler function
+ * is called only once, when the trigger is released. Subsequent calls to this function will not call
+ * the handler function again (until triggerReset() or triggerActivate() has been called to reset the
+ * trigger).
+ *
+ * This function will continue to return a value of true as long as the condition for the trigger release
+ * has been met (or exceeds the triggerCount value).
+ *
+ * This function will increment the testCounter until it reaches triggerCount.
+ *
+ * @param trigger   The trigger object.
+ * @param testValue The test value to compare against the threshold with the trigger function.
+ *
+ * @return True when the trigger has been released.
+ */
+bool triggerTestValue(trigger_t *trigger, float testValue)
+{
+  assert_param(trigger != NULL);
+
+  /* Do not do anything if the trigger has been deactivated. */
+  if(!trigger->active) {
+    return false;
+  }
+
+  switch(trigger->func) {
+    case triggerFuncIsLE: {
+      if(testValue <= trigger->threshold) {
+        triggerIncTestCounter(trigger);
+        break;
+      }
+      else {
+        /* Reset the trigger if the test failed. */
+        triggerReset(trigger);
+        return false;
+      }
+    }
+    case triggerFuncIsGE: {
+      if(testValue >= trigger->threshold) {
+        triggerIncTestCounter(trigger);
+        break;
+      }
+      else {
+        /* Reset the trigger if the test failed. */
+        triggerReset(trigger);
+        return false;
+      }
+    }
+    case triggerFuncNone: {
+      /* No action, included to avoid compiler warnings. */
+      break;
+    }
+  }
+
+  /* Check if the triggerCount has been reached. */
+  trigger->released = (trigger->testCounter >= trigger->triggerCount);
+
+  /* If the trigger has not been release, exit immediately. */
+  if(!trigger->released) {
+    return false;
+  }
+
+  /* The trigger object may be reset by the handler, thus make an internal copy of the released flag. */
+  bool iReleased = trigger->released;
+  if(trigger->released && (trigger->handler != NULL) && (!trigger->handlerCalled)) {
+    /* Set the handlerCalled = true before calling, since the handler may choose to reset the object. */
+    trigger->handlerCalled = true;
+    trigger->handler(trigger->handlerArg);
+  }
+
+  /* Return the release flag. This may return the value true more than once. */
+  return iReleased;
+}
diff --git a/crazyflie-firmware-src/src/modules/src/worker.c b/crazyflie-firmware-src/src/modules/src/worker.c
new file mode 100644
index 0000000000000000000000000000000000000000..e707ec7da33be5f6dfe3f2e85b37884a05df76a5
--- /dev/null
+++ b/crazyflie-firmware-src/src/modules/src/worker.c
@@ -0,0 +1,90 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * worker.c - Worker system that can execute asynchronous actions in tasks
+ */
+#include "worker.h"
+
+#include <errno.h>
+
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "queuemonitor.h"
+
+#include "console.h"
+
+#define WORKER_QUEUE_LENGTH 5
+
+struct worker_work {
+  void (*function)(void*);
+  void* arg;
+};
+
+static xQueueHandle workerQueue;
+
+void workerInit()
+{
+  if (workerQueue)
+    return;
+
+  workerQueue = xQueueCreate(WORKER_QUEUE_LENGTH, sizeof(struct worker_work));
+  DEBUG_QUEUE_MONITOR_REGISTER(workerQueue);
+}
+
+bool workerTest()
+{
+  return (workerQueue != NULL);
+}
+
+void workerLoop()
+{
+  struct worker_work work;
+
+  if (!workerQueue)
+    return;
+
+  while (1)
+  {
+    xQueueReceive(workerQueue, &work, portMAX_DELAY);
+    
+    if (work.function)
+      work.function(work.arg);
+  }
+}
+
+int workerSchedule(void (*function)(void*), void *arg)
+{
+  struct worker_work work;
+  
+  if (!function)
+    return ENOEXEC;
+  
+  work.function = function;
+  work.arg = arg;
+  if (xQueueSend(workerQueue, &work, 0) == pdFALSE)
+    return ENOMEM;
+
+  return 0; 
+}
+
diff --git a/crazyflie-firmware-src/src/platform/cf1/platform_cf1.c b/crazyflie-firmware-src/src/platform/cf1/platform_cf1.c
new file mode 100644
index 0000000000000000000000000000000000000000..b5fcdefde0f50fa3d7a73267c6cb32b744b285a6
--- /dev/null
+++ b/crazyflie-firmware-src/src/platform/cf1/platform_cf1.c
@@ -0,0 +1,42 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * TODO: Add description
+ */
+
+/* Project includes */
+#include "exti.h"
+#include "nvic.h"
+
+// TODO: Implement!
+int platformInit(void)
+{
+  //Low level init: Clock and Interrupt controller
+  nvicInit();
+
+  //EXTI interrupts
+  extiInit();
+
+  return 0;
+}
+
diff --git a/crazyflie-firmware-src/src/platform/cf2/platform_cf2.c b/crazyflie-firmware-src/src/platform/cf2/platform_cf2.c
new file mode 100644
index 0000000000000000000000000000000000000000..87110e6e8407d6e2f031c66e4e0f3db3b1049c84
--- /dev/null
+++ b/crazyflie-firmware-src/src/platform/cf2/platform_cf2.c
@@ -0,0 +1,43 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * TODO: Add description
+ */
+
+/* Personal configs */
+/* Project includes */
+#include "exti.h"
+#include "nvic.h"
+
+// TODO: Implement!
+int platformInit(void)
+{
+  //Low level init: Clock and Interrupt controller
+  nvicInit();
+
+  //EXTI interrupts
+  extiInit();
+
+  return 0;
+}
+
diff --git a/crazyflie-firmware-src/src/platform/platform.h b/crazyflie-firmware-src/src/platform/platform.h
new file mode 100644
index 0000000000000000000000000000000000000000..8968529b5ebccc4aa1ac571c674597d095329d87
--- /dev/null
+++ b/crazyflie-firmware-src/src/platform/platform.h
@@ -0,0 +1,51 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * config.h - Main configuration file
+ *
+ * This file define the default configuration of the copter
+ * It contains two types of parameters:
+ * - The global parameters are globally defined and independent of any
+ *   compilation profile. An example of such define could be some pinout.
+ * - The profiled defines, they are parameter that can be specific to each
+ *   dev build. The vanilla build is intended to be a "customer" build without
+ *   fancy spinning debugging stuff. The developers build are anything the
+ *   developer could need to debug and run his code/crazy stuff.
+ *
+ * The golden rule for the profile is NEVER BREAK ANOTHER PROFILE. When adding a
+ * new parameter, one shall take care to modified everything necessary to
+ * preserve the behavior of the other profiles.
+ *
+ * For the flag. T_ means task. H_ means HAL module. U_ would means utils.
+ */
+
+#ifndef PLATFORM_H_
+#define PLATFORM_H_
+
+/**
+ * Initilizes all platform specific things.
+ */
+int platformInit(void);
+
+
+#endif /* PLATFORM_H_ */
diff --git a/crazyflie-firmware-src/src/utils/interface/cfassert.h b/crazyflie-firmware-src/src/utils/interface/cfassert.h
new file mode 100644
index 0000000000000000000000000000000000000000..40109fabeb667dc78b8a5d8560f6dc6854e3f5e6
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/cfassert.h
@@ -0,0 +1,57 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * cfassert.h - Assert macro
+ */
+
+#include "console.h"
+
+#ifndef __CFASSERT_H__
+#define __CFASSERT_H__
+
+#define ASSERT(e)  if (e) ; \
+        else assertFail( #e, __FILE__, __LINE__ )
+
+#ifdef DEBUG
+#define IF_DEBUG_ASSERT(e)  if (e) ; \
+        else assertFail( #e, __FILE__, __LINE__ )
+#else
+#define IF_DEBUG_ASSERT(e)
+#endif
+
+#define ASSERT_FAILED() assertFail( "", __FILE__, __LINE__ )
+
+/**
+ * Assert handler function
+ */
+void assertFail(char *exp, char *file, int line);
+/**
+ * Print assert snapshot data
+ */
+void printAssertSnapshotData();
+/**
+ * Store assert snapshot data to be read at startup if a reset is triggered (watchdog)
+ */
+void storeAssertSnapshotData(char *file, int line);
+
+#endif //__CFASSERT_H__
diff --git a/crazyflie-firmware-src/src/utils/interface/configblock.h b/crazyflie-firmware-src/src/utils/interface/configblock.h
new file mode 100644
index 0000000000000000000000000000000000000000..3adcd7db7734cea3fe30dd386a09a30aee4ac159
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/configblock.h
@@ -0,0 +1,43 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * configblock.h - Simple static implementation of the config block
+ */
+
+#include <stdint.h>
+
+#ifndef __CONFIGBLOCK_H__
+#define __CONFIGBLOCK_H__
+
+int configblockInit(void);
+bool configblockTest(void);
+
+/* Static accessors */
+int configblockGetRadioChannel(void);
+int configblockGetRadioSpeed(void);
+uint64_t configblockGetRadioAddress(void);
+
+float configblockGetCalibPitch(void);
+float configblockGetCalibRoll(void);
+
+#endif //__CONFIGBLOCK_H__
diff --git a/crazyflie-firmware-src/src/utils/interface/cpuid.h b/crazyflie-firmware-src/src/utils/interface/cpuid.h
new file mode 100644
index 0000000000000000000000000000000000000000..3593e616109476e117cba766330c2c66714c6683
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/cpuid.h
@@ -0,0 +1,35 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * cpuid.h - CPU ID and Flash size function
+ */
+
+#ifndef __CPUID_H__
+#define __CPUID_H__
+
+//The CPU ID is 12 bytes long
+unsigned char * cpuidGetId();
+int cpuIdGetFlashSize();
+
+#endif /* __CPUID_H__ */
+
diff --git a/crazyflie-firmware-src/src/utils/interface/crc.h b/crazyflie-firmware-src/src/utils/interface/crc.h
new file mode 100644
index 0000000000000000000000000000000000000000..70afeb2a28b83cb15e4c2a159870fd5bf5cbc710
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/crc.h
@@ -0,0 +1,123 @@
+/**********************************************************************
+ *
+ * Filename:    crc.h
+ * 
+ * Description: A header file describing the various CRC standards.
+ *
+ * Notes:  See crc.c     
+ *
+ *
+ * Copyright (c) 2012 Bitcraze AB
+ * Copyright (c) 2000 by Michael Barr.  This software is placed into
+ * the public domain and may be used for any purpose.  However, this
+ * notice must not be changed or removed and no warranty is either
+ * expressed or implied by its publication or distribution.
+ **********************************************************************/
+/**
+ * @file 
+ * Efficient implementation of various CRC standards.
+ *
+ * Two CRC calculation function are implemented: flow and fast. The slow version
+ * is espcially inefficient but virtually use no RAM at all. The fast function
+ * is more efficient cpu-wise but require from 512 to 1KiB of RAM located lookup
+ * table (might be possible to move the table into FLASH, but then it would take
+ * 1K of flash ...).
+ * 
+ * crcInit() shall be used *only* if the fast version of CRC is used.
+ *
+ * The CRC algorythm to use is choosen in crc.h.
+ */
+
+#ifndef _crc_h
+#define _crc_h
+
+#include <stdint.h>
+
+#define FALSE	0
+#define TRUE	!FALSE
+
+/**
+ * Select the CRC standard from the list that follows.
+ */
+#define CRC32
+
+
+#if defined(CRC_CCITT)
+
+typedef uint16_t crc;
+
+#define CRC_NAME			"CRC-CCITT"
+#define POLYNOMIAL			0x1021
+#define INITIAL_REMAINDER	0xFFFF
+#define FINAL_XOR_VALUE		0x0000
+#define REFLECT_DATA		FALSE
+#define REFLECT_REMAINDER	FALSE
+#define CHECK_VALUE			0x29B1
+
+#elif defined(CRC16)
+
+typedef uint16_t crc;
+
+#define CRC_NAME			"CRC-16"
+#define POLYNOMIAL			0x8005
+#define INITIAL_REMAINDER	0x0000
+#define FINAL_XOR_VALUE		0x0000
+#define REFLECT_DATA		TRUE
+#define REFLECT_REMAINDER	TRUE
+#define CHECK_VALUE			0xBB3D
+
+#elif defined(CRC32)
+
+typedef uint32_t crc;
+
+#define CRC_NAME			"CRC-32"
+#define POLYNOMIAL			0x04C11DB7
+#define INITIAL_REMAINDER	0xFFFFFFFF
+#define FINAL_XOR_VALUE		0xFFFFFFFF
+#define REFLECT_DATA		TRUE
+#define REFLECT_REMAINDER	TRUE
+#define CHECK_VALUE			0xCBF43926
+
+#else
+
+#error "One of CRC_CCITT, CRC16, or CRC32 must be #define'd."
+
+#endif
+
+/**
+ * Init function that must be called before using crcFast().
+ * This function is useless for crcSlow() and shall not be called if only
+ * crcSlow() is used!
+ *
+ * @note Using this function will use 1KiB of BSS ram!
+ */
+void  crcInit(void);
+
+/**
+ * Slow implementation of CRC.
+ * 
+ * This function trades speeds for memory usage as it does not require
+ * pre-calculated tables but executes some code for each data bits. Good for one
+ * time CRC calculation. Bad for data communication check.
+ *
+ * @param datas Pointer to the data buffer onto the CRC will be calculated.
+ * @param nBytes Number of bytes to calculate the CRC from.
+ * @return The CRC value.
+ */
+crc   crcSlow(void * datas, int nBytes);
+
+/**
+ * Fast implementation of CRC.
+ * 
+ * This function trades memory usage for speed as it requires pre-calculated
+ * table (calculated by crcInit()). The requirement is 512Bytes for 16bits CRC
+ * and 1024Bytes for 32bits CRC.
+ *
+ * @param datas Pointer to the data buffer onto the CRC will be calculated.
+ * @param nBytes Number of bytes to calculate the CRC from.
+ * @return The CRC value.
+ */
+crc   crcFast(void * datas, int nBytes);
+
+
+#endif /* _crc_h */
diff --git a/crazyflie-firmware-src/src/utils/interface/debug.h b/crazyflie-firmware-src/src/utils/interface/debug.h
new file mode 100644
index 0000000000000000000000000000000000000000..0cf71eb38c295572b3491b8696a992f1803f06c4
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/debug.h
@@ -0,0 +1,66 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * debug.h - Debugging utility functions
+ */
+#include "config.h"
+#include "console.h"
+
+#ifdef DEBUG_MODULE
+#define DEBUG_FMT(fmt) DEBUG_MODULE ": " fmt
+#endif
+
+#ifndef DEBUG_FMT
+#define DEBUG_FMT(fmt) fmt
+#endif
+
+#if defined(DEBUG_PRINT_ON_UART)
+  #ifndef ENABLE_UART
+    #error "Need to define ENABLE_UART to use DEBUG_PRINT_ON_UART"
+  #endif
+  #define DEBUG_PRINT(fmt, ...) uartPrintf(DEBUG_FMT(fmt), ##__VA_ARGS__)
+  #define DEBUG_PRINT_OS(fmt, ...) uartPrintf(DEBUG_FMT(fmt), ##__VA_ARGS__)
+#elif defined(DEBUG_PRINT_ON_SWO)
+  #define DEBUG_PRINT(fmt, ...) eprintf(ITM_SendChar, fmt, ## __VA_ARGS__)
+  #define DEBUG_PRINT_OS(fmt, ...) eprintf(ITM_SendChar, fmt, ## __VA_ARGS__)
+#else
+  #define DEBUG_PRINT(fmt, ...) consolePrintf(DEBUG_FMT(fmt), ##__VA_ARGS__)
+#define DEBUG_PRINT_OS(fmt, ...) consolePrintf(DEBUG_FMT(fmt), ##__VA_ARGS__)
+  //#define DEBUG_PRINT(fmt, ...)
+#endif
+
+#ifndef PRINT_OS_DEBUG_INFO
+  #undef DEBUG_PRINT_OS
+  #define DEBUG_PRINT_OS(fmt, ...)
+#endif
+
+
+#ifdef TEST_PRINTS
+  #define TEST_AND_PRINT(e, msgOK, msgFail)\
+    if(e) { DEBUG_PRINT(msgOK); } else { DEBUG_PRINT(msgFail); }
+  #define FAIL_PRINT(msg) DEBUG_PRINT(msg)
+#else
+  #define TEST_AND_PRINT(e, msgOK, msgFail)
+  #define FAIL_PRINT(msg)
+#endif
+
diff --git a/crazyflie-firmware-src/src/utils/interface/eprintf.h b/crazyflie-firmware-src/src/utils/interface/eprintf.h
new file mode 100644
index 0000000000000000000000000000000000000000..812b3e630b40b110b8f70966ea83810798523aec
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/eprintf.h
@@ -0,0 +1,44 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (c) 2012 Bitcraze AB
+ *
+ * eprintf.c: Memory-friendly ultra-limited embedded implementation of printf
+ */
+
+#include <stdarg.h>
+
+#ifndef	__EPRINTF_H__
+#define __EPRINTF_H__
+
+/**
+ * putc function pointer definition
+ */
+typedef int (*putc_t)(int c);
+
+/**
+ * Light printf implementation
+ * @param[in] putcf Putchar function to be used by Printf
+ * @param[in] fmt Format string
+ * @param[in] ... Parameters to print
+ * @return the number of character printed
+ */
+int eprintf(putc_t putcf, char * fmt, ...) 
+    __attribute__ (( format(printf, 2, 3) ));
+
+/**
+ * Light printf implementation
+ * @param[in] putcf Putchar function to be used by Printf
+ * @param[in] fmt Format string
+ * @param[in] ap Parameters to print
+ * @return the number of character printed
+ */
+int evprintf(putc_t putcf, char * fmt, va_list ap);
+
+#endif //__EPRINTF_H__
diff --git a/crazyflie-firmware-src/src/utils/interface/filter.h b/crazyflie-firmware-src/src/utils/interface/filter.h
new file mode 100644
index 0000000000000000000000000000000000000000..9f02f93ea71d698f87b089a064edf7565f5733cd
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/filter.h
@@ -0,0 +1,50 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * filter.h - Filtering functions
+ */
+#ifndef FILTER_H_
+#define FILTER_H_
+#include <stdint.h>
+
+#define IIR_SHIFT         8
+
+int16_t iirLPFilterSingle(int32_t in, int32_t attenuation,  int32_t* filt);
+
+typedef struct {
+  float a1;
+  float a2;
+  float b0;
+  float b1;
+  float b2;
+  float delay_element_1;
+  float delay_element_2;
+} lpf2pData;
+
+void lpf2pInit(lpf2pData* lpfData, float sample_freq, float cutoff_freq);
+void lpf2pSetCutoffFreq(lpf2pData* lpfData, float sample_freq, float cutoff_freq);
+float lpf2pApply(lpf2pData* lpfData, float sample);
+float lpf2pReset(lpf2pData* lpfData, float sample);
+
+
+#endif //FILTER_H_
diff --git a/crazyflie-firmware-src/src/utils/interface/num.h b/crazyflie-firmware-src/src/utils/interface/num.h
new file mode 100644
index 0000000000000000000000000000000000000000..cb7b59f34e8b03472df75b399add94dd3a686058
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/num.h
@@ -0,0 +1,51 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * num.c - 16bit floating point handling functions
+ */
+
+#ifndef __NUM_H
+#define __NUM_H
+
+#include <stdint.h>
+
+#undef max
+#define max(a,b) ((a) > (b) ? (a) : (b))
+#undef min
+#define min(a,b) ((a) < (b) ? (a) : (b))
+
+#undef abs
+#define abs(a) ((a) > 0 ? (a) : (-1*(a)))
+
+#undef isnan
+#define isnan(n) ((n != n) ? 1 : 0)
+
+
+uint16_t single2half(float number);
+float half2single(uint16_t number);
+
+uint16_t limitUint16(int32_t value);
+float constrain(float value, const float minVal, const float maxVal);
+float deadband(float value, const float threshold);
+
+#endif
diff --git a/crazyflie-firmware-src/src/utils/interface/version.h b/crazyflie-firmware-src/src/utils/interface/version.h
new file mode 100644
index 0000000000000000000000000000000000000000..3d92b9f865b88e44c22d33a937422ef12ff2bed3
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/interface/version.h
@@ -0,0 +1,36 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * Version.h - Firmware version
+ */
+#ifndef __VERSION_H__
+#define __VERSION_H__
+
+#include <stdbool.h>
+
+extern const char * V_SLOCAL_REVISION;
+extern const char * V_SREVISION;
+extern const char * V_STAG;
+extern const bool V_MODIFIED;
+
+#endif /* __VERSION_H__ */
diff --git a/crazyflie-firmware-src/src/utils/src/FreeRTOS-openocd.c b/crazyflie-firmware-src/src/utils/src/FreeRTOS-openocd.c
new file mode 100644
index 0000000000000000000000000000000000000000..567e710b0b12422fb6bcaccbde9c1b179b09c96c
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/FreeRTOS-openocd.c
@@ -0,0 +1,20 @@
+/*
+ * Since at least FreeRTOS V7.5.3 uxTopUsedPriority is no longer
+ * present in the kernel, so it has to be supplied by other means for
+ * OpenOCD's threads awareness.
+ *
+ * Add this file to your project, and, if you're using --gc-sections,
+ * ``--undefined=uxTopUsedPriority'' (or
+ * ``-Wl,--undefined=uxTopUsedPriority'' when using gcc for final
+ * linking) to your LDFLAGS; same with all the other symbols you need.
+ */
+
+#include "FreeRTOS.h"
+
+#ifdef __GNUC__
+#define USED __attribute__((used))
+#else
+#define USED
+#endif
+
+const int USED uxTopUsedPriority = configMAX_PRIORITIES;
diff --git a/crazyflie-firmware-src/src/utils/src/abort.c b/crazyflie-firmware-src/src/utils/src/abort.c
new file mode 100644
index 0000000000000000000000000000000000000000..2375a74db9bc228d13d3e1df74f3acc7d49c42f4
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/abort.c
@@ -0,0 +1,14 @@
+/**
+ *
+ * abort.c: Simple abort function.
+ *
+ * Newer versions of newlibc always use unwind functions which do need an
+ * implementation of abort(). So in order to link without standard libraries
+ * (-nostdlib) we have to provide abort().
+ */
+
+void abort(void)
+{
+  while (1)
+    ;
+}
diff --git a/crazyflie-firmware-src/src/utils/src/cfassert.c b/crazyflie-firmware-src/src/utils/src/cfassert.c
new file mode 100644
index 0000000000000000000000000000000000000000..d6bd24aaa6c203a08535c3b69758ca549370b40e
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/cfassert.c
@@ -0,0 +1,88 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * cfassert.c - Assert implementation
+ */
+
+#define DEBUG_MODULE "SYS"
+
+#include <stdint.h>
+#include "FreeRTOS.h"
+#include "cfassert.h"
+#include "led.h"
+#include "motors.h"
+#include "debug.h"
+
+#define MAGIC_ASSERT_INDICATOR 0x2f8a001f
+
+typedef struct SNAPSHOT_DATA {
+  uint32_t magicNumber;
+  char* fileName;
+  int line;
+} SNAPSHOT_DATA;
+
+// The .nzds section is not cleared at startup, data here will survive a
+// reset (by the watch dog for instance)
+SNAPSHOT_DATA snapshot __attribute__((section(".nzds"))) = {
+  .magicNumber = 0,
+  .fileName = "",
+  .line = 0
+};
+
+
+void assertFail(char *exp, char *file, int line)
+{
+  portDISABLE_INTERRUPTS();
+  storeAssertSnapshotData(file, line);
+  DEBUG_PRINT("Assert failed %s:%d\n", file, line);
+
+  motorsSetRatio(MOTOR_M1, 0);
+  motorsSetRatio(MOTOR_M2, 0);
+  motorsSetRatio(MOTOR_M3, 0);
+  motorsSetRatio(MOTOR_M4, 0);
+
+  ledClearAll();
+  ledSet(ERR_LED1, 1);
+  ledSet(ERR_LED2, 1);
+
+  while (1);
+}
+
+void storeAssertSnapshotData(char *file, int line)
+{
+  snapshot.magicNumber = MAGIC_ASSERT_INDICATOR;
+  snapshot.fileName = file;
+  snapshot.line = line;
+}
+
+void printAssertSnapshotData()
+{
+  if (MAGIC_ASSERT_INDICATOR == snapshot.magicNumber) {
+    DEBUG_PRINT("Assert failed at %s:%d\n", snapshot.fileName, snapshot.line);
+  } else {
+    DEBUG_PRINT("No assert information found\n");
+  }
+}
+
+
+
diff --git a/crazyflie-firmware-src/src/utils/src/configblockeeprom.c b/crazyflie-firmware-src/src/utils/src/configblockeeprom.c
new file mode 100644
index 0000000000000000000000000000000000000000..df31145d33c0b12b93d178686a8f8099356eef76
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/configblockeeprom.c
@@ -0,0 +1,313 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * configblock.c - Simple static implementation of the config block
+ */
+#define DEBUG_MODULE "CFGBLK"
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <string.h>
+
+#include "config.h"
+#include "debug.h"
+#include "i2cdev.h"
+#include "configblock.h"
+#include "eeprom.h"
+
+
+/* Internal format of the config block */
+#define MAGIC 0x43427830
+#define VERSION 1
+#define HEADER_SIZE_BYTES 5 // magic + version
+#define OVERHEAD_SIZE_BYTES (HEADER_SIZE_BYTES + 1) // + cksum
+
+// Old versions
+struct configblock_v0_s {
+  /* header */
+  uint32_t magic;
+  uint8_t  version;
+  /* Content */
+  uint8_t radioChannel;
+  uint8_t radioSpeed;
+  float calibPitch;
+  float calibRoll;
+  /* Simple modulo 256 checksum */
+  uint8_t cksum;
+} __attribute__((__packed__));
+
+// Current version
+struct configblock_v1_s {
+  /* header */
+  uint32_t magic;
+  uint8_t  version;
+  /* Content */
+  uint8_t radioChannel;
+  uint8_t radioSpeed;
+  float calibPitch;
+  float calibRoll;
+  uint8_t radioAddress_upper;
+  uint32_t radioAddress_lower;
+  /* Simple modulo 256 checksum */
+  uint8_t cksum;
+} __attribute__((__packed__));
+
+// Set version 1 as current version
+typedef struct configblock_v1_s configblock_t;
+
+static configblock_t configblock;
+static configblock_t configblockDefault =
+{
+    .magic = MAGIC,
+    .version = VERSION,
+    .radioChannel = RADIO_CHANNEL,
+    .radioSpeed = RADIO_DATARATE,
+    .calibPitch = 0.0,
+    .calibRoll = 0.0,
+    .radioAddress_upper = ((uint64_t)RADIO_ADDRESS >> 32),
+    .radioAddress_lower = (RADIO_ADDRESS & 0xFFFFFFFFULL),
+};
+
+static const uint32_t configblockSizes[] =
+{
+  sizeof(struct configblock_v0_s),
+  sizeof(struct configblock_v1_s),
+};
+
+static bool isInit = false;
+static bool cb_ok = false;
+
+static bool configblockCheckMagic(configblock_t *configblock);
+static bool configblockCheckVersion(configblock_t *configblock);
+static bool configblockCheckChecksum(configblock_t *configblock);
+static bool configblockCheckDataIntegrity(uint8_t *data, uint8_t version);
+static bool configblockWrite(configblock_t *configblock);
+static bool configblockCopyToNewVersion(configblock_t *configblockSaved, configblock_t *configblockNew);
+
+static uint8_t calculate_cksum(void* data, size_t len)
+{
+  unsigned char* c = data;
+  int i;
+  unsigned char cksum=0;
+  
+  for (i=0; i<len; i++)
+    cksum += *(c++);
+
+  return cksum;
+}
+
+int configblockInit(void)
+{
+  if(isInit)
+    return 0;
+
+  i2cdevInit(I2C1_DEV);
+  eepromInit(I2C1_DEV);
+
+  // Because of strange behavior from I2C device during expansion port test
+  // the first read needs to be discarded
+  eepromTestConnection();
+
+  if (eepromTestConnection())
+  {
+    if (eepromReadBuffer((uint8_t *)&configblock, 0, sizeof(configblock)))
+    {
+      //Verify the config block
+      if (configblockCheckMagic(&configblock))
+      {
+        if (configblockCheckVersion(&configblock))
+        {
+          if (configblockCheckChecksum(&configblock))
+          {
+            // Everything is fine
+            DEBUG_PRINT("v%d, verification [OK]\n", configblock.version);
+            cb_ok = true;
+          }
+          else
+          {
+            DEBUG_PRINT("Verification [FAIL]\n");
+            cb_ok = false;
+          }
+        }
+        else // configblockCheckVersion
+        {
+          // Check data integrity of old version data
+          if (configblock.version <= VERSION &&
+              configblockCheckDataIntegrity((uint8_t *)&configblock, configblock.version))
+          {
+            // Not the same version, try to upgrade
+            if (configblockCopyToNewVersion(&configblock, &configblockDefault))
+            {
+              // Write updated config block to eeprom
+              if (configblockWrite(&configblock))
+              {
+                cb_ok = true;
+              }
+            }
+          }
+          else
+          {
+            // Can't copy old version due to bad data.
+            cb_ok = false;
+          }
+        }
+      }
+    }
+  }
+
+  if (cb_ok == false)
+  {
+    // Copy default data to used structure.
+    memcpy((uint8_t *)&configblock, (uint8_t *)&configblockDefault, sizeof(configblock));
+    // Write default configuration to eeprom
+    if (configblockWrite(&configblockDefault))
+    {
+      cb_ok = true;
+    }
+    else
+    {
+      return -1;
+    }
+  }
+
+  isInit = true;
+
+  return 0;
+}
+
+bool configblockTest(void)
+{
+  return eepromTest();
+}
+
+static bool configblockCheckMagic(configblock_t *configblock)
+{
+  return (configblock->magic == MAGIC);
+}
+
+static bool configblockCheckVersion(configblock_t *configblock)
+{
+  return (configblock->version == VERSION);
+}
+
+static bool configblockCheckChecksum(configblock_t *configblock)
+{
+  return (configblock->cksum == calculate_cksum(configblock, sizeof(configblock_t) - 1));
+}
+
+static bool configblockCheckDataIntegrity(uint8_t *data, uint8_t version)
+{
+  bool status = false;
+
+  if (version == 0)
+  {
+    struct configblock_v0_s *v0 = ( struct configblock_v0_s *)data;
+    status = (v0->cksum == calculate_cksum(data, sizeof(struct configblock_v0_s) - 1));
+  }
+  else if (version == 1)
+  {
+    struct configblock_v1_s *v1 = ( struct configblock_v1_s *)data;
+    status = (v1->cksum == calculate_cksum(data, sizeof(struct configblock_v1_s) - 1));
+  }
+
+  return status;
+}
+
+static bool configblockWrite(configblock_t *configblock)
+{
+  // Write default configuration to eeprom
+  configblock->cksum = calculate_cksum(configblock, sizeof(configblock_t) - 1);
+  if (!eepromWriteBuffer((uint8_t *)configblock, 0, sizeof(configblock_t)))
+  {
+    return false;
+  }
+
+  return true;
+}
+
+static bool configblockCopyToNewVersion(configblock_t *configblockSaved, configblock_t *configblockNew)
+{
+  configblock_t configblockTmp;
+
+  // Copy new data to temp config memory
+  memcpy((uint8_t *)&configblockTmp, (uint8_t *)configblockNew, sizeof(configblock_t));
+
+  if (configblockSaved->version <= VERSION &&
+      sizeof(configblock_t) >= configblockSizes[configblockSaved->version])
+  {
+    // Copy old saved eeprom data to new structure
+    memcpy((uint8_t *)&configblockTmp + HEADER_SIZE_BYTES,
+           (uint8_t *)configblockSaved + HEADER_SIZE_BYTES,
+           configblockSizes[configblockSaved->version] - OVERHEAD_SIZE_BYTES);
+    // Copy updated block to saved structure
+    memcpy((uint8_t *)configblockSaved, (uint8_t *)&configblockTmp, sizeof(configblock_t));
+  }
+  else
+  {
+    return false;
+  }
+
+  return true;
+}
+
+/* Static accessors */
+int configblockGetRadioChannel(void)
+{
+  if (cb_ok)
+    return configblock.radioChannel;
+  else
+    return RADIO_CHANNEL;
+}
+
+int configblockGetRadioSpeed(void)
+{
+  if (cb_ok)
+    return configblock.radioSpeed;
+  else
+    return RADIO_DATARATE;
+}
+
+uint64_t configblockGetRadioAddress(void)
+{
+  if (cb_ok)
+    return ((uint64_t)configblock.radioAddress_upper << 32) | (uint64_t)configblock.radioAddress_lower;
+  else
+    return RADIO_ADDRESS;
+}
+
+float configblockGetCalibPitch(void)
+{
+  if (cb_ok)
+    return configblock.calibPitch;
+  else
+    return 0;
+}
+
+float configblockGetCalibRoll(void)
+{
+  if (cb_ok)
+    return configblock.calibRoll;
+  else
+    return 0;
+}
diff --git a/crazyflie-firmware-src/src/utils/src/configblockflash.c b/crazyflie-firmware-src/src/utils/src/configblockflash.c
new file mode 100644
index 0000000000000000000000000000000000000000..70d05de404f45952fce095a7925a12570c9fbe1c
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/configblockflash.c
@@ -0,0 +1,126 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * configblock.c - Simple static implementation of the config block
+ */
+#define DEBUG_MODULE "CFGBLK"
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <unistd.h>
+
+#include "config.h"
+#include "configblock.h"
+#include "debug.h"
+
+/* Internal format of the config block */
+#define MAGIC 0x43427830
+#define VERSION 0
+struct configblock_s {
+  /* header */
+  uint32_t magic;
+  uint8_t  version;
+  /* Content */
+  uint8_t radioChannel;
+  uint8_t radioSpeed;
+  float calibPitch;
+  float calibRoll;
+  /* Simple modulo 256 checksum */
+  uint8_t cksum;
+} __attribute__((__packed__));
+
+static struct configblock_s *configblock;
+
+static bool cb_ok=false;
+
+static uint8_t calculate_cksum(void* data, size_t len)
+{
+  unsigned char* c = data;
+  int i;
+  unsigned char cksum=0;
+  
+  for (i=0; i<len; i++)
+    cksum += *(c++);
+
+  return cksum;
+}
+
+int configblockInit(void)
+{
+  configblock = (void*)CONFIG_BLOCK_ADDRESS;
+
+  //Verify the config block
+  if (configblock->magic!=MAGIC || configblock->version!= VERSION || 
+      calculate_cksum(configblock, sizeof(*configblock)) )
+  {
+    DEBUG_PRINT("Verification [FAIL]\n");
+    return -1;
+  }
+  else
+  {
+    DEBUG_PRINT("v%d, verification [OK]\n", configblock->version);
+    cb_ok = true;
+  }
+
+  
+  return 0;
+}
+
+bool configblockTest(void)
+{
+  return true;
+}
+
+/* Static accessors */
+int configblockGetRadioChannel(void)
+{
+  if (cb_ok)
+    return configblock->radioChannel;
+  else
+    return RADIO_CHANNEL;
+}
+
+int configblockGetRadioSpeed(void)
+{
+  if (cb_ok)
+    return configblock->radioSpeed;
+  else
+    return RADIO_DATARATE;
+}
+
+float configblockGetCalibPitch(void)
+{
+  if (cb_ok)
+    return configblock->calibPitch;
+  else
+    return 0;
+}
+
+float configblockGetCalibRoll(void)
+{
+  if (cb_ok)
+    return configblock->calibRoll;
+  else
+    return 0;
+}
+
diff --git a/crazyflie-firmware-src/src/utils/src/cpuid.c b/crazyflie-firmware-src/src/utils/src/cpuid.c
new file mode 100644
index 0000000000000000000000000000000000000000..8bbcd025f92ff0b14452a8ea18adb40b833eff0e
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/cpuid.c
@@ -0,0 +1,36 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * cpuid.c - CPU ID functions
+ */
+#include "cpuid.h"
+
+unsigned char * cpuidGetId()
+{
+  return (unsigned char *)(0x1FFFF7E8);
+}
+
+int cpuIdGetFlashSize()
+{
+  return *((short*)(0x1FFFF7E0));
+}
diff --git a/crazyflie-firmware-src/src/utils/src/crc.c b/crazyflie-firmware-src/src/utils/src/crc.c
new file mode 100644
index 0000000000000000000000000000000000000000..b69c3bb5a7ebae3c3aa1837c6e2c418162569e4f
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/crc.c
@@ -0,0 +1,227 @@
+/**********************************************************************
+ *
+ * Filename:    crc.c
+ * 
+ * Description: Slow and fast implementations of the CRC standards.
+ *
+ * Notes:       The parameters for each supported CRC standard are
+ *				defined in the header file crc.h.  The implementations
+ *				here should stand up to further additions to that list.
+ *
+ *              Modified by Bitcraze: made static local variables and 
+ *              used stdint.h types where relevant.
+ *
+ * Copyright (c) 2012 Bitcraze AB
+ * Copyright (c) 2000 by Michael Barr.  This software is placed into
+ * the public domain and may be used for any purpose.  However, this
+ * notice must not be changed or removed and no warranty is either
+ * expressed or implied by its publication or distribution.
+ **********************************************************************/
+
+#include "crc.h"
+
+/*
+ * Derive parameters from the standard-specific parameters in crc.h.
+ */
+#define WIDTH    (8 * sizeof(crc))
+#define TOPBIT   (1 << (WIDTH - 1))
+
+#if (REFLECT_DATA == TRUE)
+#undef  REFLECT_DATA
+#define REFLECT_DATA(X)			((unsigned char) reflect((X), 8))
+#else
+#undef  REFLECT_DATA
+#define REFLECT_DATA(X)			(X)
+#endif
+
+#if (REFLECT_REMAINDER == TRUE)
+#undef  REFLECT_REMAINDER
+#define REFLECT_REMAINDER(X)	((crc) reflect((X), WIDTH))
+#else
+#undef  REFLECT_REMAINDER
+#define REFLECT_REMAINDER(X)	(X)
+#endif
+
+/*********************************************************************
+ *
+ * Function:    reflect()
+ * 
+ * Description: Reorder the bits of a binary sequence, by reflecting
+ *				them about the middle position.
+ *
+ * Notes:		No checking is done that nBits <= 32.
+ *
+ * Returns:		The reflection of the original data.
+ *
+ *********************************************************************/
+static unsigned long reflect(unsigned long data, unsigned char nBits)
+{
+  unsigned long reflection = 0x00000000;
+  unsigned char bit;
+
+  /*
+   * Reflect the data about the center bit.
+   */
+  for (bit = 0; bit < nBits; ++bit)
+  {
+    /*
+     * If the LSB bit is set, set the reflection of it.
+     */
+    if (data & 0x01)
+    {
+      reflection |= (1 << ((nBits - 1) - bit));
+    }
+
+    data = (data >> 1);
+  }
+
+  return (reflection);
+
+} /* reflect() */
+
+/*********************************************************************
+ *
+ * Function:    crcSlow()
+ * 
+ * Description: Compute the CRC of a given message.
+ *
+ * Notes:		
+ *
+ * Returns:		The CRC of the message.
+ *
+ *********************************************************************/
+crc crcSlow(void * datas, int nBytes)
+{
+  crc remainder = INITIAL_REMAINDER;
+  unsigned char * message = datas;
+  int byte;
+  unsigned char bit;
+
+  /*
+   * Perform modulo-2 division, a byte at a time.
+   */
+  for (byte = 0; byte < nBytes; ++byte)
+  {
+    /*
+     * Bring the next byte into the remainder.
+     */
+    remainder ^= (REFLECT_DATA(message[byte]) << (WIDTH - 8));
+
+    /*
+     * Perform modulo-2 division, a bit at a time.
+     */
+    for (bit = 8; bit > 0; --bit)
+    {
+      /*
+       * Try to divide the current data bit.
+       */
+      if (remainder & TOPBIT)
+      {
+        remainder = (remainder << 1) ^ POLYNOMIAL;
+      }
+      else
+      {
+        remainder = (remainder << 1);
+      }
+    }
+  }
+
+  /*
+   * The final remainder is the CRC result.
+   */
+  return (REFLECT_REMAINDER(remainder) ^ FINAL_XOR_VALUE);
+
+} /* crcSlow() */
+
+#ifdef CRC_FAST
+static crc crcTable[256];
+
+/*********************************************************************
+ *
+ * Function:    crcInit()
+ * 
+ * Description: Populate the partial CRC lookup table.
+ *
+ * Notes:		This function must be rerun any time the CRC standard
+ *				is changed.  If desired, it can be run "offline" and
+ *				the table results stored in an embedded system's ROM.
+ *
+ * Returns:		None defined.
+ *
+ *********************************************************************/
+void crcInit(void)
+{
+  crc remainder;
+  int dividend;
+  unsigned char bit;
+
+  /*
+   * Compute the remainder of each possible dividend.
+   */
+  for (dividend = 0; dividend < 256; ++dividend)
+  {
+    /*
+     * Start with the dividend followed by zeros.
+     */
+    remainder = dividend << (WIDTH - 8);
+
+    /*
+     * Perform modulo-2 division, a bit at a time.
+     */
+    for (bit = 8; bit > 0; --bit)
+    {
+      /*
+       * Try to divide the current data bit.
+       */
+      if (remainder & TOPBIT)
+      {
+        remainder = (remainder << 1) ^ POLYNOMIAL;
+      }
+      else
+      {
+        remainder = (remainder << 1);
+      }
+    }
+
+    /*
+     * Store the result into the table.
+     */
+    crcTable[dividend] = remainder;
+  }
+
+} /* crcInit() */
+
+/*********************************************************************
+ *
+ * Function:    crcFast()
+ * 
+ * Description: Compute the CRC of a given message.
+ *
+ * Notes:		crcInit() must be called first.
+ *
+ * Returns:		The CRC of the message.
+ *
+ *********************************************************************/
+crc crcFast(void * datas, int nBytes)
+{
+  crc remainder = INITIAL_REMAINDER;
+  unsigned char * message = datas;
+  unsigned char data;
+  int byte;
+
+  /*
+   * Divide the message by the polynomial, a byte at a time.
+   */
+  for (byte = 0; byte < nBytes; ++byte)
+  {
+    data = REFLECT_DATA(message[byte]) ^ (remainder >> (WIDTH - 8));
+    remainder = crcTable[data] ^ (remainder << 8);
+  }
+
+  /*
+   * The final remainder is the CRC.
+   */
+  return (REFLECT_REMAINDER(remainder) ^ FINAL_XOR_VALUE);
+
+} /* crcFast() */
+#endif
diff --git a/crazyflie-firmware-src/src/utils/src/debug.c b/crazyflie-firmware-src/src/utils/src/debug.c
new file mode 100644
index 0000000000000000000000000000000000000000..f743f7f5ff1386cc41720ef34c042a4232e3fb36
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/debug.c
@@ -0,0 +1,31 @@
+/*
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * debug.c - Debugging utility functions
+ */
+
+
+
+
+
+
diff --git a/crazyflie-firmware-src/src/utils/src/eprintf.c b/crazyflie-firmware-src/src/utils/src/eprintf.c
new file mode 100644
index 0000000000000000000000000000000000000000..3cd1d9e74551a3d7816fb929320d7c60e67be655
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/eprintf.c
@@ -0,0 +1,183 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (c) 2012 Bitcraze AB
+ *
+ * eprintf.c: Memory-friendly ultra-limited embedded implementation of printf
+ *
+ * This implementation trades CPU cycle for data memory eficiency
+ * (No malloc, no unecessary buffers, etc...)
+ *
+ * Functionality: Implements %s, %d, %x, %X and %f without print size settings.
+ * The float handling is verry limited and without exponential notation (ie.
+ * works good for number around 0 and within int32 value range).
+ *
+ * To use this printf a 'putc' function shall be implemented with the prototype
+ * 'int putc(int)'. Then a macro calling eprintf can be created. For example:
+ * int consolePutc(int c);
+ * #define consolePrintf(FMT, ...) eprintf(consolePutc, FMT, ## __VA_ARGS__)
+ */
+#include "eprintf.h"
+
+#include <stdarg.h>
+#include <stdbool.h>
+#include <ctype.h>
+
+static const char digit[] = {'0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 
+                             'A', 'B', 'C', 'D', 'E', 'F'};
+
+int get_int_len (int value)
+{
+  int l=1;
+  while(value>9)
+  {
+    l++;
+    value/=10;
+  }
+  return l;
+}
+
+int power(int a, int b)
+{
+  int i;
+  int x = a;
+
+  for (i = 1; i < b; i++)
+  {
+    x *= a;
+  }
+
+  return x;
+}
+
+static int itoa(putc_t putcf, int num, int base, int precision)
+{
+  long long int i = 1;
+  int len = 0;
+  unsigned int n = num;
+  int numLenght = get_int_len(num);
+  int fillWithZero = 0;
+
+  if (num == 0)
+  {
+    putcf('0');
+    return 1;
+  }
+
+  if (num < 0  && base == 10)
+  {
+    n = -num;
+    putcf('-');
+  }
+
+  if (numLenght < precision)
+  {
+    fillWithZero = precision -numLenght;
+    while (fillWithZero>0)
+    {
+      putcf('0');
+      len++;
+      fillWithZero--;
+    }
+  }
+
+  while (n / i)
+  i*=base;
+
+  while (i /= base)
+  {
+    putcf(digit[(n / i) % base]);
+    len++;
+  }
+  
+  return len;
+}
+
+int evprintf(putc_t putcf, char * fmt, va_list ap)
+{
+  int len=0;
+  float num;
+  char* str;
+  int precision;
+
+  while (*fmt)
+  {
+    precision = 6;
+    if (*fmt == '%')
+    {
+      while (!isalpha((unsigned) * ++fmt))//TODO: Implement basic print length handling!
+      {
+        if (*fmt == '.')
+        {
+          if (isdigit((unsigned)*++fmt))
+            precision = *fmt - '0';
+        }
+      }
+      switch (*fmt++)
+      {
+        case 'i':
+        case 'd':
+          len += itoa(putcf, va_arg(ap, int), 10 , 0);
+          break;
+        case 'u':
+          len += itoa(putcf, va_arg(ap, unsigned int), 10 , 0);
+          break;
+        case 'l':
+          if (*fmt++ == 'u')
+            len += itoa(putcf, va_arg(ap, long unsigned int), 10 , 0);
+          break;
+        case 'x':
+        case 'X':
+          len += itoa(putcf, va_arg(ap, int), 16 , 0);
+          break;
+        case 'f':
+          num = va_arg(ap, double);
+          if(num<0)
+          {
+            putcf('-');
+            num = -num;
+            len++;
+          }
+          len += itoa(putcf, (int)num, 10, 0);
+          putcf('.'); len++;
+          len += itoa(putcf, (num - (int)num) * power(10,precision), 10, precision);
+          break;
+        case 's':
+          str = va_arg( ap, char* );
+          while(*str)
+          {
+            putcf(*str++);
+            len++;
+          }
+          break;
+        default:
+          break;
+      }
+    }
+    else
+    {
+      putcf(*fmt++);
+      len++;
+    }
+  }
+  
+  return len;
+}
+
+int eprintf(putc_t putcf, char * fmt, ...)
+{
+  va_list ap;
+  int len;
+
+  va_start(ap, fmt);
+  len = evprintf(putcf, fmt, ap);
+  va_end(ap);
+
+  return len;
+}
diff --git a/crazyflie-firmware-src/src/utils/src/filter.c b/crazyflie-firmware-src/src/utils/src/filter.c
new file mode 100644
index 0000000000000000000000000000000000000000..281cb38b5be67f626b2aefa7d55a36fa8b7e8be9
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/filter.c
@@ -0,0 +1,109 @@
+/**
+ *    ||          ____  _ __
+ * +------+      / __ )(_) /_______________ _____  ___
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * filter.h - Filtering functions
+ */
+
+#include <math.h>
+#include <stdlib.h>
+
+#include "filter.h"
+
+/**
+ * IIR filter the samples.
+ */
+int16_t iirLPFilterSingle(int32_t in, int32_t attenuation,  int32_t* filt)
+{
+  int32_t inScaled;
+  int32_t filttmp = *filt;
+  int16_t out;
+
+  if (attenuation > (1<<IIR_SHIFT))
+  {
+    attenuation = (1<<IIR_SHIFT);
+  }
+  else if (attenuation < 1)
+  {
+    attenuation = 1;
+  }
+
+  // Shift to keep accuracy
+  inScaled = in << IIR_SHIFT;
+  // Calculate IIR filter
+  filttmp = filttmp + (((inScaled-filttmp) >> IIR_SHIFT) * attenuation);
+  // Scale and round
+  out = (filttmp >> 8) + ((filttmp & (1 << (IIR_SHIFT - 1))) >> (IIR_SHIFT - 1));
+  *filt = filttmp;
+
+  return out;
+}
+
+/**
+ * 2-Pole low pass filter
+ */
+void lpf2pInit(lpf2pData* lpfData, float sample_freq, float cutoff_freq)
+{
+  if (lpfData == NULL || cutoff_freq <= 0.0f) {
+    return;
+  }
+
+  lpf2pSetCutoffFreq(lpfData, sample_freq, cutoff_freq);
+}
+
+void lpf2pSetCutoffFreq(lpf2pData* lpfData, float sample_freq, float cutoff_freq)
+{
+  float fr = sample_freq/cutoff_freq;
+  float ohm = tanf(M_PI/fr);
+  float c = 1.0f+2.0f*cosf(M_PI/4.0f)*ohm+ohm*ohm;
+  lpfData->b0 = ohm*ohm/c;
+  lpfData->b1 = 2.0f*lpfData->b0;
+  lpfData->b2 = lpfData->b0;
+  lpfData->a1 = 2.0f*(ohm*ohm-1.0f)/c;
+  lpfData->a2 = (1.0f-2.0f*cosf(M_PI/4.0f)*ohm+ohm*ohm)/c;
+  lpfData->delay_element_1 = 0.0f;
+  lpfData->delay_element_2 = 0.0f;
+}
+
+float lpf2pApply(lpf2pData* lpfData, float sample)
+{
+  float delay_element_0 = sample - lpfData->delay_element_1 * lpfData->a1 - lpfData->delay_element_2 * lpfData->a2;
+  if (!isfinite(delay_element_0)) {
+    // don't allow bad values to propigate via the filter
+    delay_element_0 = sample;
+  }
+
+  float output = delay_element_0 * lpfData->b0 + lpfData->delay_element_1 * lpfData->b1 + lpfData->delay_element_2 * lpfData->b2;
+
+  lpfData->delay_element_2 = lpfData->delay_element_1;
+  lpfData->delay_element_1 = delay_element_0;
+  return output;
+}
+
+float lpf2pReset(lpf2pData* lpfData, float sample)
+{
+  float dval = sample / (lpfData->b0 + lpfData->b1 + lpfData->b2);
+  lpfData->delay_element_1 = dval;
+  lpfData->delay_element_2 = dval;
+  return lpf2pApply(lpfData, sample);
+}
+
diff --git a/crazyflie-firmware-src/src/utils/src/num.c b/crazyflie-firmware-src/src/utils/src/num.c
new file mode 100644
index 0000000000000000000000000000000000000000..33340a64db873c2637949223b44edf80bc12d608
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/num.c
@@ -0,0 +1,123 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2012-2016 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * num.c - 16bit floating point handling functions
+ */
+
+#include <math.h>
+#include <stdint.h>
+
+#include "num.h"
+
+/* Half precision floating point **********************************************
+ *
+ * To not use the GCC implementation, uint16_t is used to carry fp16 values
+ *
+ * FP16 or Half precision floating points is specified by IEEE 754 as binary 16.
+ * (float is specified as binary 32). This implementation is NOT GUARANTEED to
+ * be conform to the ieee 754 specification, it is 'just' good enough for the
+ * Crazyflie usage. For more info about fp16 see 
+ * http://en.wikipedia.org/wiki/Half-precision_floating-point_format
+ *
+ * The current implementation has the following limitation:
+ *  * No subnormalized number generation
+ *  * Rounding seems to give at least 11 bits precision
+ *  * Faster and smaller than the GCC implementation 
+ */
+
+uint16_t single2half(float number)
+{
+    uint32_t num = *((uint32_t*)&number);
+    uint32_t s = num>>31;
+    uint32_t e = (num>>23)&0x0FF;
+    
+    if ((e==255) && (num&0x007fffff))
+        return 0x7E00; // NaN
+    if (e>(127+15))
+        return s?0xFC00:0x7C00;  //+/- inf
+    if (e<(127-15))
+        return 0; //Do not handle generating subnormalised representation
+    
+    return (s<<15) | ((e-127+15)<<10) | (((num>>13)&0x3FF)+((num>>12)&0x01));
+}
+
+float half2single(uint16_t number)
+{
+    uint32_t fp32;
+    uint32_t s = number>>15;
+    uint32_t e = (number>>10)&0x01F;
+    
+    //All binary16 can be mapped in a binary32
+    if(e==0)
+        e=15-127;
+    if (e==0x1F)
+    {
+        if (number&0x03FF)
+            fp32 = 0x7FC00000; // NaN
+        else
+            fp32 = s?0xFF800000:0x7F800000;  //+/- inf
+    }
+    else
+        fp32 = (s<<31) | ((e+127-15)<<23) | ((number&0x3ff)<<13);
+    
+    return *(float*)&fp32;
+}
+
+
+/*****************************************************************************/
+
+uint16_t limitUint16(int32_t value)
+{
+  if(value > UINT16_MAX)
+  {
+    value = UINT16_MAX;
+  }
+  else if(value < 0)
+  {
+    value = 0;
+  }
+
+  return (uint16_t)value;
+}
+
+float constrain(float value, const float minVal, const float maxVal)
+{
+  return min(maxVal, max(minVal,value));
+}
+
+float deadband(float value, const float threshold)
+{
+  if (fabs(value) < threshold)
+  {
+    value = 0;
+  }
+  else if (value > 0)
+  {
+    value -= threshold;
+  }
+  else if (value < 0)
+  {
+    value += threshold;
+  }
+  return value;
+}
diff --git a/crazyflie-firmware-src/src/utils/src/version.vtpl b/crazyflie-firmware-src/src/utils/src/version.vtpl
new file mode 100644
index 0000000000000000000000000000000000000000..4e6de8f052c641e42071ddfb51fe1b3dedee3c59
--- /dev/null
+++ b/crazyflie-firmware-src/src/utils/src/version.vtpl
@@ -0,0 +1,48 @@
+/**
+ *    ||          ____  _ __                           
+ * +------+      / __ )(_) /_______________ _____  ___ 
+ * | 0xBC |     / __  / / __/ ___/ ___/ __ `/_  / / _ \
+ * +------+    / /_/ / / /_/ /__/ /  / /_/ / / /_/  __/
+ *  ||  ||    /_____/_/\__/\___/_/   \__,_/ /___/\___/
+ *
+ * Crazyflie control firmware
+ *
+ * Copyright (C) 2011-2012 Bitcraze AB
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, in version 3.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * version.tmpl - version of the build
+ */
+#include <stdint.h>
+#include <stdbool.h>
+
+#include "config.h"
+#include "param.h"
+
+const char * V_SLOCAL_REVISION="{local_revision}";
+const char * V_SREVISION="{revision}";
+const char * V_STAG="{tag}";
+const char * V_BRANCH="{branch}";
+const char * V_PROFILE=P_NAME;
+const bool V_MODIFIED={modified};
+
+/* Version recoverable from the ground */
+const uint32_t V_REVISION_0={irevision0};
+const uint16_t V_REVISION_1={irevision1};
+
+PARAM_GROUP_START(firmware)
+PARAM_ADD(PARAM_UINT32 | PARAM_RONLY, revision0, &V_REVISION_0)
+PARAM_ADD(PARAM_UINT16 | PARAM_RONLY, revision1, &V_REVISION_1)
+PARAM_ADD(PARAM_UINT8 | PARAM_RONLY, modified, &V_MODIFIED)
+PARAM_GROUP_STOP(firmware)
+