You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@mynewt.apache.org by ma...@apache.org on 2017/03/10 19:51:55 UTC

[50/52] [partial] incubator-mynewt-core git commit: Add support for STM32F7xx and NUCLEO-F767

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/bsp/stm32f767-nucleo/src/system_stm32f7xx.c
----------------------------------------------------------------------
diff --git a/hw/bsp/stm32f767-nucleo/src/system_stm32f7xx.c b/hw/bsp/stm32f767-nucleo/src/system_stm32f7xx.c
new file mode 100644
index 0000000..57bafcd
--- /dev/null
+++ b/hw/bsp/stm32f767-nucleo/src/system_stm32f7xx.c
@@ -0,0 +1,277 @@
+/**
+  ******************************************************************************
+  * @file    system_stm32f7xx.c
+  * @author  MCD Application Team
+  * @version V1.2.0
+  * @date    30-December-2016
+  * @brief   CMSIS Cortex-M7 Device Peripheral Access Layer System Source File.
+  *
+  *   This file provides two functions and one global variable to be called from 
+  *   user application:
+  *      - SystemInit(): This function is called at startup just after reset and 
+  *                      before branch to main program. This call is made inside
+  *                      the "startup_stm32f7xx.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.
+  *
+  *
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT 2016 STMicroelectronics</center></h2>
+  *
+  * Redistribution and use in source and binary forms, with or without modification,
+  * are permitted provided that the following conditions are met:
+  *   1. Redistributions of source code must retain the above copyright notice,
+  *      this list of conditions and the following disclaimer.
+  *   2. Redistributions in binary form must reproduce the above copyright notice,
+  *      this list of conditions and the following disclaimer in the documentation
+  *      and/or other materials provided with the distribution.
+  *   3. Neither the name of STMicroelectronics nor the names of its contributors
+  *      may be used to endorse or promote products derived from this software
+  *      without specific prior written permission.
+  *
+  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+  *
+  ******************************************************************************
+  */
+
+/** @addtogroup CMSIS
+  * @{
+  */
+
+/** @addtogroup stm32f7xx_system
+  * @{
+  */  
+  
+/** @addtogroup STM32F7xx_System_Private_Includes
+  * @{
+  */
+
+#include "stm32f7xx.h"
+#include "bsp/cmsis_nvic.h"
+
+#if !defined  (HSE_VALUE) 
+  #define HSE_VALUE    ((uint32_t)25000000) /*!< Default value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined  (HSI_VALUE)
+  #define HSI_VALUE    ((uint32_t)16000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F7xx_System_Private_TypesDefinitions
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F7xx_System_Private_Defines
+  * @{
+  */
+
+/************************* Miscellaneous Configuration ************************/
+
+/*!< 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. */
+/******************************************************************************/
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F7xx_System_Private_Macros
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F7xx_System_Private_Variables
+  * @{
+  */
+
+  /* This variable is updated in three ways:
+      1) by calling CMSIS function SystemCoreClockUpdate()
+      2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+      3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency 
+         Note: If you use this function to configure the system clock; then there
+               is no need to call the 2 first functions listed above, since SystemCoreClock
+               variable is updated automatically.
+  */
+  uint32_t SystemCoreClock = 16000000;
+  const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+  const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F7xx_System_Private_FunctionPrototypes
+  * @{
+  */
+
+/**
+  * @}
+  */
+
+/** @addtogroup STM32F7xx_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;
+
+  /* Relocate the vector table */
+  NVIC_Relocate();
+}
+
+/**
+   * @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 stm32f7xx_hal_conf.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 stm32f7xx_hal_conf.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;
+}
+
+/**
+  * @}
+  */
+
+/**
+  * @}
+  */
+  
+/**
+  * @}
+  */    
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/bsp/stm32f767-nucleo/stm32f767-nucleo.ld
----------------------------------------------------------------------
diff --git a/hw/bsp/stm32f767-nucleo/stm32f767-nucleo.ld b/hw/bsp/stm32f767-nucleo/stm32f767-nucleo.ld
new file mode 100644
index 0000000..c70073e
--- /dev/null
+++ b/hw/bsp/stm32f767-nucleo/stm32f767-nucleo.ld
@@ -0,0 +1,32 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
+ *
+ * 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.
+ */
+
+/* Linker script for STM32F767 when running from flash and using the bootloader */
+
+/* Linker script to configure memory regions. */
+MEMORY
+{
+  FLASH (rx) :  ORIGIN = 0x08040000, LENGTH = 768K /* Image slot 1 */
+  ITCM (rx)  :  ORIGIN = 0x00000000, LENGTH = 16K
+  DTCM (rwx) :  ORIGIN = 0x20000000, LENGTH = 128K
+  RAM (rwx)  :  ORIGIN = 0x20020000, LENGTH = 512K
+}
+
+/* This linker script is used for images and thus contains an image header */
+_imghdr_size = 0x20;

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/bsp/stm32f767-nucleo/syscfg.yml
----------------------------------------------------------------------
diff --git a/hw/bsp/stm32f767-nucleo/syscfg.yml b/hw/bsp/stm32f767-nucleo/syscfg.yml
new file mode 100644
index 0000000..a4d2a73
--- /dev/null
+++ b/hw/bsp/stm32f767-nucleo/syscfg.yml
@@ -0,0 +1,38 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
+#
+# 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.
+#
+
+syscfg.defs:
+    UART_0:
+        description: 'Uart 0'
+        value:  1
+    TIMER_0:
+        description: 'Timer 0'
+        value:  1
+    TIMER_1:
+        description: 'Timer 1'
+        value: 1
+    TIMER_2:
+        description: 'Timer 2'
+        value: 1
+
+syscfg.vals:
+    REBOOT_LOG_FLASH_AREA: FLASH_AREA_REBOOT_LOG
+    CONFIG_FCB_FLASH_AREA: FLASH_AREA_NFFS
+    NFFS_FLASH_AREA: FLASH_AREA_NFFS
+    COREDUMP_FLASH_AREA: FLASH_AREA_IMAGE_1

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/mcu/stm/stm32f7xx/include/mcu/cortex_m7.h
----------------------------------------------------------------------
diff --git a/hw/mcu/stm/stm32f7xx/include/mcu/cortex_m7.h b/hw/mcu/stm/stm32f7xx/include/mcu/cortex_m7.h
new file mode 100644
index 0000000..59fd9db
--- /dev/null
+++ b/hw/mcu/stm/stm32f7xx/include/mcu/cortex_m7.h
@@ -0,0 +1,35 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
+ *
+ * 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.
+ */
+
+#ifndef __MCU_CORTEX_M4_H__
+#define __MCU_CORTEX_M4_H__
+
+#include "stm32f7xx.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define OS_TICKS_PER_SEC    (1000)
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MCU_CORTEX_M4_H__ */

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/mcu/stm/stm32f7xx/include/mcu/mcu.h
----------------------------------------------------------------------
diff --git a/hw/mcu/stm/stm32f7xx/include/mcu/mcu.h b/hw/mcu/stm/stm32f7xx/include/mcu/mcu.h
new file mode 100644
index 0000000..5721567
--- /dev/null
+++ b/hw/mcu/stm/stm32f7xx/include/mcu/mcu.h
@@ -0,0 +1,48 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
+ *
+ * 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.
+ */
+
+#ifndef __MCU_MCU_H_
+#define __MCU_MCU_H_
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*
+ * Defines for naming GPIOs.
+ */
+#define MCU_GPIO_PORTA(pin)	((0 * 16) + (pin))
+#define MCU_GPIO_PORTB(pin)	((1 * 16) + (pin))
+#define MCU_GPIO_PORTC(pin)	((2 * 16) + (pin))
+#define MCU_GPIO_PORTD(pin)	((3 * 16) + (pin))
+#define MCU_GPIO_PORTE(pin)	((4 * 16) + (pin))
+#define MCU_GPIO_PORTF(pin)	((5 * 16) + (pin))
+#define MCU_GPIO_PORTG(pin)	((6 * 16) + (pin))
+#define MCU_GPIO_PORTH(pin)	((7 * 16) + (pin))
+#define MCU_GPIO_PORTI(pin)	((8 * 16) + (pin))
+#define MCU_GPIO_PORTJ(pin)	((8 * 16) + (pin))
+
+/* NOTE: PORTK only have pins 0, 1, 3, 4, 5, 6, 7 available */
+#define MCU_GPIO_PORTK(pin)	((8 * 16) + (pin))
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MCU_MCU_H_ */

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7_bsp.h
----------------------------------------------------------------------
diff --git a/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7_bsp.h b/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7_bsp.h
new file mode 100644
index 0000000..98dac5b
--- /dev/null
+++ b/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7_bsp.h
@@ -0,0 +1,55 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
+ *
+ * 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.
+ */
+
+#ifndef __MCU_STM32F7_BSP_H_
+#define __MCU_STM32F7_BSP_H_
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * BSP specific UART settings.
+ */
+struct stm32f7_uart_cfg {
+    USART_TypeDef *suc_uart;            /* UART dev registers */
+    volatile uint32_t *suc_rcc_reg;     /* RCC register to modify */
+    uint32_t suc_rcc_dev;               /* RCC device ID */
+    int8_t suc_pin_tx;                  /* pins for IO */
+    int8_t suc_pin_rx;
+    int8_t suc_pin_rts;
+    int8_t suc_pin_cts;
+    uint8_t suc_pin_af;                 /* AF selection for this */
+    IRQn_Type suc_irqn;                 /* NVIC IRQn */
+};
+
+/*
+ * Internal API for stm32f7xx mcu specific code.
+ */
+int hal_gpio_init_af(int pin, uint8_t af_type, enum hal_gpio_pull pull, uint8_t
+od);
+
+struct hal_flash;
+extern struct hal_flash stm32f7_flash_dev;
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MCU_STM32F7_BSP_H_ */

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7xx_mynewt_hal.h
----------------------------------------------------------------------
diff --git a/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7xx_mynewt_hal.h b/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7xx_mynewt_hal.h
new file mode 100644
index 0000000..10c51ec
--- /dev/null
+++ b/hw/mcu/stm/stm32f7xx/include/mcu/stm32f7xx_mynewt_hal.h
@@ -0,0 +1,74 @@
+/*
+ * Licensed to the Apache Software Foundation (ASF) under one
+ * or more contributor license agreements.  See the NOTICE file
+ * distributed with this work for additional information
+ * regarding copyright ownership.  The ASF licenses this file
+ * to you under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
+ *
+ * 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.
+ */
+
+#ifndef __MCU_STM32F7_MYNEWT_HAL_H
+#define __MCU_STM32F7_MYNEWT_HAL_H
+
+#include "stm32f7xx.h"
+#include "stm32f7xx_hal_dma.h"
+#include "stm32f7xx_hal_gpio.h"
+#include "stm32f7xx_hal_i2c.h"
+#include "stm32f7xx_hal_spi.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Helper functions to enable/disable interrupts. */
+#define __HAL_DISABLE_INTERRUPTS(x)                     \
+    do {                                                \
+        x = __get_PRIMASK();                            \
+        __disable_irq();                                \
+    } while(0);
+
+#define __HAL_ENABLE_INTERRUPTS(x)                      \
+    do {                                                \
+        if (!x) {                                       \
+            __enable_irq();                             \
+        }                                               \
+    } while(0);
+
+
+int hal_gpio_init_stm(int pin, GPIO_InitTypeDef *cfg);
+int hal_gpio_deinit_stm(int pin, GPIO_InitTypeDef *cfg);
+
+struct stm32f7_hal_i2c_cfg {
+    I2C_TypeDef *hic_i2c;
+    volatile uint32_t *hic_rcc_reg;      /* RCC register to modify */
+    uint32_t hic_rcc_dev;                /* RCC device ID */
+    uint8_t hic_pin_sda;
+    uint8_t hic_pin_scl;
+    uint8_t hic_pin_af;
+    uint8_t hic_10bit;
+    uint32_t hic_speed;
+};
+
+struct stm32f7_hal_spi_cfg {
+    int ss_pin;                          /* for slave mode */
+    int sck_pin;
+    int miso_pin;
+    int mosi_pin;
+    int irq_prio;
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __MCU_STM32F4_MYNEWT_HAL_H */

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-core/blob/35529b95/hw/mcu/stm/stm32f7xx/pkg.yml
----------------------------------------------------------------------
diff --git a/hw/mcu/stm/stm32f7xx/pkg.yml b/hw/mcu/stm/stm32f7xx/pkg.yml
new file mode 100644
index 0000000..1573805
--- /dev/null
+++ b/hw/mcu/stm/stm32f7xx/pkg.yml
@@ -0,0 +1,40 @@
+#
+# Licensed to the Apache Software Foundation (ASF) under one
+# or more contributor license agreements.  See the NOTICE file
+# distributed with this work for additional information
+# regarding copyright ownership.  The ASF licenses this file
+# to you under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
+#
+# 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.
+#
+
+pkg.name: hw/mcu/stm/stm32f7xx
+pkg.description: MCU definition for STM32F7 ARM Cortex-M7 chips.
+pkg.author: "Apache Mynewt <de...@mynewt.incubator.apache.org>"
+pkg.homepage: "http://mynewt.apache.org/"
+pkg.keywords:
+    - stm32
+    - stm32f7
+
+pkg.type: sdk
+
+pkg.ign_files:
+    - ".*template.*"
+
+pkg.ign_dirs:
+    - "Device"
+
+pkg.deps:
+    - hw/hal
+    - hw/mcu/stm/stm32f7xx
+    - hw/cmsis-core
+    - compiler/arm-none-eabi-m7