works and calculates air quality, based on bme680 repo but modified for stm32

This commit is contained in:
robin 2023-11-17 10:41:27 +00:00
commit fd839ed467
20 changed files with 4938 additions and 0 deletions

57
.gitignore vendored Normal file
View File

@ -0,0 +1,57 @@
# STM32Cube copied library and project folders
Drivers/*
MDK-ARM/*
EWARM/*
# CrossWorks project files
!*/*.hzp
!*/*.hzs
*.o
.mxproject
Debug/*
*.settings
# Object files
*.o
*.ko
*.obj
*.elf
# Libraries
*.lib
*.a
*.la
*.lo
# Shared objects (inc. Windows DLLs)
*.dll
*.so
*.so.*
*.dylib
# Executables
*.exe
*.out
*.app
*.i*86
*.x86_64
*.hex
# Misc
*.map
*.m
*.png
# Eclipse CDT project files
.cproject
.project
.settings/
# Vagrant directory
.vagrant/
# Include makefiles
!Makefile
*~

161
Core/Inc/bme680.h Normal file
View File

@ -0,0 +1,161 @@
#ifndef BME680_H
#define BME680
#include <stdint.h>
#define BME680_IS_SPI(m) ((m & 1) == 1)
#define BME680_IS_FLOAT(m) (((m >> 1) & 1) == 0)
#define BME680_GAS_ENABLED(m) (((m >> 2) & 1) == 1)
#define BME680_IDAC(c) (c << 1)
#define BME680_GAS_WAIT(val, scal) ((uint8_t)(((scal & 0b11) << 6) | (val & 0b111111)))
/* connection modes */
#define BME680_SPI 1
#define BME680_I2C 0
/* calculation modes; int or float calc */
#define BME680_MODE_INT 2
#define BME680_MODE_FLOAT 0
/* to enable gas conversion OR this into mode byte */
#define BME680_ENABLE_GAS 4
/* config values */
#define BME680_OVERSAMPLE_X1 0b001
#define BME680_OVERSAMPLE_X2 0b010
#define BME680_OVERSAMPLE_X4 0b011
#define BME680_OVERSAMPLE_X8 0b100
#define BME680_OVERSAMPLE_X16 0b101
/* IIR filter */
#define BME680_IIR_COEFF_0 0b000
#define BME680_IIR_COEFF_1 0b001
#define BME680_IIR_COEFF_3 0b010
#define BME680_IIR_COEFF_7 0b011
#define BME680_IIR_COEFF_15 0b100
#define BME680_IIR_COEFF_31 0b101
#define BME680_IIR_COEFF_63 0b110
#define BME680_IIR_COEFF_127 0b111
/* gas related values */
#define BME680_GAS_WAIT_X1 0b00
#define BME680_GAS_WAIT_X4 0b01
#define BME680_GAS_WAIT_X16 0b10
#define BME680_GAS_WAIT_X64 0b11
/* user supplied spi/i2c functions */
struct bme680_dev {
int (*init) (void);
int (*read) (uint8_t reg, uint8_t *dst, uint32_t size);
int (*write) (uint8_t reg, uint8_t value);
int (*deinit) (void);
void (*sleep) (uint32_t period);
};
struct bme680_cal {
/* temp calibration */
uint16_t par_t1;
int16_t par_t2;
int8_t par_t3;
/* press calibration */
uint16_t par_p1;
int16_t par_p2;
int8_t par_p3;
int16_t par_p4;
int16_t par_p5;
int8_t par_p6;
int8_t par_p7;
int16_t par_p8;
int16_t par_p9;
uint8_t par_p10;
/* humidity calibration */
uint16_t par_h1;
uint16_t par_h2;
int8_t par_h3;
int8_t par_h4;
int8_t par_h5;
uint8_t par_h6;
int8_t par_h7;
/* heater + gas */
uint16_t par_g1;
uint16_t par_g2;
uint16_t par_g3;
uint16_t range_switching_error;
uint8_t res_heat_range;
int8_t res_heat_val;
};
struct bme680_config {
uint8_t osrs_t;
uint8_t osrs_p;
uint8_t osrs_h;
uint8_t filter;
uint8_t idac_heat[10];
uint8_t res_heat[10];
uint8_t gas_wait[10];
uint8_t meas; /* required because you can't read back ctrl regs */
};
struct bme680_comp_float {
double tfine;
double temp;
double press;
double hum;
double gas_res;
};
struct bme680_comp_int {
int32_t tfine;
int32_t temp;
int32_t press;
int32_t hum;
int32_t gas_res;
};
struct bme680_adc {
uint32_t temp;
uint32_t press;
uint32_t hum;
uint32_t gas;
uint32_t gas_range;
};
struct bme680 {
struct bme680_comp_float fcomp;
struct bme680_comp_int icomp;
struct bme680_cal cal;
struct bme680_dev dev;
struct bme680_config cfg;
struct bme680_adc adc;
uint8_t mode;
uint8_t setpoint;
uint8_t spi_page;
uint8_t gas_valid;
uint8_t heat_stab;
};
typedef struct bme680 bme680_t;
int bme680_init(bme680_t *bme680, uint8_t mode);
int bme680_deinit(bme680_t *bme680);
int bme680_reset(bme680_t *bme680);
int bme680_calibrate(bme680_t *bme680);
int bme680_configure(bme680_t *bme680);
int bme680_start(bme680_t *bme680);
int bme680_poll(bme680_t *bme680);
int bme680_read(bme680_t *bme680);
int bme680_write_setpoint_index(bme680_t *bme680);
int bme680_read_setpoint_index(bme680_t *bme680, uint8_t *index);
uint8_t bme680_calc_target(bme680_t *bme680, double target, double ambient);
void bme680_print_calibration(bme680_t *bme680);
#endif

83
Core/Inc/main.h Normal file
View File

@ -0,0 +1,83 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.h
* @brief : Header for main.c file.
* This file contains the common defines of the application.
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx_hal.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define B1_Pin GPIO_PIN_13
#define B1_GPIO_Port GPIOC
#define USART_TX_Pin GPIO_PIN_2
#define USART_TX_GPIO_Port GPIOA
#define USART_RX_Pin GPIO_PIN_3
#define USART_RX_GPIO_Port GPIOA
#define LD2_Pin GPIO_PIN_5
#define LD2_GPIO_Port GPIOA
#define TMS_Pin GPIO_PIN_13
#define TMS_GPIO_Port GPIOA
#define TCK_Pin GPIO_PIN_14
#define TCK_GPIO_Port GPIOA
#define SWO_Pin GPIO_PIN_3
#define SWO_GPIO_Port GPIOB
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */

70
Core/Inc/registers.h Normal file
View File

@ -0,0 +1,70 @@
#ifndef REGISTERS_H
#define REGISTERS_H
/* SPI page number 0 => 0x00 to 0x7F */
/* SPI page number 1 => 0x80 to 0xFF */
#define REG_SPI_PAGE(v) ((v > 0x7F) ? 0 : 1)
#define REG_SPI_PAGE_MAP(v) (v == 0 ? "LOW" : "HIGH")
#define REG_STATUS 0x73
#define REG_RESET 0xE0
#define REG_ID 0xD0
#define REG_CONFIG 0x75
#define REG_CTRL_MEAS 0x74
#define REG_CTRL_HUM 0x72
#define REG_CTRL_GAS_1 0x71
#define REG_CTRL_GAS_0 0x70
#define REG_GAS_WAIT_9 0x6D
#define REG_GAS_WAIT_8 0x6C
#define REG_GAS_WAIT_7 0x6B
#define REG_GAS_WAIT_6 0x6A
#define REG_GAS_WAIT_5 0x69
#define REG_GAS_WAIT_4 0x68
#define REG_GAS_WAIT_3 0x67
#define REG_GAS_WAIT_2 0x66
#define REG_GAS_WAIT_1 0x65
#define REG_GAS_WAIT_0 0x64
#define REG_RES_HEAT_9 0x63
#define REG_RES_HEAT_8 0x62
#define REG_RES_HEAT_7 0x61
#define REG_RES_HEAT_6 0x60
#define REG_RES_HEAT_5 0x5F
#define REG_RES_HEAT_4 0x5E
#define REG_RES_HEAT_3 0x5D
#define REG_RES_HEAT_2 0x5C
#define REG_RES_HEAT_1 0x5B
#define REG_RES_HEAT_0 0x5A
#define REG_IDAC_HEAT_9 0x59
#define REG_IDAC_HEAT_8 0x58
#define REG_IDAC_HEAT_7 0x57
#define REG_IDAC_HEAT_6 0x56
#define REG_IDAC_HEAT_5 0x55
#define REG_IDAC_HEAT_4 0x54
#define REG_IDAC_HEAT_3 0x53
#define REG_IDAC_HEAT_2 0x52
#define REG_IDAC_HEAT_1 0x51
#define REG_IDAC_HEAT_0 0x50
#define REG_GAS_R_LSB 0x2B
#define REG_GAS_R_MSB 0x2A
#define REG_HUM_LSB 0x26
#define REG_HUM_MSB 0x25
#define REG_TEMP_XLSB 0x24
#define REG_TEMP_LSB 0x23
#define REG_TEMP_MSB 0x22
#define REG_PRESS_XLSB 0x21
#define REG_PRESS_LSB 0x20
#define REG_PRESS_MSB 0x1F
#define REG_MEAS_STATUS 0x1D
#endif

View File

@ -0,0 +1,495 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f4xx_hal_conf_template.h
* @author MCD Application Team
* @brief HAL configuration template file.
* This file should be copied to the application folder and renamed
* to stm32f4xx_hal_conf.h.
******************************************************************************
* @attention
*
* Copyright (c) 2017 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_HAL_CONF_H
#define __STM32F4xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
/* #define HAL_CRYP_MODULE_ENABLED */
/* #define HAL_ADC_MODULE_ENABLED */
/* #define HAL_CAN_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
/* #define HAL_CAN_LEGACY_MODULE_ENABLED */
/* #define HAL_DAC_MODULE_ENABLED */
/* #define HAL_DCMI_MODULE_ENABLED */
/* #define HAL_DMA2D_MODULE_ENABLED */
/* #define HAL_ETH_MODULE_ENABLED */
/* #define HAL_ETH_LEGACY_MODULE_ENABLED */
/* #define HAL_NAND_MODULE_ENABLED */
/* #define HAL_NOR_MODULE_ENABLED */
/* #define HAL_PCCARD_MODULE_ENABLED */
/* #define HAL_SRAM_MODULE_ENABLED */
/* #define HAL_SDRAM_MODULE_ENABLED */
/* #define HAL_HASH_MODULE_ENABLED */
/* #define HAL_I2C_MODULE_ENABLED */
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
/* #define HAL_LTDC_MODULE_ENABLED */
/* #define HAL_RNG_MODULE_ENABLED */
/* #define HAL_RTC_MODULE_ENABLED */
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
/* #define HAL_MMC_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_SMBUS_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
/* #define HAL_HCD_MODULE_ENABLED */
/* #define HAL_DSI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_CEC_MODULE_ENABLED */
/* #define HAL_FMPI2C_MODULE_ENABLED */
/* #define HAL_FMPSMBUS_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */
/* #define HAL_DFSDM_MODULE_ENABLED */
/* #define HAL_LPTIM_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
/* ########################## HSE/HSI Values adaptation ##################### */
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE 32000U /*!< LSI Typical Value in Hz*/
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
The real value may vary depending on the variations
in voltage and temperature.*/
/**
* @brief External Low Speed oscillator (LSE) value.
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for I2S peripheral
* This value is used by the I2S HAL module to compute the I2S clock source
* frequency, this source is inserted directly through I2S_CKIN pad.
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External audio frequency in Hz*/
#endif /* EXTERNAL_CLOCK_VALUE */
/* 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. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE 3300U /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 1U
#define INSTRUCTION_CACHE_ENABLE 1U
#define DATA_CACHE_ENABLE 1U
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */
#define USE_HAL_FMPSMBUS_REGISTER_CALLBACKS 0U /* FMPSMBUS register callback disabled */
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## Ethernet peripheral configuration ##################### */
/* Section 1 : Ethernet peripheral configuration */
/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */
#define MAC_ADDR0 2U
#define MAC_ADDR1 0U
#define MAC_ADDR2 0U
#define MAC_ADDR3 0U
#define MAC_ADDR4 0U
#define MAC_ADDR5 0U
/* Definition of the Ethernet driver buffers size and count */
#define ETH_RX_BUF_SIZE /* buffer size for receive */
#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */
#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */
#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */
/* Section 2: PHY configuration section */
/* DP83848_PHY_ADDRESS Address*/
#define DP83848_PHY_ADDRESS
/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
#define PHY_RESET_DELAY 0x000000FFU
/* PHY Configuration delay */
#define PHY_CONFIG_DELAY 0x00000FFFU
#define PHY_READ_TO 0x0000FFFFU
#define PHY_WRITE_TO 0x0000FFFFU
/* Section 3: Common PHY Registers */
#define PHY_BCR ((uint16_t)0x0000U) /*!< Transceiver Basic Control Register */
#define PHY_BSR ((uint16_t)0x0001U) /*!< Transceiver Basic Status Register */
#define PHY_RESET ((uint16_t)0x8000U) /*!< PHY Reset */
#define PHY_LOOPBACK ((uint16_t)0x4000U) /*!< Select loop-back mode */
#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100U) /*!< Set the full-duplex mode at 100 Mb/s */
#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000U) /*!< Set the half-duplex mode at 100 Mb/s */
#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100U) /*!< Set the full-duplex mode at 10 Mb/s */
#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000U) /*!< Set the half-duplex mode at 10 Mb/s */
#define PHY_AUTONEGOTIATION ((uint16_t)0x1000U) /*!< Enable auto-negotiation function */
#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200U) /*!< Restart auto-negotiation function */
#define PHY_POWERDOWN ((uint16_t)0x0800U) /*!< Select the power down mode */
#define PHY_ISOLATE ((uint16_t)0x0400U) /*!< Isolate PHY from MII */
#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020U) /*!< Auto-Negotiation process completed */
#define PHY_LINKED_STATUS ((uint16_t)0x0004U) /*!< Valid link established */
#define PHY_JABBER_DETECTION ((uint16_t)0x0002U) /*!< Jabber condition detected */
/* Section 4: Extended PHY Registers */
#define PHY_SR ((uint16_t)) /*!< PHY status register Offset */
#define PHY_SPEED_STATUS ((uint16_t)) /*!< PHY Speed mask */
#define PHY_DUPLEX_STATUS ((uint16_t)) /*!< PHY Duplex mask */
/* ################## SPI peripheral configuration ########################## */
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/
#define USE_SPI_CRC 0U
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32f4xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32f4xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32f4xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32f4xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32f4xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32f4xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32f4xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
#include "stm32f4xx_hal_can_legacy.h"
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32f4xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32f4xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DMA2D_MODULE_ENABLED
#include "stm32f4xx_hal_dma2d.h"
#endif /* HAL_DMA2D_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32f4xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_DCMI_MODULE_ENABLED
#include "stm32f4xx_hal_dcmi.h"
#endif /* HAL_DCMI_MODULE_ENABLED */
#ifdef HAL_ETH_MODULE_ENABLED
#include "stm32f4xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
#ifdef HAL_ETH_LEGACY_MODULE_ENABLED
#include "stm32f4xx_hal_eth_legacy.h"
#endif /* HAL_ETH_LEGACY_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32f4xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32f4xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32f4xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32f4xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_PCCARD_MODULE_ENABLED
#include "stm32f4xx_hal_pccard.h"
#endif /* HAL_PCCARD_MODULE_ENABLED */
#ifdef HAL_SDRAM_MODULE_ENABLED
#include "stm32f4xx_hal_sdram.h"
#endif /* HAL_SDRAM_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32f4xx_hal_hash.h"
#endif /* HAL_HASH_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32f4xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32f4xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32f4xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32f4xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LTDC_MODULE_ENABLED
#include "stm32f4xx_hal_ltdc.h"
#endif /* HAL_LTDC_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32f4xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32f4xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32f4xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32f4xx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32f4xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f4xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32f4xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32f4xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32f4xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32f4xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32f4xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32f4xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32f4xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_DSI_MODULE_ENABLED
#include "stm32f4xx_hal_dsi.h"
#endif /* HAL_DSI_MODULE_ENABLED */
#ifdef HAL_QSPI_MODULE_ENABLED
#include "stm32f4xx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32f4xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_FMPI2C_MODULE_ENABLED
#include "stm32f4xx_hal_fmpi2c.h"
#endif /* HAL_FMPI2C_MODULE_ENABLED */
#ifdef HAL_FMPSMBUS_MODULE_ENABLED
#include "stm32f4xx_hal_fmpsmbus.h"
#endif /* HAL_FMPSMBUS_MODULE_ENABLED */
#ifdef HAL_SPDIFRX_MODULE_ENABLED
#include "stm32f4xx_hal_spdifrx.h"
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
#ifdef HAL_DFSDM_MODULE_ENABLED
#include "stm32f4xx_hal_dfsdm.h"
#endif /* HAL_DFSDM_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32f4xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32f4xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
/* 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)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F4xx_HAL_CONF_H */

66
Core/Inc/stm32f4xx_it.h Normal file
View File

@ -0,0 +1,66 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f4xx_it.h
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F4xx_IT_H
#define __STM32F4xx_IT_H
#ifdef __cplusplus
extern "C" {
#endif
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void NMI_Handler(void);
void HardFault_Handler(void);
void MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMon_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __STM32F4xx_IT_H */

642
Core/Src/bme680.c Normal file
View File

@ -0,0 +1,642 @@
#define _DEFAULT_SOURCE
#include <stdio.h>
#include <unistd.h>
#include "bme680.h"
#include "registers.h"
static void calc_temp_comp(bme680_t *bme680);
static void calc_press_comp(bme680_t *bme680);
static void calc_hum_comp(bme680_t *bme680);
static void calc_gas_res(bme680_t *bme680);
static void check_spi_page(bme680_t *bme680, uint8_t reg);
static int set_spi_page(bme680_t *bme680, uint8_t no);
/********************************************************************/
static int write_dev(bme680_t *bme680, uint8_t reg, uint8_t value) {
if (BME680_IS_SPI(bme680->mode)) {
check_spi_page(bme680, reg);
reg &= 0x7F;
}
return bme680->dev.write(reg, value);
}
/********************************************************************/
static int read_dev(bme680_t *bme680, uint8_t reg, uint8_t *dst, uint32_t size) {
if (BME680_IS_SPI(bme680->mode)) {
check_spi_page(bme680, reg);
reg |= 0x80;
}
return bme680->dev.read(reg, dst, size);
}
/********************************************************************/
/* change spi page if necessary */
static void check_spi_page(bme680_t *bme680, uint8_t reg) {
uint8_t required_page = REG_SPI_PAGE(reg);
if (required_page != bme680->spi_page) {
set_spi_page(bme680, required_page);
bme680->spi_page = required_page;
}
}
/********************************************************************/
static int set_spi_page(bme680_t *bme680, uint8_t page_no) {
uint8_t status_reg = page_no << 4;
return bme680->dev.write(REG_STATUS, status_reg);
}
/********************************************************************/
static int read_id(bme680_t *bme680, uint8_t *id) {
uint8_t id_reg;
/* force spi page 0. special case */
if (BME680_IS_SPI(bme680->mode)) {
set_spi_page(bme680, 0);
bme680->spi_page = 0;
id_reg = 0x50 | 0x80;
} else {
id_reg = REG_ID;
}
return bme680->dev.read(id_reg, id, 1);
}
/********************************************************************/
/* write local setpoint index to device, must not be running */
int bme680_write_setpoint_index(bme680_t *bme680) {
/* setpoint (0 thru 9) bits 0,1,2,3 and run_gas bit 4 */
uint8_t ctrl_gas_1 = (bme680->setpoint & 0x0F) | (1 << 4);
return write_dev(bme680, REG_CTRL_GAS_1, ctrl_gas_1);
}
/********************************************************************/
/* read the currently selected heater setpoint index on the device */
int bme680_read_setpoint_index(bme680_t *bme680, uint8_t *index) {
uint8_t meas_status;
int err = 0;
err |= read_dev(bme680, REG_MEAS_STATUS, &meas_status, 1);
*index = (meas_status) & 0x0F;
return err;
}
/********************************************************************/
int bme680_init(bme680_t *bme680, uint8_t mode) {
uint8_t id;
int i;
bme680->mode = mode;
bme680->spi_page = 0;
bme680->gas_valid = 0;
bme680->heat_stab = 0;
bme680->setpoint = 0;
if (bme680->dev.init() != 0) {
return 1;
}
if (read_id(bme680, &id) != 0) {
return 1;
}
if (id != 0x61) {
return 1;
}
/* zero gas sensor arrays */
for(i=0; i<10; i++) {
bme680->cfg.idac_heat[i] = 0;
bme680->cfg.res_heat[i] = 0;
bme680->cfg.gas_wait[i] = 0;
}
return 0;
}
/********************************************************************/
int bme680_deinit(bme680_t *bme680) {
if (bme680->dev.deinit) {
bme680->dev.deinit();
}
return 0;
}
/********************************************************************/
int bme680_reset(bme680_t *bme680) {
uint8_t magic = 0xB6;
uint8_t reg;
int ret;
/* force page 0. special case */
if (BME680_IS_SPI(bme680->mode)) {
set_spi_page(bme680, 0);
bme680->spi_page = 0;
reg = 0x60 | 0x80;
} else {
reg = REG_RESET;
}
ret = bme680->dev.write(reg, magic);
bme680->dev.sleep(2000); /* sleep for 2 ms */
return ret;
}
/********************************************************************/
/* configure device */
int bme680_configure(bme680_t *bme680) {
uint8_t meas, hum, filter, ctrl_gas1, ctrl_gas0, err;
int i;
meas = hum = filter = err = 0;
/* ctrl_meas. the last 0 is ticked on to enable forced mode,
* but the config has to be written fist. strange behaviour.
*/
meas = bme680->cfg.osrs_t << 5 | bme680->cfg.osrs_p << 2;
hum = bme680->cfg.osrs_h;
filter = bme680->cfg.filter << 2;
/* backup of ctrl meas reg because you cannot retrieve it from the device later */
bme680->cfg.meas = meas;
err |= write_dev(bme680, REG_CTRL_MEAS, meas);
err |= write_dev(bme680, REG_CTRL_HUM, hum);
err |= write_dev(bme680, REG_CONFIG, filter);
if (!BME680_GAS_ENABLED(bme680->mode)) {
goto SKIP_GAS;
}
/* write out all 10 setpoints */
/* those not explicitly set are defaulted to 0 (which has no effect) */
for(i=0; i<10; i++) {
err |= write_dev(bme680, 0x6D - i, bme680->cfg.gas_wait[9 - i]);
err |= write_dev(bme680, 0x63 - i, bme680->cfg.res_heat[9 - i]);
err |= write_dev(bme680, 0x59 - i, bme680->cfg.idac_heat[9 - i]);
}
ctrl_gas1 = bme680->setpoint | (1 << 4);
ctrl_gas0 = 0; /* := (1 << 3) to turn off current going to heater */
err |= write_dev(bme680, REG_CTRL_GAS_1, ctrl_gas1);
err |= write_dev(bme680, REG_CTRL_GAS_0, ctrl_gas0);
SKIP_GAS:
return err;
}
/********************************************************************/
/* To start forced mode, you just have to set the lsb=1 of REG_CTRL_MEAS */
int bme680_start(bme680_t *bme680) {
int err = 0;
uint8_t meas;
meas = bme680->cfg.meas | 1;
err |= write_dev(bme680, REG_CTRL_MEAS, meas);
return err;
}
/********************************************************************/
/* blocks until all scheduled conversions on the device are done. */
int bme680_poll(bme680_t *bme680) {
uint8_t meas_status = 0;
uint8_t gas_measuring = 0;
uint8_t any_measuring = 0;
int err = 0;
do {
bme680->dev.sleep(5000); /* 5 ms */
err |= read_dev(bme680, REG_MEAS_STATUS, &meas_status, 1);
gas_measuring = (meas_status >> 6) & 1;
any_measuring = (meas_status >> 5) & 1;
} while ((gas_measuring || any_measuring) && !err);
return err;
}
/********************************************************************/
/* assume start'd and poll'd */
int bme680_read(bme680_t *bme680) {
/* begin by reading ADCs */
uint8_t buffer[3] = {0, 0 ,0};
int err = 0;
err |= read_dev(bme680, 0x22, buffer, 3);
bme680->adc.temp = (buffer[0] << 12) | (buffer[1] << 4) | (buffer[2] >> 4);
err |= read_dev(bme680, 0x1F, buffer, 3);
bme680->adc.press = (buffer[0] << 12) | (buffer[1] << 4) | (buffer[2] >> 4);
err |= read_dev(bme680, 0x25, buffer, 2);
bme680->adc.hum = (buffer[0] << 8) | buffer[1];
/* adc readings are only 20-bit when the IIR filter is enabled.
* otherwise, it depends on the oversample settings.
* note: humidity is not IIR filtered, and always 16-bit.
* IIR filter on (any level) -> 20-bit
* IIR filter off -> 16 + (osrs_x - 1) bits.
* */
if (bme680->cfg.filter == BME680_IIR_COEFF_0) {
bme680->adc.temp >>= (bme680->cfg.osrs_t - 1);
bme680->adc.press >>= (bme680->cfg.osrs_p - 1);
}
/* read gas adc values and check error bits */
if (BME680_GAS_ENABLED(bme680->mode)) {
err |= read_dev(bme680, 0x2A, buffer, 2);
/* read gas-related adc values */
bme680->adc.gas = (buffer[0] << 2) | (buffer[1] >> 6);
bme680->adc.gas_range = buffer[1] & 0xF;
/* check gas validity status (if one actually took place ??? ) */
bme680->gas_valid = (buffer[1] >> 5) & 1;
/* check heater stability. if it managed to get to temp within given time + preload current */
bme680->heat_stab = (buffer[1] >> 4) & 1;
}
/* read/convert in order ..*/
calc_temp_comp(bme680);
calc_press_comp(bme680);
calc_hum_comp(bme680);
if (BME680_GAS_ENABLED(bme680->mode)) {
calc_gas_res(bme680);
}
return err;
}
/***********************************************************************/
/* These arrays are used to compute a sensor heating value `res_heat' */
/* for a specified heating target, specified in degree C. */
/***********************************************************************/
static double const_array1[16] = {
1, 1, 1, 1, 1, 0.99, 1, 0.992, 1,
1, 0.998, 0.995, 1, 0.99, 1, 1
};
static double const_array2[16] = {
8000000, 4000000, 2000000, 1000000, 499500.4995, 248262.1648,
125000, 63004.03226, 31281.28128, 15625, 7812.5, 3906.25,
1953.125, 976.5625, 488.28125, 244.140625
};
static int const_array1_int[16] = {
2147483647, 2147483647, 2147483647, 2147483647, 2147483647,
2126008810, 2147483647, 2130303777, 2147483647, 2147483647,
2143188679, 2136746228, 2147483647, 2126008810, 2147483647,
2147483647
};
static int const_array2_int[16] = {
4096000000, 2048000000, 1024000000, 512000000, 255744255,
127110228, 64000000, 32258064, 16016016, 8000000, 4000000,
2000000, 1000000, 500000, 250000, 125000
};
/********************************************************************/
/********************************************************************/
static void calc_temp_comp_1 (bme680_t *bme680) {
double var1, var2, temp_comp;
var1 = (((double)bme680->adc.temp / 16384.0) - ((double)bme680->cal.par_t1 / 1024.0)) *
(double)bme680->cal.par_t2;
var2 = ((((double)bme680->adc.temp / 131072.0) - ((double)bme680->cal.par_t1 / 8192.0)) *
(((double)bme680->adc.temp / 131072.0) - ((double)bme680->cal.par_t1 / 8192.0))) *
((double)bme680->cal.par_t3 * 16.0);
bme680->fcomp.tfine = var1 + var2;
temp_comp = (var1 + var2) / 5120.0;
bme680->fcomp.temp = temp_comp;
}
/********************************************************************/
static void calc_temp_comp_2 (bme680_t *bme680) {
int32_t var1, var2, var3, temp_comp;
var1 = ((int32_t)bme680->adc.temp >> 3) - ((int32_t) bme680->cal.par_t1 << 1);
var2 = (var1 * (int32_t)bme680->cal.par_t2) >> 11;
var3 = ((((var1 >> 1) * (var1 >> 1)) >> 12) * ((int32_t)bme680->cal.par_t3 << 4)) >> 14;
bme680->icomp.tfine = var2 + var3;
temp_comp = (((var2 + var3) * 5) + 128) >> 8;
bme680->icomp.temp = temp_comp;
}
/********************************************************************/
static void calc_temp_comp (bme680_t *bme680) {
if (BME680_IS_FLOAT(bme680->mode)) {
calc_temp_comp_1(bme680);
} else {
calc_temp_comp_2(bme680);
}
}
/********************************************************************/
static void calc_press_comp_1 (bme680_t *bme680) {
double var1, var2, var3, press_comp;
var1 = ((double)bme680->fcomp.tfine / 2.0) - 64000.0;
var2 = var1 * var1 * ((double)bme680->cal.par_p6 / 131072.0);
var2 = var2 + (var1 * (double)bme680->cal.par_p5 * 2.0);
var2 = (var2 / 4.0) + ((double)bme680->cal.par_p4 * 65536.0);
var1 = ((((double)bme680->cal.par_p3 * var1 * var1) / 16384.0) +
((double)bme680->cal.par_p2 * var1)) / 524288.0;
var1 = (1.0 + (var1 / 32768.0)) * (double)bme680->cal.par_p1;
press_comp = 1048576.0 - (double)bme680->adc.press;
press_comp = ((press_comp - (var2 / 4096.0)) * 6250.0) / var1;
var1 = ((double)bme680->cal.par_p9 * press_comp * press_comp) / 2147483648.0;
var2 = press_comp * ((double)bme680->cal.par_p8 / 32768.0);
var3 = (press_comp / 256.0) * (press_comp / 256.0) *
(press_comp / 256.0) * (bme680->cal.par_p10 / 131072.0);
press_comp = press_comp + (var1 + var2 + var3 + ((double)bme680->cal.par_p7 * 128.0)) / 16.0;
bme680->fcomp.press = press_comp;
}
/********************************************************************/
static void calc_press_comp_2 (bme680_t *bme680 ) {
int32_t var1, var2, var3, press_comp;
var1 = ((int32_t)bme680->icomp.tfine >> 1) - 64000;
var2 = ((((var1 >> 2) * (var1 >> 2)) >> 11) * (int32_t)bme680->cal.par_p6) >> 2;
var2 = var2 + ((var1 * (int32_t)bme680->cal.par_p5) << 1);
var2 = (var2 >> 2) + ((int32_t)bme680->cal.par_p4 << 16);
var1 = (((((var1 >> 2) * (var1 >> 2)) >> 13) *
((int32_t)bme680->cal.par_p3 << 5)) >> 3) + (((int32_t)bme680->cal.par_p2 * var1) >> 1);
var1 = var1 >> 18;
var1 = ((32768 + var1) * (int32_t)bme680->cal.par_p1) >> 15;
press_comp = 1048576 - bme680->adc.press; // bosch code pg 19 says "press_raw" here ???
press_comp = (uint32_t)((press_comp - (var2 >> 12)) * ((uint32_t)3125));
if (press_comp >= (1 << 30))
press_comp = ((press_comp / (uint32_t)var1) << 1);
else
press_comp = ((press_comp << 1) / (uint32_t)var1);
var1 = ((int32_t)bme680->cal.par_p9 * (int32_t)(((press_comp >> 3) *
(press_comp >> 3)) >> 13)) >> 12;
var2 = ((int32_t)(press_comp >> 2) * (int32_t)bme680->cal.par_p8) >> 13;
var3 = ((int32_t)(press_comp >> 8) * (int32_t)(press_comp >> 8) *
(int32_t)(press_comp >> 8) * (int32_t)bme680->cal.par_p10) >> 17;
press_comp = (int32_t)(press_comp) + ((var1 + var2 + var3 + ((int32_t)bme680->cal.par_p7 << 7)) >> 4);
bme680->icomp.press = press_comp;
}
/********************************************************************/
static void calc_press_comp (bme680_t *bme680) {
if (BME680_IS_FLOAT(bme680->mode)) {
calc_press_comp_1(bme680);
} else {
calc_press_comp_2(bme680);
}
}
/********************************************************************/
static void calc_hum_comp_1 (bme680_t *bme680) {
double var1, var2, var3, var4, hum_comp, temp_comp;
temp_comp = bme680->fcomp.temp;
var1 = bme680->adc.hum - (((double)bme680->cal.par_h1 * 16.0) + (((double)bme680->cal.par_h3 / 2.0) * temp_comp));
var2 = var1 * (((double)bme680->cal.par_h2 / 262144.0) * (1.0 + (((double)bme680->cal.par_h4 / 16384.0) *
temp_comp) + (((double)bme680->cal.par_h5 / 1048576.0) * temp_comp * temp_comp)));
var3 = (double)bme680->cal.par_h6 / 16384.0;
var4 = (double)bme680->cal.par_h7 / 2097152.0;
hum_comp = var2 + ((var3 + (var4 * temp_comp)) * var2 * var2);
bme680->fcomp.hum = hum_comp;
}
/********************************************************************/
static void calc_hum_comp_2 (bme680_t *bme680) {
int32_t var1, var2, var3, var4, var5, var6, temp_scaled, hum_comp;
temp_scaled = (int32_t)bme680->icomp.temp;
var1 = (int32_t)bme680->adc.hum - (int32_t)((int32_t)bme680->cal.par_h1 << 4) -
(((temp_scaled * (int32_t)bme680->cal.par_h3) / ((int32_t)100)) >> 1);
var2 = ((int32_t)bme680->cal.par_h2 * (((temp_scaled * (int32_t)bme680->cal.par_h4) / ((int32_t)100)) +
(((temp_scaled * ((temp_scaled * (int32_t)bme680->cal.par_h5) /
((int32_t)100))) >> 6) / ((int32_t)100)) + ((int32_t)(1 << 14)))) >> 10;
var3 = var1 * var2;
var4 = (((int32_t)bme680->cal.par_h6 << 7) +
((temp_scaled * (int32_t)bme680->cal.par_h7) / ((int32_t)100))) >> 4;
var5 = ((var3 >> 14) * (var3 >> 14)) >> 10;
var6 = (var4 * var5) >> 1;
hum_comp = (((var3 + var6) >> 10) * ((int32_t) 1000)) >> 12;
bme680->icomp.hum = hum_comp;
}
/********************************************************************/
static void calc_hum_comp (bme680_t *bme680) {
if (BME680_IS_FLOAT(bme680->mode)) {
calc_hum_comp_1(bme680);
} else {
calc_hum_comp_2(bme680);
}
}
/********************************************************************/
// TODO: read one big contiguous block
int bme680_calibrate(bme680_t *bme680) {
uint8_t buffer[3] = {0, 0 ,0};
int err = 0;
/* temperature */
err |= read_dev(bme680, 0xE9, buffer, 2);
bme680->cal.par_t1 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0x8A, buffer, 2);
bme680->cal.par_t2 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0x8C, buffer, 1);
bme680->cal.par_t3 = buffer[0];
/* pressure */
err |= read_dev(bme680, 0x8E, buffer, 2);
bme680->cal.par_p1 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0x90, buffer, 2);
bme680->cal.par_p2 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0x92, buffer, 1);
bme680->cal.par_p3 = buffer[0];
err |= read_dev(bme680, 0x94, buffer, 2);
bme680->cal.par_p4 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0x96, buffer, 2);
bme680->cal.par_p5 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0x99, buffer, 1);
bme680->cal.par_p6 = buffer[0];
err |= read_dev(bme680, 0x98, buffer, 1);
bme680->cal.par_p7 = buffer[0];
err |= read_dev(bme680, 0x9C, buffer, 1);
bme680->cal.par_p8 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0x9E, buffer, 2);
bme680->cal.par_p9 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0xA0, buffer, 1);
bme680->cal.par_p10 = buffer[0];
/* humidity */
err |= read_dev(bme680, 0xE2, buffer, 2);
bme680->cal.par_h1 = (buffer[1] << 4) | (buffer[0] & 0xF);
err |= read_dev(bme680, 0xE1, buffer, 2);
bme680->cal.par_h2 = (buffer[0] << 4) | ((buffer[1] >> 4) & 0xF);
err |= read_dev(bme680, 0xE4, buffer, 1);
bme680->cal.par_h3 = buffer[0];
err |= read_dev(bme680, 0xE5, buffer, 1);
bme680->cal.par_h4 = buffer[0];
err |= read_dev(bme680, 0xE6, buffer, 1);
bme680->cal.par_h5 = buffer[0];
err |= read_dev(bme680, 0xE7, buffer, 1);
bme680->cal.par_h6 = buffer[0];
err |= read_dev(bme680, 0xE8, buffer, 1);
bme680->cal.par_h7 = buffer[0];
/* gas */
err |= read_dev(bme680, 0xED, buffer, 1);
bme680->cal.par_g1 = buffer[0];
err |= read_dev(bme680, 0xEB, buffer, 2);
bme680->cal.par_g2 = (buffer[1] << 8) | buffer[0];
err |= read_dev(bme680, 0xEE, buffer, 1);
bme680->cal.par_g3 = buffer[0];
err |= read_dev(bme680, 0x04, buffer, 1);
bme680->cal.range_switching_error = buffer[0];
err |= read_dev(bme680, 0x02, buffer, 1);
bme680->cal.res_heat_range = (buffer[0] >> 4) & 0b11;
err |= read_dev(bme680, 0x00, buffer, 1);
bme680->cal.res_heat_val = buffer[0];
return err;
}
/********************************************************************/
static void calc_gas_res_1(bme680_t *bme680) {
double var1, gas_res;
var1 = (1340.0 + 5.0 * bme680->cal.range_switching_error) * const_array1[bme680->adc.gas_range];
gas_res = var1 * const_array2[bme680->adc.gas_range] / (bme680->adc.gas - 512.0 + var1);
bme680->fcomp.gas_res = gas_res;
}
/********************************************************************/
static void calc_gas_res_2(bme680_t *bme680) {
int64_t var1, var2;
int32_t gas_res;
var1 = (int64_t)(((1340 + (5 * (int64_t)bme680->cal.range_switching_error)) *
((int64_t)const_array1_int[bme680->adc.gas_range])) >> 16);
var2 = (int64_t)(bme680->adc.gas << 15) - (int64_t)(1 << 24) + var1;
gas_res = (int32_t)((((int64_t)(const_array2_int[bme680->adc.gas_range] *
(int64_t)var1) >> 9) + (var2 >> 1)) / var2);
bme680->icomp.gas_res = gas_res;
}
/********************************************************************/
static void calc_gas_res(bme680_t *bme680) {
if (BME680_IS_FLOAT(bme680->mode)) {
calc_gas_res_1(bme680);
} else {
calc_gas_res_2(bme680);
}
}
/********************************************************************/
void bme680_print_calibration (bme680_t *bme680) {
printf("par_t1: %d\n", bme680->cal.par_t1);
printf("par_t2: %d\n", bme680->cal.par_t2);
printf("par_t3: %d\n", bme680->cal.par_t3);
printf("par_p1: %d\n", bme680->cal.par_p1);
printf("par_p2: %d\n", bme680->cal.par_p2);
printf("par_p3: %d\n", bme680->cal.par_p3);
printf("par_p4: %d\n", bme680->cal.par_p4);
printf("par_p5: %d\n", bme680->cal.par_p5);
printf("par_p6: %d\n", bme680->cal.par_p6);
printf("par_p7: %d\n", bme680->cal.par_p7);
printf("par_p8: %d\n", bme680->cal.par_p8);
printf("par_p9: %d\n", bme680->cal.par_p9);
printf("par_p10: %d\n", bme680->cal.par_p10);
printf("par_h1: %d\n", bme680->cal.par_h1);
printf("par_h2: %d\n", bme680->cal.par_h2);
printf("par_h3: %d\n", bme680->cal.par_h3);
printf("par_h4: %d\n", bme680->cal.par_h4);
printf("par_h5: %d\n", bme680->cal.par_h5);
printf("par_h6: %d\n", bme680->cal.par_h6);
printf("par_h7: %d\n", bme680->cal.par_h7);
printf("par_g1: %d\n", bme680->cal.par_g1);
printf("par_g2: %d\n", bme680->cal.par_g2);
printf("par_g3: %d\n", bme680->cal.par_g3);
printf("range_switching_error: %d\n", bme680->cal.range_switching_error);
printf("res_heat_range: %d\n", bme680->cal.res_heat_range);
printf("res_heat_val: %d\n", bme680->cal.res_heat_val);
}
/********************************************************************/
static uint8_t calc_target_1(bme680_t *bme680, double target, double ambient) {
double var1, var2, var3, var4, var5;
uint8_t res_heat;
var1 = ((double)bme680->cal.par_g1 / 16.0) + 49.0;
var2 = (((double)bme680->cal.par_g2 / 32768.0) * 0.0005) + 0.00235;
var3 = (double)bme680->cal.par_g3 / 1024.0;
var4 = var1 * (1.0 + (var2 * (double)target)); /* */
var5 = var4 + (var3 * (double)ambient);
res_heat = (uint8_t)(3.4 * ((var5 * (4.0 / (4.0 + (double)bme680->cal.res_heat_range)) *
(1.0 / (1.0 + ((double)bme680->cal.res_heat_val * 0.002)))) - 25));
return res_heat;
}
/********************************************************************/
static uint8_t calc_target_2(bme680_t *bme680, double target, double ambient) {
int32_t var1, var2, var3, var4, var5, res_heat_x100;
uint8_t res_heat;
var1 = (((int32_t)ambient * bme680->cal.par_g3) / 10) << 8;
var2 = (bme680->cal.par_g1 + 784) * (((((bme680->cal.par_g2 + 154009) * target * 5) /
100) + 3276800) / 10);
var3 = var1 + (var2 >> 1);
var4 = (var3 / (bme680->cal.res_heat_range + 4));
var5 = (131 * bme680->cal.res_heat_val) + 65536;
res_heat_x100 = (int32_t)(((var4 / var5) - 250) * 34);
res_heat = (uint8_t)((res_heat_x100 + 50) / 100);
return res_heat;
}
/********************************************************************/
uint8_t bme680_calc_target(bme680_t *bme680, double target, double ambient) {
if (BME680_IS_FLOAT(bme680->mode)) {
return calc_target_1(bme680, target, ambient);
} else {
return calc_target_2(bme680, target, ambient);
}
}

593
Core/Src/main.c Normal file
View File

@ -0,0 +1,593 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "bme680.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
#define AMBIENT_TEMP_GUESS 19.0
#define HEATER_TARGET 300.0
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
SPI_HandleTypeDef hspi2;
TIM_HandleTypeDef htim6;
UART_HandleTypeDef huart2;
/* USER CODE BEGIN PV */
double gBase = 8000; // 02NOV2023 //358714.656; // 27OCT2023 avg taken from clean room
double hBase = 40.0;
double tAmbient = 25.0*100.0; // was the integer value times 100 oC ?
double humidityScore;
double hWeight = 0.5;
double iaqPercent;
double iaqScore;
double eCO2Value;
double calc_air_q (double hRead, double tRead, double gRes)
{
double humidityScore = 0;
double gasScore = 0;
double humidityOffset = hRead - hBase; // Calculate the humidity offset from the baseline setting
double ambTemp = (tAmbient / 100);
double temperatureOffset = tRead - ambTemp; // Calculate the temperature offset from the ambient temperature
double humidityRatio = ((humidityOffset / hBase) + 1);
double temperatureRatio = (temperatureOffset / ambTemp);
// IAQ Calculations
if (humidityOffset > 0) { // Different paths for calculating the humidity score depending on whether the offset is greater than 0
humidityScore = (100 - hRead) / (100 - hBase);
}
else {
humidityScore = hRead / hBase;
}
humidityScore = humidityScore * hWeight * 100;
double gasRatio = (gRes / gBase);
if ( gasRatio > 1.0 ) {
asm("nop");
// problem the gas resistance should not be this high. This mean the
// gBase is too low!
gBase = gRes;
gasRatio = (gRes / gBase); // heuristic for now learning how this works
}
if ((gBase - gRes) > 0) { // Different paths for calculating the gas score depending on whether the offset is greater than 0
gasScore = gasRatio * (100 * (1 - hWeight));
}
else {
// Make sure that when the gas offset and humidityOffset are 0, iaqPercent is 95% - leaves room for cleaner air to be identified
gasScore = (double)((int)((70 + (5 * (gasRatio - 1))+0.5)));
if (gasScore > 75) {
gasScore = 75;
}
}
iaqPercent = (humidityScore + gasScore); // Air quality percentage is the sum of the humidity (25% weighting) and gas (75% weighting) scores
iaqScore = (100 - iaqPercent) * 5 ; // Final air quality score is in range 0 - 500 (see BME688 datasheet page 11 for details)
// eCO2 Calculations
//eCO2Value = 250 * pow(2.718 /*Math.E*/, (0.012 * iaqScore)); // Exponential curve equation to calculate the eCO2 from an iaqScore input
// Adjust eCO2Value for humidity and/or temperature greater than the baseline values
// if (humidityOffset > 0) {
// if (temperatureOffset > 0) {
// eCO2Value = eCO2Value * (humidityRatio + temperatureRatio);
// }
// else {
// eCO2Value = eCO2Value * humidityRatio;
// }
//}
// else if (temperatureOffset > 0) {
// eCO2Value = eCO2Value * (temperatureRatio + 1);
//}
//
// If measurements are taking place rapidly, breath detection is possible due to the sudden increase in humidity (~7-10%)
// If this increase happens within a 5s time window, 1200ppm is added to the eCO2 value
// (These values were based on 'breath-testing' with another eCO2 sensor with algorithms built-in)
//if ((measTime - measTimePrev) <= 5000) {
// if ((hRead - hPrev) >= 3) {
// eCO2Value = eCO2Value + 1500;
// }
//}
// eCO2Value = Math.trunc(eCO2Value);
if (iaqScore < 0)
asm ("nop");
return iaqScore;
}
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_USART2_UART_Init(void);
static void MX_SPI2_Init(void);
static void MX_TIM6_Init(void);
/* USER CODE BEGIN PFP */
// Assumes TIMER6 is set to count every 1uS and that it wraps around (or counts up to 65535)
// and that it counts UP.
void delay_micro_seconds(uint32_t period) {
int16_t a,then,now = *&htim6.Instance->CNT;
asm(" nop");
do {
then = *&htim6.Instance->CNT;
}
while ( (a=(then - now)) < period ); // hows about all that then.
asm(" nop");
}
int BME680init() { return 0; }
int BME680deinit() { return 0; }
int BME680_read_spi(uint8_t reg, uint8_t *dst, uint32_t size){
uint8_t Tx[2];
Tx[0] = reg | 0x80;
Tx[1] = 0;
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_3, GPIO_PIN_RESET); // NSS low
//HAL_SPI_TransmitReceive(&hspi2, Tx, dst, size, 1000); // timeout 1000msec;
HAL_SPI_Transmit(&hspi2, &reg, 1, 1000);
HAL_SPI_Receive(&hspi2, dst, size, 1000);
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_3, GPIO_PIN_SET); // NSS high
return 0;
}
int BME680_write_spi(uint8_t reg, uint8_t value)
{
int8_t Tx[2],Rx[2];
int32_t hal_status;
Tx[0] = reg & 0x7F;
Tx[1] = value;
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_3, GPIO_PIN_RESET); // NSS low
hal_status = HAL_SPI_Transmit(&hspi2, Tx, 2, 1000);
while(&hspi2.State == HAL_SPI_STATE_BUSY); // wait for xmission complete
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_3, GPIO_PIN_SET); // NSS high
return 0;
}
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void)
{
/* USER CODE BEGIN 1 */
bme680_t bme680;
uint8_t mode;
int i;
int error = 0;
/* USER CODE END 1 */
/* MCU Configuration--------------------------------------------------------*/
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
HAL_Init();
/* USER CODE BEGIN Init */
/* USER CODE END Init */
/* Configure the system clock */
SystemClock_Config();
/* USER CODE BEGIN SysInit */
/* USER CODE END SysInit */
/* Initialize all configured peripherals */
MX_GPIO_Init();
MX_USART2_UART_Init();
MX_SPI2_Init();
MX_TIM6_Init();
/* USER CODE BEGIN 2 */
// start TIM6 used for sleeping
HAL_TIM_Base_Start(&htim6);
bme680.dev.init = BME680init;
bme680.dev.read = BME680_read_spi;
bme680.dev.write = BME680_write_spi;
bme680.dev.deinit = BME680deinit;
bme680.dev.sleep = delay_micro_seconds;
/* 2. set the device mode */
mode = BME680_MODE_FLOAT | BME680_SPI | BME680_ENABLE_GAS;
/* BME680_MODE_INT | BME680_I2C; */
/* 3. initialise dev func's, and check device id */
if (bme680_init(&bme680, mode) != 0) {
asm("nop");
error = 1;
}
/* 4. reset device */
bme680_reset(&bme680);
/* 5. read calibration parameters from the device and store in memory */
if (bme680_calibrate(&bme680) != 0) {
bme680_deinit(&bme680);
asm("nop");
error = 2;
}
/* debug */
bme680_print_calibration(&bme680);
/* 6. set up device config */
bme680.cfg.osrs_t = BME680_OVERSAMPLE_X16;
bme680.cfg.osrs_p = BME680_OVERSAMPLE_X16;
bme680.cfg.osrs_h = BME680_OVERSAMPLE_X8;
bme680.cfg.filter = BME680_IIR_COEFF_127;
/* configuring gas sensor. */
/* NB: mode |= BME680_ENABLE_GAS; */
/* there are 10 possible heater setpoints */
/* they can be thought of as frames that define one single gas-resistance measurement */
/* they do not carry over or affect each other in any way. */
for(i=0; i<10; i++) {
/* calculate a resistance target, based on desired temp, and ambient temp */
bme680.cfg.res_heat[i] = bme680_calc_target(&bme680, HEATER_TARGET, AMBIENT_TEMP_GUESS);
/* initial heating current for the setpoint. Could be useful in cold places or short gas_wait durations */
/* 7-bit word. Each step/lsb is equiv. to 1/8 mA; so max 16 mA */
/* a value of 20 would be equal to 2.5 mA */
/* this s.p. field is allowed to be left as 0 if no preload is required. */
bme680.cfg.idac_heat[i] = BME680_IDAC(100);
/* define the time between the start of heating and start of resistance sensing in this s.p.*/
/* Bosch datasheet suggests ~30 - 40ms is usually all that is required to get up to temp. */
/* ^ probably with a good idac_heat current but doesn't mention it. */
/* 25 * X4 = 100 ms wait before sampling resistance starts. */
/* the first value is 6-bit (0...63) with 1 ms step size. */
bme680.cfg.gas_wait[i] = BME680_GAS_WAIT(25, BME680_GAS_WAIT_X4);
}
/* The BME680 does not cycle between setpoints. They have to be manually set. */
/* After each "run", the setpoint has to be changed. */
/* the func bme680_write_setpoint_index() will write this field to the dev, without having to reconfigure */
bme680.setpoint = 0; /* 0 thru 9 */
/* 7. write config to device */
if (bme680_configure(&bme680) != 0) {
bme680_deinit(&bme680);
error = 3;
}
int counter = 0;
/* USER CODE END 2 */
/* Infinite loop */
/* USER CODE BEGIN WHILE */
while (1)
{
/* USER CODE END WHILE */
/* 8. Start forced measurement*. After it finishes, it should remember the previous config. */
/* * = bosch speak for one single T, P, H, GasRes measuring cycle. */
if (bme680_start(&bme680) != 0) {
error = 4;
bme680_deinit(&bme680);
}
/* 9. poll the meas_status register until all scheduled conversions are done */
/* this step can be skipped with SPI interrupt (3 wire SPI only. See 5.3.1.1 in datasheet; pg 29) */
if (bme680_poll(&bme680) != 0) {
error = 5;
bme680_deinit(&bme680);
}
/* 10. read the ADC's and perform a conversion */
if (bme680_read(&bme680) != 0) {
error = 6;
bme680_deinit(&bme680);
}
double airq = calc_air_q(bme680.fcomp.hum, bme680.fcomp.temp, bme680.fcomp.gas_res);
if (counter++ > 100) {
counter = 0;
asm("nop");
}
/* USER CODE BEGIN 3 */
}
/* USER CODE END 3 */
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void)
{
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
/** Configure the main internal regulator output voltage
*/
__HAL_RCC_PWR_CLK_ENABLE();
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE3);
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLM = 16;
RCC_OscInitStruct.PLL.PLLN = 336;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4;
RCC_OscInitStruct.PLL.PLLQ = 2;
RCC_OscInitStruct.PLL.PLLR = 2;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief SPI2 Initialization Function
* @param None
* @retval None
*/
static void MX_SPI2_Init(void)
{
/* USER CODE BEGIN SPI2_Init 0 */
/* USER CODE END SPI2_Init 0 */
/* USER CODE BEGIN SPI2_Init 1 */
/* USER CODE END SPI2_Init 1 */
/* SPI2 parameter configuration*/
hspi2.Instance = SPI2;
hspi2.Init.Mode = SPI_MODE_MASTER;
hspi2.Init.Direction = SPI_DIRECTION_2LINES;
hspi2.Init.DataSize = SPI_DATASIZE_8BIT;
hspi2.Init.CLKPolarity = SPI_POLARITY_LOW;
hspi2.Init.CLKPhase = SPI_PHASE_1EDGE;
hspi2.Init.NSS = SPI_NSS_SOFT;
hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
hspi2.Init.CRCPolynomial = 10;
if (HAL_SPI_Init(&hspi2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN SPI2_Init 2 */
/* USER CODE END SPI2_Init 2 */
}
/**
* @brief TIM6 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM6_Init(void)
{
/* USER CODE BEGIN TIM6_Init 0 */
/* USER CODE END TIM6_Init 0 */
TIM_MasterConfigTypeDef sMasterConfig = {0};
/* USER CODE BEGIN TIM6_Init 1 */
/* USER CODE END TIM6_Init 1 */
htim6.Instance = TIM6;
htim6.Init.Prescaler = 84-1;
htim6.Init.CounterMode = TIM_COUNTERMODE_UP;
htim6.Init.Period = 65535;
htim6.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim6) != HAL_OK)
{
Error_Handler();
}
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
if (HAL_TIMEx_MasterConfigSynchronization(&htim6, &sMasterConfig) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM6_Init 2 */
/* USER CODE END TIM6_Init 2 */
}
/**
* @brief USART2 Initialization Function
* @param None
* @retval None
*/
static void MX_USART2_UART_Init(void)
{
/* USER CODE BEGIN USART2_Init 0 */
/* USER CODE END USART2_Init 0 */
/* USER CODE BEGIN USART2_Init 1 */
/* USER CODE END USART2_Init 1 */
huart2.Instance = USART2;
huart2.Init.BaudRate = 115200;
huart2.Init.WordLength = UART_WORDLENGTH_8B;
huart2.Init.StopBits = UART_STOPBITS_1;
huart2.Init.Parity = UART_PARITY_NONE;
huart2.Init.Mode = UART_MODE_TX_RX;
huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart2.Init.OverSampling = UART_OVERSAMPLING_16;
if (HAL_UART_Init(&huart2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN USART2_Init 2 */
/* USER CODE END USART2_Init 2 */
}
/**
* @brief GPIO Initialization Function
* @param None
* @retval None
*/
static void MX_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
/* USER CODE BEGIN MX_GPIO_Init_1 */
/* USER CODE END MX_GPIO_Init_1 */
/* GPIO Ports Clock Enable */
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOH_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_3, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(LD2_GPIO_Port, LD2_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin : B1_Pin */
GPIO_InitStruct.Pin = B1_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(B1_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pin : PC3 */
GPIO_InitStruct.Pin = GPIO_PIN_3;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/*Configure GPIO pin : LD2_Pin */
GPIO_InitStruct.Pin = LD2_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(LD2_GPIO_Port, &GPIO_InitStruct);
/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}
/* USER CODE BEGIN 4 */
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void)
{
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state */
__disable_irq();
while (1)
{
}
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t *file, uint32_t line)
{
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line number,
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

View File

@ -0,0 +1,277 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f4xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN Define */
/* USER CODE END Define */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN Macro */
/* USER CODE END Macro */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* External functions --------------------------------------------------------*/
/* USER CODE BEGIN ExternalFunctions */
/* USER CODE END ExternalFunctions */
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_0);
/* System interrupt init*/
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
/**
* @brief SPI MSP Initialization
* This function configures the hardware resources used in this example
* @param hspi: SPI handle pointer
* @retval None
*/
void HAL_SPI_MspInit(SPI_HandleTypeDef* hspi)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hspi->Instance==SPI2)
{
/* USER CODE BEGIN SPI2_MspInit 0 */
/* USER CODE END SPI2_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_SPI2_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**SPI2 GPIO Configuration
PC1 ------> SPI2_MOSI
PC2 ------> SPI2_MISO
PB10 ------> SPI2_SCK
*/
GPIO_InitStruct.Pin = GPIO_PIN_1;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_SPI2;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_2;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN SPI2_MspInit 1 */
/* USER CODE END SPI2_MspInit 1 */
}
}
/**
* @brief SPI MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hspi: SPI handle pointer
* @retval None
*/
void HAL_SPI_MspDeInit(SPI_HandleTypeDef* hspi)
{
if(hspi->Instance==SPI2)
{
/* USER CODE BEGIN SPI2_MspDeInit 0 */
/* USER CODE END SPI2_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_SPI2_CLK_DISABLE();
/**SPI2 GPIO Configuration
PC1 ------> SPI2_MOSI
PC2 ------> SPI2_MISO
PB10 ------> SPI2_SCK
*/
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_1|GPIO_PIN_2);
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_10);
/* USER CODE BEGIN SPI2_MspDeInit 1 */
/* USER CODE END SPI2_MspDeInit 1 */
}
}
/**
* @brief TIM_Base MSP Initialization
* This function configures the hardware resources used in this example
* @param htim_base: TIM_Base handle pointer
* @retval None
*/
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base)
{
if(htim_base->Instance==TIM6)
{
/* USER CODE BEGIN TIM6_MspInit 0 */
/* USER CODE END TIM6_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM6_CLK_ENABLE();
/* USER CODE BEGIN TIM6_MspInit 1 */
/* USER CODE END TIM6_MspInit 1 */
}
}
/**
* @brief TIM_Base MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param htim_base: TIM_Base handle pointer
* @retval None
*/
void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base)
{
if(htim_base->Instance==TIM6)
{
/* USER CODE BEGIN TIM6_MspDeInit 0 */
/* USER CODE END TIM6_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM6_CLK_DISABLE();
/* USER CODE BEGIN TIM6_MspDeInit 1 */
/* USER CODE END TIM6_MspDeInit 1 */
}
}
/**
* @brief UART MSP Initialization
* This function configures the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspInit(UART_HandleTypeDef* huart)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(huart->Instance==USART2)
{
/* USER CODE BEGIN USART2_MspInit 0 */
/* USER CODE END USART2_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_USART2_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**USART2 GPIO Configuration
PA2 ------> USART2_TX
PA3 ------> USART2_RX
*/
GPIO_InitStruct.Pin = USART_TX_Pin|USART_RX_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF7_USART2;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USER CODE BEGIN USART2_MspInit 1 */
/* USER CODE END USART2_MspInit 1 */
}
}
/**
* @brief UART MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
{
if(huart->Instance==USART2)
{
/* USER CODE BEGIN USART2_MspDeInit 0 */
/* USER CODE END USART2_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_USART2_CLK_DISABLE();
/**USART2 GPIO Configuration
PA2 ------> USART2_TX
PA3 ------> USART2_RX
*/
HAL_GPIO_DeInit(GPIOA, USART_TX_Pin|USART_RX_Pin);
/* USER CODE BEGIN USART2_MspDeInit 1 */
/* USER CODE END USART2_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

203
Core/Src/stm32f4xx_it.c Normal file
View File

@ -0,0 +1,203 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32f4xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32f4xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/******************************************************************************/
/* Cortex-M4 Processor Interruption and Exception Handlers */
/******************************************************************************/
/**
* @brief This function handles Non maskable interrupt.
*/
void NMI_Handler(void)
{
/* USER CODE BEGIN NonMaskableInt_IRQn 0 */
/* USER CODE END NonMaskableInt_IRQn 0 */
/* USER CODE BEGIN NonMaskableInt_IRQn 1 */
while (1)
{
}
/* USER CODE END NonMaskableInt_IRQn 1 */
}
/**
* @brief This function handles Hard fault interrupt.
*/
void HardFault_Handler(void)
{
/* USER CODE BEGIN HardFault_IRQn 0 */
/* USER CODE END HardFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_HardFault_IRQn 0 */
/* USER CODE END W1_HardFault_IRQn 0 */
}
}
/**
* @brief This function handles Memory management fault.
*/
void MemManage_Handler(void)
{
/* USER CODE BEGIN MemoryManagement_IRQn 0 */
/* USER CODE END MemoryManagement_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
/* USER CODE END W1_MemoryManagement_IRQn 0 */
}
}
/**
* @brief This function handles Pre-fetch fault, memory access fault.
*/
void BusFault_Handler(void)
{
/* USER CODE BEGIN BusFault_IRQn 0 */
/* USER CODE END BusFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_BusFault_IRQn 0 */
/* USER CODE END W1_BusFault_IRQn 0 */
}
}
/**
* @brief This function handles Undefined instruction or illegal state.
*/
void UsageFault_Handler(void)
{
/* USER CODE BEGIN UsageFault_IRQn 0 */
/* USER CODE END UsageFault_IRQn 0 */
while (1)
{
/* USER CODE BEGIN W1_UsageFault_IRQn 0 */
/* USER CODE END W1_UsageFault_IRQn 0 */
}
}
/**
* @brief This function handles System service call via SWI instruction.
*/
void SVC_Handler(void)
{
/* USER CODE BEGIN SVCall_IRQn 0 */
/* USER CODE END SVCall_IRQn 0 */
/* USER CODE BEGIN SVCall_IRQn 1 */
/* USER CODE END SVCall_IRQn 1 */
}
/**
* @brief This function handles Debug monitor.
*/
void DebugMon_Handler(void)
{
/* USER CODE BEGIN DebugMonitor_IRQn 0 */
/* USER CODE END DebugMonitor_IRQn 0 */
/* USER CODE BEGIN DebugMonitor_IRQn 1 */
/* USER CODE END DebugMonitor_IRQn 1 */
}
/**
* @brief This function handles Pendable request for system service.
*/
void PendSV_Handler(void)
{
/* USER CODE BEGIN PendSV_IRQn 0 */
/* USER CODE END PendSV_IRQn 0 */
/* USER CODE BEGIN PendSV_IRQn 1 */
/* USER CODE END PendSV_IRQn 1 */
}
/**
* @brief This function handles System tick timer.
*/
void SysTick_Handler(void)
{
/* USER CODE BEGIN SysTick_IRQn 0 */
/* USER CODE END SysTick_IRQn 0 */
HAL_IncTick();
/* USER CODE BEGIN SysTick_IRQn 1 */
/* USER CODE END SysTick_IRQn 1 */
}
/******************************************************************************/
/* STM32F4xx Peripheral Interrupt Handlers */
/* Add here the Interrupt Handlers for the used peripherals. */
/* For the available peripheral interrupt handler names, */
/* please refer to the startup file (startup_stm32f4xx.s). */
/******************************************************************************/
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

176
Core/Src/syscalls.c Normal file
View File

@ -0,0 +1,176 @@
/**
******************************************************************************
* @file syscalls.c
* @author Auto-generated by STM32CubeIDE
* @brief STM32CubeIDE Minimal System calls file
*
* For more information about which c-functions
* need which of these lowlevel functions
* please consult the Newlib libc-manual
******************************************************************************
* @attention
*
* Copyright (c) 2020-2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* Includes */
#include <sys/stat.h>
#include <stdlib.h>
#include <errno.h>
#include <stdio.h>
#include <signal.h>
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>
/* Variables */
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));
char *__env[1] = { 0 };
char **environ = __env;
/* Functions */
void initialise_monitor_handles()
{
}
int _getpid(void)
{
return 1;
}
int _kill(int pid, int sig)
{
(void)pid;
(void)sig;
errno = EINVAL;
return -1;
}
void _exit (int status)
{
_kill(status, -1);
while (1) {} /* Make sure we hang here */
}
__attribute__((weak)) int _read(int file, char *ptr, int len)
{
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len)
{
(void)file;
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
}
int _close(int file)
{
(void)file;
return -1;
}
int _fstat(int file, struct stat *st)
{
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file)
{
(void)file;
return 1;
}
int _lseek(int file, int ptr, int dir)
{
(void)file;
(void)ptr;
(void)dir;
return 0;
}
int _open(char *path, int flags, ...)
{
(void)path;
(void)flags;
/* Pretend like we always fail */
return -1;
}
int _wait(int *status)
{
(void)status;
errno = ECHILD;
return -1;
}
int _unlink(char *name)
{
(void)name;
errno = ENOENT;
return -1;
}
int _times(struct tms *buf)
{
(void)buf;
return -1;
}
int _stat(char *file, struct stat *st)
{
(void)file;
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new)
{
(void)old;
(void)new;
errno = EMLINK;
return -1;
}
int _fork(void)
{
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env)
{
(void)name;
(void)argv;
(void)env;
errno = ENOMEM;
return -1;
}

79
Core/Src/sysmem.c Normal file
View File

@ -0,0 +1,79 @@
/**
******************************************************************************
* @file sysmem.c
* @author Generated by STM32CubeIDE
* @brief STM32CubeIDE System Memory calls file
*
* For more information about which C functions
* need which of these lowlevel functions
* please consult the newlib libc manual
******************************************************************************
* @attention
*
* Copyright (c) 2023 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* Includes */
#include <errno.h>
#include <stdint.h>
/**
* Pointer to the current high watermark of the heap usage
*/
static uint8_t *__sbrk_heap_end = NULL;
/**
* @brief _sbrk() allocates memory to the newlib heap and is used by malloc
* and others from the C library
*
* @verbatim
* ############################################################################
* # .data # .bss # newlib heap # MSP stack #
* # # # # Reserved by _Min_Stack_Size #
* ############################################################################
* ^-- RAM start ^-- _end _estack, RAM end --^
* @endverbatim
*
* This implementation starts allocating at the '_end' linker symbol
* The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack
* The implementation considers '_estack' linker symbol to be RAM end
* NOTE: If the MSP stack, at any point during execution, grows larger than the
* reserved size, please increase the '_Min_Stack_Size'.
*
* @param incr Memory size
* @return Pointer to allocated memory
*/
void *_sbrk(ptrdiff_t incr)
{
extern uint8_t _end; /* Symbol defined in the linker script */
extern uint8_t _estack; /* Symbol defined in the linker script */
extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */
const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size;
const uint8_t *max_heap = (uint8_t *)stack_limit;
uint8_t *prev_heap_end;
/* Initialize heap end at first call */
if (NULL == __sbrk_heap_end)
{
__sbrk_heap_end = &_end;
}
/* Protect heap from growing into the reserved MSP stack */
if (__sbrk_heap_end + incr > max_heap)
{
errno = ENOMEM;
return (void *)-1;
}
prev_heap_end = __sbrk_heap_end;
__sbrk_heap_end += incr;
return (void *)prev_heap_end;
}

747
Core/Src/system_stm32f4xx.c Normal file
View File

@ -0,0 +1,747 @@
/**
******************************************************************************
* @file system_stm32f4xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M4 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_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.
*
*
******************************************************************************
* @attention
*
* Copyright (c) 2017 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f4xx_system
* @{
*/
/** @addtogroup STM32F4xx_System_Private_Includes
* @{
*/
#include "stm32f4xx.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 STM32F4xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_Defines
* @{
*/
/************************* Miscellaneous Configuration ************************/
/*!< Uncomment the following line if you need to use external SRAM or SDRAM as data memory */
#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx)\
|| defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|| defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx)
/* #define DATA_IN_ExtSRAM */
#endif /* STM32F40xxx || STM32F41xxx || STM32F42xxx || STM32F43xxx || STM32F469xx || STM32F479xx ||\
STM32F412Zx || STM32F412Vx */
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|| defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
/* #define DATA_IN_ExtSDRAM */
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\
STM32F479xx */
/* Note: Following vector table addresses must be defined in line with linker
configuration. */
/*!< Uncomment the following line if you need to relocate the vector table
anywhere in Flash or Sram, else the vector table is kept at the automatic
remap of boot address selected */
/* #define USER_VECT_TAB_ADDRESS */
#if defined(USER_VECT_TAB_ADDRESS)
/*!< Uncomment the following line if you need to relocate your vector Table
in Sram else user remap will be done in Flash. */
/* #define VECT_TAB_SRAM */
#if defined(VECT_TAB_SRAM)
#define VECT_TAB_BASE_ADDRESS SRAM_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#else
#define VECT_TAB_BASE_ADDRESS FLASH_BASE /*!< Vector Table base address field.
This value must be a multiple of 0x200. */
#define VECT_TAB_OFFSET 0x00000000U /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
#endif /* VECT_TAB_SRAM */
#endif /* USER_VECT_TAB_ADDRESS */
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_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 STM32F4xx_System_Private_FunctionPrototypes
* @{
*/
#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 FPU setting, vector table location and External memory
* configuration.
* @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
#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
SystemInit_ExtMemCtl();
#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
/* Configure the Vector Table location -------------------------------------*/
#if defined(USER_VECT_TAB_ADDRESS)
SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
#endif /* USER_VECT_TAB_ADDRESS */
}
/**
* @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_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 stm32f4xx_hal_conf.h file (its value
* depends on the application requirements), 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;
}
#if defined (DATA_IN_ExtSRAM) && defined (DATA_IN_ExtSDRAM)
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|| defined(STM32F469xx) || defined(STM32F479xx)
/**
* @brief Setup the external memory controller.
* Called in startup_stm32f4xx.s before jump to main.
* This function configures the external memories (SRAM/SDRAM)
* This SRAM/SDRAM will be used as program data memory (including heap and stack).
* @param None
* @retval None
*/
void SystemInit_ExtMemCtl(void)
{
__IO uint32_t tmp = 0x00;
register uint32_t tmpreg = 0, timeout = 0xFFFF;
register __IO uint32_t index;
/* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface clock */
RCC->AHB1ENR |= 0x000001F8;
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);
/* Connect PDx pins to FMC Alternate function */
GPIOD->AFR[0] = 0x00CCC0CC;
GPIOD->AFR[1] = 0xCCCCCCCC;
/* Configure PDx pins in Alternate function mode */
GPIOD->MODER = 0xAAAA0A8A;
/* Configure PDx pins speed to 100 MHz */
GPIOD->OSPEEDR = 0xFFFF0FCF;
/* 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] = 0xC00CC0CC;
GPIOE->AFR[1] = 0xCCCCCCCC;
/* Configure PEx pins in Alternate function mode */
GPIOE->MODER = 0xAAAA828A;
/* Configure PEx pins speed to 100 MHz */
GPIOE->OSPEEDR = 0xFFFFC3CF;
/* 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;
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
FMC_Bank5_6->SDCR[0] = 0x000019E4;
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;
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
timeout = 0xFFFF;
while((tmpreg != 0) && (timeout-- > 0))
{
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
}
/* Auto refresh command */
FMC_Bank5_6->SDCMR = 0x00000073;
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
timeout = 0xFFFF;
while((tmpreg != 0) && (timeout-- > 0))
{
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
}
/* MRD register program */
FMC_Bank5_6->SDCMR = 0x00046014;
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
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);
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)
/* Configure and enable Bank1_SRAM2 */
FMC_Bank1->BTCR[2] = 0x00001011;
FMC_Bank1->BTCR[3] = 0x00000201;
FMC_Bank1E->BWTR[2] = 0x0fffffff;
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */
#if defined(STM32F469xx) || defined(STM32F479xx)
/* Configure and enable Bank1_SRAM2 */
FMC_Bank1->BTCR[2] = 0x00001091;
FMC_Bank1->BTCR[3] = 0x00110212;
FMC_Bank1E->BWTR[2] = 0x0fffffff;
#endif /* STM32F469xx || STM32F479xx */
(void)(tmp);
}
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */
#elif defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
/**
* @brief Setup the external memory controller.
* Called in startup_stm32f4xx.s before jump to main.
* This function configures the external memories (SRAM/SDRAM)
* This SRAM/SDRAM will be used as program data memory (including heap and stack).
* @param None
* @retval None
*/
void SystemInit_ExtMemCtl(void)
{
__IO uint32_t tmp = 0x00;
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|| defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx)
#if defined (DATA_IN_ExtSDRAM)
register uint32_t tmpreg = 0, timeout = 0xFFFF;
register __IO uint32_t index;
#if defined(STM32F446xx)
/* Enable GPIOA, GPIOC, GPIOD, GPIOE, GPIOF, GPIOG interface
clock */
RCC->AHB1ENR |= 0x0000007D;
#else
/* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
clock */
RCC->AHB1ENR |= 0x000001F8;
#endif /* STM32F446xx */
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);
#if defined(STM32F446xx)
/* Connect PAx pins to FMC Alternate function */
GPIOA->AFR[0] |= 0xC0000000;
GPIOA->AFR[1] |= 0x00000000;
/* Configure PDx pins in Alternate function mode */
GPIOA->MODER |= 0x00008000;
/* Configure PDx pins speed to 50 MHz */
GPIOA->OSPEEDR |= 0x00008000;
/* Configure PDx pins Output type to push-pull */
GPIOA->OTYPER |= 0x00000000;
/* No pull-up, pull-down for PDx pins */
GPIOA->PUPDR |= 0x00000000;
/* Connect PCx pins to FMC Alternate function */
GPIOC->AFR[0] |= 0x00CC0000;
GPIOC->AFR[1] |= 0x00000000;
/* Configure PDx pins in Alternate function mode */
GPIOC->MODER |= 0x00000A00;
/* Configure PDx pins speed to 50 MHz */
GPIOC->OSPEEDR |= 0x00000A00;
/* Configure PDx pins Output type to push-pull */
GPIOC->OTYPER |= 0x00000000;
/* No pull-up, pull-down for PDx pins */
GPIOC->PUPDR |= 0x00000000;
#endif /* STM32F446xx */
/* 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;
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|| defined(STM32F469xx) || defined(STM32F479xx)
/* 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;
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */
/*-- FMC Configuration -------------------------------------------------------*/
/* Enable the FMC interface clock */
RCC->AHB3ENR |= 0x00000001;
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
/* Configure and enable SDRAM bank1 */
#if defined(STM32F446xx)
FMC_Bank5_6->SDCR[0] = 0x00001954;
#else
FMC_Bank5_6->SDCR[0] = 0x000019E4;
#endif /* STM32F446xx */
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;
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
timeout = 0xFFFF;
while((tmpreg != 0) && (timeout-- > 0))
{
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
}
/* Auto refresh command */
#if defined(STM32F446xx)
FMC_Bank5_6->SDCMR = 0x000000F3;
#else
FMC_Bank5_6->SDCMR = 0x00000073;
#endif /* STM32F446xx */
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
timeout = 0xFFFF;
while((tmpreg != 0) && (timeout-- > 0))
{
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
}
/* MRD register program */
#if defined(STM32F446xx)
FMC_Bank5_6->SDCMR = 0x00044014;
#else
FMC_Bank5_6->SDCMR = 0x00046014;
#endif /* STM32F446xx */
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
timeout = 0xFFFF;
while((tmpreg != 0) && (timeout-- > 0))
{
tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
}
/* Set refresh count */
tmpreg = FMC_Bank5_6->SDRTR;
#if defined(STM32F446xx)
FMC_Bank5_6->SDRTR = (tmpreg | (0x0000050C<<1));
#else
FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
#endif /* STM32F446xx */
/* Disable write protection */
tmpreg = FMC_Bank5_6->SDCR[0];
FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
#endif /* DATA_IN_ExtSDRAM */
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */
#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx)\
|| defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)\
|| defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx)
#if defined(DATA_IN_ExtSRAM)
/*-- GPIOs Configuration -----------------------------------------------------*/
/* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
RCC->AHB1ENR |= 0x00000078;
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);
/* Connect PDx pins to FMC Alternate function */
GPIOD->AFR[0] = 0x00CCC0CC;
GPIOD->AFR[1] = 0xCCCCCCCC;
/* Configure PDx pins in Alternate function mode */
GPIOD->MODER = 0xAAAA0A8A;
/* Configure PDx pins speed to 100 MHz */
GPIOD->OSPEEDR = 0xFFFF0FCF;
/* 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] = 0xC00CC0CC;
GPIOE->AFR[1] = 0xCCCCCCCC;
/* Configure PEx pins in Alternate function mode */
GPIOE->MODER = 0xAAAA828A;
/* Configure PEx pins speed to 100 MHz */
GPIOE->OSPEEDR = 0xFFFFC3CF;
/* 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 = 0x00085AAA;
/* Configure PGx pins speed to 100 MHz */
GPIOG->OSPEEDR = 0x000CAFFF;
/* Configure PGx pins Output type to push-pull */
GPIOG->OTYPER = 0x00000000;
/* No pull-up, pull-down for PGx pins */
GPIOG->PUPDR = 0x00000000;
/*-- FMC/FSMC Configuration --------------------------------------------------*/
/* Enable the FMC/FSMC interface clock */
RCC->AHB3ENR |= 0x00000001;
#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx)
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
/* Configure and enable Bank1_SRAM2 */
FMC_Bank1->BTCR[2] = 0x00001011;
FMC_Bank1->BTCR[3] = 0x00000201;
FMC_Bank1E->BWTR[2] = 0x0fffffff;
#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */
#if defined(STM32F469xx) || defined(STM32F479xx)
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);
/* Configure and enable Bank1_SRAM2 */
FMC_Bank1->BTCR[2] = 0x00001091;
FMC_Bank1->BTCR[3] = 0x00110212;
FMC_Bank1E->BWTR[2] = 0x0fffffff;
#endif /* STM32F469xx || STM32F479xx */
#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx)\
|| defined(STM32F412Zx) || defined(STM32F412Vx)
/* Delay after an RCC peripheral clock enabling */
tmp = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);
/* Configure and enable Bank1_SRAM2 */
FSMC_Bank1->BTCR[2] = 0x00001011;
FSMC_Bank1->BTCR[3] = 0x00000201;
FSMC_Bank1E->BWTR[2] = 0x0FFFFFFF;
#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx */
#endif /* DATA_IN_ExtSRAM */
#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\
STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx */
(void)(tmp);
}
#endif /* DATA_IN_ExtSRAM && DATA_IN_ExtSDRAM */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/

View File

@ -0,0 +1,535 @@
/**
******************************************************************************
* @file startup_stm32f446xx.s
* @author MCD Application Team
* @brief STM32F446xx Devices vector table for GCC based toolchains.
* 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-M4 processor is in Thread mode,
* priority is Privileged, and the Stack is set to Main.
******************************************************************************
* @attention
*
* Copyright (c) 2017 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
.syntax unified
.cpu cortex-m4
.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:
ldr sp, =_estack /* set stack pointer */
/* Copy the data segment initializers from flash to SRAM */
ldr r0, =_sdata
ldr r1, =_edata
ldr r2, =_sidata
movs r3, #0
b LoopCopyDataInit
CopyDataInit:
ldr r4, [r2, r3]
str r4, [r0, r3]
adds r3, r3, #4
LoopCopyDataInit:
adds r4, r0, r3
cmp r4, r1
bcc CopyDataInit
/* Zero fill the bss segment. */
ldr r2, =_sbss
ldr r4, =_ebss
movs r3, #0
b LoopFillZerobss
FillZerobss:
str r3, [r2]
adds r2, r2, #4
LoopFillZerobss:
cmp r2, r4
bcc FillZerobss
/* Call the clock system initialization function.*/
bl SystemInit
/* Call static constructors */
bl __libc_init_array
/* 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 FMC_IRQHandler /* FMC */
.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 0 /* Reserved */
.word 0 /* Reserved */
.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 0 /* Reserved */
.word 0 /* Reserved */
.word FPU_IRQHandler /* FPU */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word SPI4_IRQHandler /* SPI4 */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word SAI1_IRQHandler /* SAI1 */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word SAI2_IRQHandler /* SAI2 */
.word QUADSPI_IRQHandler /* QuadSPI */
.word CEC_IRQHandler /* CEC */
.word SPDIF_RX_IRQHandler /* SPDIF RX */
.word FMPI2C1_EV_IRQHandler /* FMPI2C 1 Event */
.word FMPI2C1_ER_IRQHandler /* FMPI2C 1 Error */
/*******************************************************************************
*
* 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 FMC_IRQHandler
.thumb_set FMC_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 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 FPU_IRQHandler
.thumb_set FPU_IRQHandler,Default_Handler
.weak SPI4_IRQHandler
.thumb_set SPI4_IRQHandler,Default_Handler
.weak SAI1_IRQHandler
.thumb_set SAI1_IRQHandler,Default_Handler
.weak SAI2_IRQHandler
.thumb_set SAI2_IRQHandler,Default_Handler
.weak QUADSPI_IRQHandler
.thumb_set QUADSPI_IRQHandler,Default_Handler
.weak CEC_IRQHandler
.thumb_set CEC_IRQHandler,Default_Handler
.weak SPDIF_RX_IRQHandler
.thumb_set SPDIF_RX_IRQHandler,Default_Handler
.weak FMPI2C1_EV_IRQHandler
.thumb_set FMPI2C1_EV_IRQHandler,Default_Handler
.weak FMPI2C1_ER_IRQHandler
.thumb_set FMPI2C1_ER_IRQHandler,Default_Handler

94
Debug/makefile Normal file
View File

@ -0,0 +1,94 @@
################################################################################
# Automatically-generated file. Do not edit!
# Toolchain: GNU Tools for STM32 (11.3.rel1)
################################################################################
-include ../makefile.init
RM := rm -rf
# All of the sources participating in the build are defined here
-include sources.mk
-include Drivers/STM32F4xx_HAL_Driver/Src/subdir.mk
-include Core/Startup/subdir.mk
-include Core/Src/subdir.mk
-include objects.mk
ifneq ($(MAKECMDGOALS),clean)
ifneq ($(strip $(S_DEPS)),)
-include $(S_DEPS)
endif
ifneq ($(strip $(S_UPPER_DEPS)),)
-include $(S_UPPER_DEPS)
endif
ifneq ($(strip $(C_DEPS)),)
-include $(C_DEPS)
endif
endif
-include ../makefile.defs
OPTIONAL_TOOL_DEPS := \
$(wildcard ../makefile.defs) \
$(wildcard ../makefile.init) \
$(wildcard ../makefile.targets) \
BUILD_ARTIFACT_NAME := william_bme680
BUILD_ARTIFACT_EXTENSION := elf
BUILD_ARTIFACT_PREFIX :=
BUILD_ARTIFACT := $(BUILD_ARTIFACT_PREFIX)$(BUILD_ARTIFACT_NAME)$(if $(BUILD_ARTIFACT_EXTENSION),.$(BUILD_ARTIFACT_EXTENSION),)
# Add inputs and outputs from these tool invocations to the build variables
EXECUTABLES += \
william_bme680.elf \
MAP_FILES += \
william_bme680.map \
SIZE_OUTPUT += \
default.size.stdout \
OBJDUMP_LIST += \
william_bme680.list \
# All Target
all: main-build
# Main-build Target
main-build: william_bme680.elf secondary-outputs
# Tool invocations
william_bme680.elf william_bme680.map: $(OBJS) $(USER_OBJS) /Users/robin/STM32CubeIDE/workspace_1.12.1/william_bme680/STM32F446RETX_FLASH.ld makefile objects.list $(OPTIONAL_TOOL_DEPS)
arm-none-eabi-gcc -o "william_bme680.elf" @"objects.list" $(USER_OBJS) $(LIBS) -mcpu=cortex-m4 -T"/Users/robin/STM32CubeIDE/workspace_1.12.1/william_bme680/STM32F446RETX_FLASH.ld" --specs=nosys.specs -Wl,-Map="william_bme680.map" -Wl,--gc-sections -static --specs=nano.specs -mfpu=fpv4-sp-d16 -mfloat-abi=hard -mthumb -Wl,--start-group -lc -lm -Wl,--end-group
@echo 'Finished building target: $@'
@echo ' '
default.size.stdout: $(EXECUTABLES) makefile objects.list $(OPTIONAL_TOOL_DEPS)
arm-none-eabi-size $(EXECUTABLES)
@echo 'Finished building: $@'
@echo ' '
william_bme680.list: $(EXECUTABLES) makefile objects.list $(OPTIONAL_TOOL_DEPS)
arm-none-eabi-objdump -h -S $(EXECUTABLES) > "william_bme680.list"
@echo 'Finished building: $@'
@echo ' '
# Other Targets
clean:
-$(RM) default.size.stdout william_bme680.elf william_bme680.list william_bme680.map
-@echo ' '
secondary-outputs: $(SIZE_OUTPUT) $(OBJDUMP_LIST)
fail-specified-linker-script-missing:
@echo 'Error: Cannot find the specified linker script. Check the linker settings in the build configuration.'
@exit 2
warn-no-linker-script-specified:
@echo 'Warning: No linker script specified. Check the linker settings in the build configuration.'
.PHONY: all clean dependents main-build fail-specified-linker-script-missing warn-no-linker-script-specified
-include ../makefile.targets

3
README.md Normal file
View File

@ -0,0 +1,3 @@
# bme680_stm32f446

185
STM32F446RETX_FLASH.ld Normal file
View File

@ -0,0 +1,185 @@
/*
******************************************************************************
**
** @file : LinkerScript.ld
**
** @author : Auto-generated by STM32CubeIDE
**
** Abstract : Linker script for NUCLEO-F446RE Board embedding STM32F446RETx Device from stm32f4 series
** 512KBytes FLASH
** 128KBytes RAM
**
** Set heap size, stack size and stack location according
** to application requirements.
**
** Set memory bank area and size if external memory is used
**
** Target : STMicroelectronics STM32
**
** Distribution: The file is distributed as is, without any warranty
** of any kind.
**
******************************************************************************
** @attention
**
** Copyright (c) 2023 STMicroelectronics.
** All rights reserved.
**
** This software is licensed under terms that can be found in the LICENSE file
** in the root directory of this software component.
** If no LICENSE file comes with this software, it is provided AS-IS.
**
******************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
_Min_Heap_Size = 0x200; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Memories definition */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 512K
}
/* Sections */
SECTIONS
{
/* The startup code into "FLASH" Rom type memory */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data into "FLASH" Rom type memory */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data into "FLASH" Rom type memory */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab : {
. = ALIGN(4);
*(.ARM.extab* .gnu.linkonce.armextab.*)
. = ALIGN(4);
} >FLASH
.ARM : {
. = ALIGN(4);
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
. = ALIGN(4);
} >FLASH
.preinit_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
} >FLASH
.init_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
} >FLASH
.fini_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
. = ALIGN(4);
} >FLASH
/* Used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections into "RAM" Ram type memory */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
*(.RamFunc) /* .RamFunc sections */
*(.RamFunc*) /* .RamFunc* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section into "RAM" Ram type memory */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
._user_heap_stack :
{
. = ALIGN(8);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(8);
} >RAM
/* Remove information from the compiler libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

185
STM32F446RETX_RAM.ld Normal file
View File

@ -0,0 +1,185 @@
/*
******************************************************************************
**
** @file : LinkerScript.ld (debug in RAM dedicated)
**
** @author : Auto-generated by STM32CubeIDE
**
** Abstract : Linker script for NUCLEO-F446RE Board embedding STM32F446RETx Device from stm32f4 series
** 512KBytes FLASH
** 128KBytes RAM
**
** Set heap size, stack size and stack location according
** to application requirements.
**
** Set memory bank area and size if external memory is used
**
** Target : STMicroelectronics STM32
**
** Distribution: The file is distributed as is, without any warranty
** of any kind.
**
******************************************************************************
** @attention
**
** Copyright (c) 2023 STMicroelectronics.
** All rights reserved.
**
** This software is licensed under terms that can be found in the LICENSE file
** in the root directory of this software component.
** If no LICENSE file comes with this software, it is provided AS-IS.
**
******************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
_Min_Heap_Size = 0x200; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Memories definition */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 512K
}
/* Sections */
SECTIONS
{
/* The startup code into "RAM" Ram type memory */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >RAM
/* The program code and other data into "RAM" Ram type memory */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
*(.RamFunc) /* .RamFunc sections */
*(.RamFunc*) /* .RamFunc* sections */
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >RAM
/* Constant data into "RAM" Ram type memory */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >RAM
.ARM.extab : {
. = ALIGN(4);
*(.ARM.extab* .gnu.linkonce.armextab.*)
. = ALIGN(4);
} >RAM
.ARM : {
. = ALIGN(4);
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
. = ALIGN(4);
} >RAM
.preinit_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
} >RAM
.init_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
} >RAM
.fini_array :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
. = ALIGN(4);
} >RAM
/* Used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections into "RAM" Ram type memory */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM
/* Uninitialized data section into "RAM" Ram type memory */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
._user_heap_stack :
{
. = ALIGN(8);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(8);
} >RAM
/* Remove information from the compiler libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View File

@ -0,0 +1,83 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<launchConfiguration type="com.st.stm32cube.ide.mcu.debug.launch.launchConfigurationType">
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.access_port_id" value="0"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.cubeprog_external_loaders" value="[]"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_certif_path" value=""/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_check_enable" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_key_path" value=""/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.debug_auth_permission" value="debug_non_secure_L3"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_live_expr" value="true"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.enable_swv" value="false"/>
<intAttribute key="com.st.stm32cube.ide.mcu.debug.launch.formatVersion" value="2"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.ip_address_local" value="localhost"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.limit_swo_clock.enabled" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.limit_swo_clock.value" value=""/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.loadList" value="{&quot;fItems&quot;:[{&quot;fIsFromMainTab&quot;:true,&quot;fPath&quot;:&quot;Debug/william_bme680.elf&quot;,&quot;fProjectName&quot;:&quot;william_bme680&quot;,&quot;fPerformBuild&quot;:true,&quot;fDownload&quot;:true,&quot;fLoadSymbols&quot;:true}]}"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.override_start_address_mode" value="default"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.remoteCommand" value="target remote"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startServer" value="true"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.divby0" value="true"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.exception.unaligned" value="false"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.startuptab.haltonexception" value="true"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swd_mode" value="true"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_port" value="61235"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.swv_trace_hclk" value="84000000"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.useRemoteTarget" value="true"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.launch.vector_table" value=""/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.launch.verify_flash_download" value="true"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_allow_halt" value="false"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.cti_signal_halt" value="false"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_logging" value="false"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_max_halt_delay" value="false"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.enable_shared_stlink" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.frequency" value="0"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.halt_all_on_reset" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.log_file" value="/Users/robin/STM32CubeIDE/workspace_1.12.1/william_bme680/Debug/st-link_gdbserver_log.txt"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.low_power_debug" value="enable"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.max_halt_delay" value="2"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.reset_strategy" value="connect_under_reset"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_check_serial_number" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.stlink_txt_serial_number" value=""/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlink.watchdog_config" value="none"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.debug.stlinkenable_rtos" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.debug.stlinkrestart_configurations" value="{&quot;fVersion&quot;:1,&quot;fItems&quot;:[{&quot;fDisplayName&quot;:&quot;Reset&quot;,&quot;fIsSuppressible&quot;:false,&quot;fResetAttribute&quot;:&quot;Software system reset&quot;,&quot;fResetStrategies&quot;:[{&quot;fDisplayName&quot;:&quot;Software system reset&quot;,&quot;fLaunchAttribute&quot;:&quot;system_reset&quot;,&quot;fGdbCommands&quot;:[&quot;monitor reset\n&quot;],&quot;fCmdOptions&quot;:[&quot;-g&quot;]},{&quot;fDisplayName&quot;:&quot;Hardware reset&quot;,&quot;fLaunchAttribute&quot;:&quot;hardware_reset&quot;,&quot;fGdbCommands&quot;:[&quot;monitor reset hardware\n&quot;],&quot;fCmdOptions&quot;:[&quot;-g&quot;]},{&quot;fDisplayName&quot;:&quot;Core reset&quot;,&quot;fLaunchAttribute&quot;:&quot;core_reset&quot;,&quot;fGdbCommands&quot;:[&quot;monitor reset core\n&quot;],&quot;fCmdOptions&quot;:[&quot;-g&quot;]},{&quot;fDisplayName&quot;:&quot;None&quot;,&quot;fLaunchAttribute&quot;:&quot;no_reset&quot;,&quot;fGdbCommands&quot;:[],&quot;fCmdOptions&quot;:[&quot;-g&quot;]}],&quot;fGdbCommandGroup&quot;:{&quot;name&quot;:&quot;Additional commands&quot;,&quot;commands&quot;:[]},&quot;fStartApplication&quot;:true}]}"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.enableRtosProxy" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyCustomProperties" value=""/>
<stringAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyDriver" value="threadx"/>
<booleanAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyDriverAuto" value="false"/>
<stringAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyDriverPort" value="cortex_m0"/>
<intAttribute key="com.st.stm32cube.ide.mcu.rtosproxy.rtosProxyPort" value="60000"/>
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doHalt" value="false"/>
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.doReset" value="false"/>
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.initCommands" value=""/>
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.ipAddress" value="localhost"/>
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.jtagDeviceId" value="com.st.stm32cube.ide.mcu.debug.stlink"/>
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.pcRegister" value=""/>
<intAttribute key="org.eclipse.cdt.debug.gdbjtag.core.portNumber" value="61234"/>
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.runCommands" value=""/>
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setPcRegister" value="false"/>
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setResume" value="true"/>
<booleanAttribute key="org.eclipse.cdt.debug.gdbjtag.core.setStopAt" value="true"/>
<stringAttribute key="org.eclipse.cdt.debug.gdbjtag.core.stopAt" value="main"/>
<stringAttribute key="org.eclipse.cdt.dsf.gdb.DEBUG_NAME" value="arm-none-eabi-gdb"/>
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.NON_STOP" value="false"/>
<booleanAttribute key="org.eclipse.cdt.dsf.gdb.UPDATE_THREADLIST_ON_SUSPEND" value="false"/>
<intAttribute key="org.eclipse.cdt.launch.ATTR_BUILD_BEFORE_LAUNCH_ATTR" value="2"/>
<stringAttribute key="org.eclipse.cdt.launch.COREFILE_PATH" value=""/>
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_START_MODE" value="remote"/>
<booleanAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN" value="true"/>
<stringAttribute key="org.eclipse.cdt.launch.DEBUGGER_STOP_AT_MAIN_SYMBOL" value="main"/>
<stringAttribute key="org.eclipse.cdt.launch.PROGRAM_NAME" value="Debug/william_bme680.elf"/>
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_ATTR" value="william_bme680"/>
<booleanAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_AUTO_ATTR" value="true"/>
<stringAttribute key="org.eclipse.cdt.launch.PROJECT_BUILD_CONFIG_ID_ATTR" value="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.602378783"/>
<booleanAttribute key="org.eclipse.debug.core.ATTR_FORCE_SYSTEM_CONSOLE_ENCODING" value="false"/>
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_PATHS">
<listEntry value="/william_bme680"/>
</listAttribute>
<listAttribute key="org.eclipse.debug.core.MAPPED_RESOURCE_TYPES">
<listEntry value="4"/>
</listAttribute>
<stringAttribute key="org.eclipse.dsf.launch.MEMORY_BLOCKS" value="&lt;?xml version=&quot;1.0&quot; encoding=&quot;UTF-8&quot; standalone=&quot;no&quot;?&gt;&lt;memoryBlockExpressionList context=&quot;reserved-for-future-use&quot;/&gt;"/>
<stringAttribute key="process_factory_id" value="com.st.stm32cube.ide.mcu.debug.launch.HardwareDebugProcessFactory"/>
</launchConfiguration>

204
william_bme680.ioc Normal file
View File

@ -0,0 +1,204 @@
#MicroXplorer Configuration settings - do not modify
CAD.formats=
CAD.pinconfig=
CAD.provider=
File.Version=6
KeepUserPlacement=false
Mcu.CPN=STM32F446RET6
Mcu.Family=STM32F4
Mcu.IP0=NVIC
Mcu.IP1=RCC
Mcu.IP2=SPI2
Mcu.IP3=SYS
Mcu.IP4=TIM6
Mcu.IP5=USART2
Mcu.IPNb=6
Mcu.Name=STM32F446R(C-E)Tx
Mcu.Package=LQFP64
Mcu.Pin0=PC13
Mcu.Pin1=PC14-OSC32_IN
Mcu.Pin10=PA5
Mcu.Pin11=PB10
Mcu.Pin12=PA13
Mcu.Pin13=PA14
Mcu.Pin14=PB3
Mcu.Pin15=VP_SYS_VS_Systick
Mcu.Pin16=VP_TIM6_VS_ClockSourceINT
Mcu.Pin2=PC15-OSC32_OUT
Mcu.Pin3=PH0-OSC_IN
Mcu.Pin4=PH1-OSC_OUT
Mcu.Pin5=PC1
Mcu.Pin6=PC2
Mcu.Pin7=PC3
Mcu.Pin8=PA2
Mcu.Pin9=PA3
Mcu.PinsNb=17
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F446RETx
MxCube.Version=6.9.0
MxDb.Version=DB.6.0.90
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_0
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.SysTick_IRQn=true\:0\:0\:true\:false\:true\:true\:true\:false
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
PA13.GPIOParameters=GPIO_Label
PA13.GPIO_Label=TMS
PA13.Locked=true
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.GPIOParameters=GPIO_Label
PA14.GPIO_Label=TCK
PA14.Locked=true
PA14.Mode=Serial_Wire
PA14.Signal=SYS_JTCK-SWCLK
PA2.GPIOParameters=GPIO_Label
PA2.GPIO_Label=USART_TX
PA2.Locked=true
PA2.Mode=Asynchronous
PA2.Signal=USART2_TX
PA3.GPIOParameters=GPIO_Label
PA3.GPIO_Label=USART_RX
PA3.Locked=true
PA3.Mode=Asynchronous
PA3.Signal=USART2_RX
PA5.GPIOParameters=GPIO_Label
PA5.GPIO_Label=LD2 [Green Led]
PA5.Locked=true
PA5.Signal=GPIO_Output
PB10.Mode=Full_Duplex_Master
PB10.Signal=SPI2_SCK
PB3.GPIOParameters=GPIO_Label
PB3.GPIO_Label=SWO
PB3.Locked=true
PB3.Signal=SYS_JTDO-SWO
PC1.Mode=Full_Duplex_Master
PC1.Signal=SPI2_MOSI
PC13.GPIOParameters=GPIO_Label,GPIO_ModeDefaultEXTI
PC13.GPIO_Label=B1 [Blue PushButton]
PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_FALLING
PC13.Locked=true
PC13.Signal=GPXTI13
PC14-OSC32_IN.Locked=true
PC14-OSC32_IN.Mode=LSE-External-Oscillator
PC14-OSC32_IN.Signal=RCC_OSC32_IN
PC15-OSC32_OUT.Locked=true
PC15-OSC32_OUT.Mode=LSE-External-Oscillator
PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
PC2.Mode=Full_Duplex_Master
PC2.Signal=SPI2_MISO
PC3.Locked=true
PC3.Signal=GPIO_Output
PH0-OSC_IN.Locked=true
PH0-OSC_IN.Mode=HSE-External-Oscillator
PH0-OSC_IN.Signal=RCC_OSC_IN
PH1-OSC_OUT.Locked=true
PH1-OSC_OUT.Mode=HSE-External-Oscillator
PH1-OSC_OUT.Signal=RCC_OSC_OUT
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=false
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F446RETx
ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.27.1
ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=william_bme680.ioc
ProjectManager.ProjectName=william_bme680
ProjectManager.ProjectStructure=
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=STM32CubeIDE
ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=true
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_USART2_UART_Init-USART2-false-HAL-true,4-MX_SPI2_Init-SPI2-false-HAL-true
RCC.48MHZClocksFreq_Value=84000000
RCC.AHBFreq_Value=84000000
RCC.APB1CLKDivider=RCC_HCLK_DIV2
RCC.APB1Freq_Value=42000000
RCC.APB1TimFreq_Value=84000000
RCC.APB2Freq_Value=84000000
RCC.APB2TimFreq_Value=84000000
RCC.CECFreq_Value=32786.88524590164
RCC.CortexFreq_Value=84000000
RCC.EthernetFreq_Value=84000000
RCC.FCLKCortexFreq_Value=84000000
RCC.FLatency-AdvancedSettings=FLASH_LATENCY_2
RCC.FMPI2C1Freq_Value=42000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=84000000
RCC.HSE_VALUE=8000000
RCC.HSI_VALUE=16000000
RCC.I2SClocksFreq_Value=96000000
RCC.IPParameters=48MHZClocksFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CECFreq_Value,CortexFreq_Value,EthernetFreq_Value,FCLKCortexFreq_Value,FLatency-AdvancedSettings,FMPI2C1Freq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2SClocksFreq_Value,LSI_VALUE,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLI2SPCLKFreq_Value,PLLI2SQCLKFreq_Value,PLLI2SRCLKFreq_Value,PLLN,PLLP,PLLQCLKFreq_Value,PLLRCLKFreq_Value,PLLSAIPCLKFreq_Value,PLLSAIQCLKFreq_Value,PWRFreq_Value,RTCFreq_Value,RTCHSEDivFreq_Value,SAIAFreq_Value,SAIBFreq_Value,SDIOFreq_Value,SPDIFRXFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,USBFreq_Value,VCOI2SInputFreq_Value,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOInputMFreq_Value,VCOOutputFreq_Value,VCOSAIInputFreq_Value,VCOSAIOutputFreq_Value,VcooutputI2S
RCC.LSI_VALUE=32000
RCC.MCO2PinFreq_Value=84000000
RCC.PLLCLKFreq_Value=84000000
RCC.PLLI2SPCLKFreq_Value=96000000
RCC.PLLI2SQCLKFreq_Value=96000000
RCC.PLLI2SRCLKFreq_Value=96000000
RCC.PLLN=336
RCC.PLLP=RCC_PLLP_DIV4
RCC.PLLQCLKFreq_Value=168000000
RCC.PLLRCLKFreq_Value=168000000
RCC.PLLSAIPCLKFreq_Value=96000000
RCC.PLLSAIQCLKFreq_Value=96000000
RCC.PWRFreq_Value=84000000
RCC.RTCFreq_Value=32000
RCC.RTCHSEDivFreq_Value=4000000
RCC.SAIAFreq_Value=96000000
RCC.SAIBFreq_Value=96000000
RCC.SDIOFreq_Value=168000000
RCC.SPDIFRXFreq_Value=168000000
RCC.SYSCLKFreq_VALUE=84000000
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.USBFreq_Value=168000000
RCC.VCOI2SInputFreq_Value=1000000
RCC.VCOI2SOutputFreq_Value=192000000
RCC.VCOInputFreq_Value=1000000
RCC.VCOInputMFreq_Value=1000000
RCC.VCOOutputFreq_Value=336000000
RCC.VCOSAIInputFreq_Value=1000000
RCC.VCOSAIOutputFreq_Value=192000000
RCC.VcooutputI2S=96000000
SH.GPXTI13.0=GPIO_EXTI13
SH.GPXTI13.ConfNb=1
SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_16
SPI2.CalculateBaudRate=2.625 MBits/s
SPI2.Direction=SPI_DIRECTION_2LINES
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler
SPI2.Mode=SPI_MODE_MASTER
SPI2.VirtualType=VM_MASTER
TIM6.IPParameters=Prescaler
TIM6.Prescaler=84-1
USART2.IPParameters=VirtualMode
USART2.VirtualMode=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
VP_TIM6_VS_ClockSourceINT.Mode=Enable_Timer
VP_TIM6_VS_ClockSourceINT.Signal=TIM6_VS_ClockSourceINT
board=NUCLEO-F446RE
boardIOC=true
isbadioc=false