Added new stm32nucleo-spirit1 platform

This commit is contained in:
Marco Grella 2015-07-24 16:30:10 +02:00
parent d87f6f67e2
commit 86f35536a4
254 changed files with 173555 additions and 0 deletions

View file

@ -0,0 +1,233 @@
/**
******************************************************************************
* @file spirit1_appli.h
* @author System Lab - NOIDA
* @version V1.1.0
* @date 14-Aug-2014
* @brief Header for spirit1_appli.c module
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SPIRIT1_APPLI_H
#define __SPIRIT1_APPLI_H
/* Includes ------------------------------------------------------------------*/
#include "stm32l1xx_hal.h"
#include "radio_shield_config.h"
#include "MCU_Interface.h"
#include "SPIRIT_Config.h"
#include "stm32l1xx_nucleo.h"
/* Exported macro ------------------------------------------------------------*/
#if defined(X_NUCLEO_IDS01A3)
#define USE_SPIRIT1_433MHz
#elif defined(X_NUCLEO_IDS01A4)
#define USE_SPIRIT1_868MHz
#elif defined(X_NUCLEO_IDS01A5)
#define USE_SPIRIT1_915MHz
#else
#error SPIRIT1 Nucleo Shield undefined or unsupported
#endif
/* Uncomment the Link Layer features to be used */
// #define USE_AUTO_ACK
// #define USE_AUTO_ACK_PIGGYBACKING
// #define USE_AUTO_RETRANSMISSION
#if defined(USE_AUTO_ACK)&& defined(USE_AUTO_ACK_PIGGYBACKING)&& defined(USE_AUTO_RETRANSMISSION)
#define USE_STack_PROTOCOL
/* LLP configuration parameters */
#define EN_AUTOACK S_ENABLE
#define EN_PIGGYBACKING S_ENABLE
#define MAX_RETRANSMISSIONS PKT_N_RETX_2
#else
#define USE_BASIC_PROTOCOL
#endif
/* Uncomment the system Operating mode */
//#define USE_LOW_POWER_MODE
#if defined (USE_LOW_POWER_MODE)
#define LPM_ENABLE
#define MCU_STOP_MODE
//#define MCU_SLEEP_MODE
//#define RF_STANDBY
#endif
/* Exported constants --------------------------------------------------------*/
/* Radio configuration parameters */
#define XTAL_OFFSET_PPM 0
#define INFINITE_TIMEOUT 0.0
#ifdef USE_SPIRIT1_433MHz
#define BASE_FREQUENCY 433.0e6
#endif
#ifdef USE_SPIRIT1_868MHz
#define BASE_FREQUENCY 868.0e6
#endif
#ifdef USE_SPIRIT1_915MHz
//#define BASE_FREQUENCY 915.0e6
#define BASE_FREQUENCY 902.0e6
#endif
/* Addresses configuration parameters */
#define EN_FILT_MY_ADDRESS S_DISABLE
#define MY_ADDRESS 0x34
#define EN_FILT_MULTICAST_ADDRESS S_DISABLE
#define MULTICAST_ADDRESS 0xEE
#define EN_FILT_BROADCAST_ADDRESS S_DISABLE
#define BROADCAST_ADDRESS 0xFF
#define DESTINATION_ADDRESS 0x44
#define EN_FILT_SOURCE_ADDRESS S_DISABLE
#define SOURCE_ADDR_MASK 0xf0
#define SOURCE_ADDR_REF 0x37
#define APPLI_CMD 0x11
#define NWK_CMD 0x22
#define LED_TOGGLE 0xff
#define ACK_OK 0x01
#define MAX_BUFFER_LEN 96
#define TIME_TO_EXIT_RX 3000
#define DELAY_RX_LED_TOGGLE 200
#define DELAY_TX_LED_GLOW 1000
#define LPM_WAKEUP_TIME 100
#define DATA_SEND_TIME 30
#define PREAMBLE_LENGTH PKT_PREAMBLE_LENGTH_04BYTES
#define SYNC_LENGTH PKT_SYNC_LENGTH_4BYTES
#define CONTROL_LENGTH PKT_CONTROL_LENGTH_0BYTES
#define EN_ADDRESS S_DISABLE
#define EN_FEC S_DISABLE
#define CHANNEL_NUMBER 0
#define LENGTH_TYPE PKT_LENGTH_VAR
#define POWER_INDEX 7
#define RECEIVE_TIMEOUT 2000.0 /*change the value for required timeout period*/
#define RSSI_THRESHOLD -120
#define POWER_DBM 11.6
#define CHANNEL_SPACE 100e3
#define FREQ_DEVIATION 127e3
#define BANDWIDTH 540.0e3
#define MODULATION_SELECT GFSK_BT1
#define DATARATE 250000
#define XTAL_OFFSET_PPM 0
#define SYNC_WORD 0x88888888
#define LENGTH_WIDTH 8
#define CRC_MODE PKT_CRC_MODE_16BITS_2
#define EN_WHITENING S_DISABLE
#define INFINITE_TIMEOUT 0.0
/* Exported types ------------------------------------------------------------*/
//extern LPTIM_HandleTypeDef LptimHandle;
extern volatile FlagStatus xRxDoneFlag, xTxDoneFlag;
extern volatile FlagStatus PushButtonStatusWakeup;
extern uint16_t wakeupCounter;
extern uint16_t dataSendCounter ;
extern volatile FlagStatus PushButtonStatusData, datasendFlag;
typedef struct sRadioDriver
{
void ( *Init )( void );
void ( *GpioIrq )( SGpioInit *pGpioIRQ );
void ( *RadioInit )( SRadioInit *pRadioInit );
void ( *SetRadioPower )( uint8_t cIndex, float fPowerdBm );
void ( *PacketConfig )( void );
void ( *SetPayloadLen )( uint8_t length);
void ( *SetDestinationAddress )( uint8_t address);
void ( *EnableTxIrq )( void );
void ( *EnableRxIrq )( void );
void ( *DisableIrq )(void);
void ( *SetRxTimeout )( float cRxTimeout );
void ( *EnableSQI )(void);
void ( *SetRssiThreshold)(int dbmValue);
void ( *ClearIrqStatus )(void);
void ( *StartRx )( void );
void ( *StartTx )( uint8_t *buffer, uint8_t size );
void ( *GetRxPacket )( uint8_t *buffer, uint8_t size );
}RadioDriver_t;
typedef struct sMCULowPowerMode
{
void ( *McuStopMode )( void );
void ( *McuStandbyMode )( void );
void ( *McuSleepMode )( void );
}MCULowPowerMode_t;
typedef struct sRadioLowPowerMode
{
void ( *RadioShutDown )( void );
void ( *RadioStandBy )( void );
void ( *RadioSleep ) ( void );
void ( *RadioPowerON )( void );
}RadioLowPowerMode_t;
typedef struct
{
uint8_t Cmdtag;
uint8_t CmdType;
uint8_t CmdLen;
uint8_t Cmd;
uint8_t DataLen;
uint8_t* DataBuff;
}AppliFrame_t;
/* Exported functions ------------------------------------------------------- */
void HAL_Spirit1_Init(void);
void Enter_LP_mode(void);
void Exit_LP_mode(void);
void MCU_Enter_StopMode(void);
void MCU_Enter_StandbyMode(void);
void MCU_Enter_SleepMode(void);
void RadioPowerON(void);
void RadioPowerOFF(void);
void RadioStandBy(void);
void RadioSleep(void);
void SPIRIT1_Init(void);
void BasicProtocolInit(void);
void Set_KeyStatus(FlagStatus val);
#endif /* __SPIRIT1_APPLI_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,87 @@
/**
******************************************************************************
* @file stm32cube_hal_init.h
* @author MCD Application Team
* @version V1.0.0
* @date 18-February-2014
* @brief This file contains all the functions prototypes for the
* stm32cube_hal_init.c file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32CUBE_HAL_INIT_H
#define __STM32CUBE_HAL_INIT_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l1xx_hal.h"
#include "stm32l1xx_nucleo.h"
#include "platform-conf.h"
#if COMPILE_SENSORS
#include "x_nucleo_iks01a1_pressure.h"
#include "x_nucleo_iks01a1_imu_6axes.h"
#include "x_nucleo_iks01a1_magneto.h"
#include "x_nucleo_iks01a1_hum_temp.h"
#endif /*COMPILE_SENSORS*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Uncomment to enable the adaquate RTC Clock Source */
#define RTC_CLOCK_SOURCE_LSI
#ifdef RTC_CLOCK_SOURCE_LSI
#define RTC_ASYNCH_PREDIV 0x7F
#define RTC_SYNCH_PREDIV 0x0130
#endif
#ifdef RTC_CLOCK_SOURCE_LSE
#define RTC_ASYNCH_PREDIV 0x7F
#define RTC_SYNCH_PREDIV 0x00FF
#endif
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void stm32cube_hal_init();
void RTC_TimeRegulate(uint8_t hh, uint8_t mm, uint8_t ss);
#ifdef __cplusplus
}
#endif
#endif /* __STM32CUBE_HAL_INIT */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,289 @@
/**
******************************************************************************
* @file stm32l1xx_hal_conf.h
* @author MCD Application Team
* @version V1.0.0
* @date 5-September-2014
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L1xx_HAL_CONF_H
#define __STM32L1xx_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_ADC_MODULE_ENABLED
#define HAL_COMP_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_CRC_MODULE_ENABLED
#define HAL_CRYP_MODULE_ENABLED
#define HAL_DAC_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_GPIO_MODULE_ENABLED
#define HAL_I2C_MODULE_ENABLED
#define HAL_I2S_MODULE_ENABLED
#define HAL_IRDA_MODULE_ENABLED
#define HAL_IWDG_MODULE_ENABLED
#define HAL_LCD_MODULE_ENABLED
#define HAL_NOR_MODULE_ENABLED
//#define HAL_OPAMP_MODULE_ENABLED
//#define HAL_PCD_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
#define HAL_SD_MODULE_ENABLED
#define HAL_SMARTCARD_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
#define HAL_SRAM_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_WWDG_MODULE_ENABLED
/* ########################## Oscillator 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 ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal Multiple Speed oscillator (MSI) default value.
* This value is the default MSI range value after Reset.
*/
#if !defined (MSI_VALUE)
#define MSI_VALUE ((uint32_t)2097000) /*!< Value of the Internal oscillator in Hz*/
#endif /* MSI_VALUE */
/**
* @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)16000000) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/* 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 ((uint32_t)3300) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0x000F) /*!< tick interrupt priority */
#define USE_RTOS 0
#define PREFETCH_ENABLE 1
#define INSTRUCTION_CACHE_ENABLE 0
#define DATA_CACHE_ENABLE 0
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/*#define USE_FULL_ASSERT 1*/
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include module's header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32l1xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32l1xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32l1xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32l1xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32l1xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32l1xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32l1xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32l1xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32l1xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32l1xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32l1xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32l1xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32l1xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32l1xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32l1xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LCD_MODULE_ENABLED
#include "stm32l1xx_hal_lcd.h"
#endif /* HAL_LCD_MODULE_ENABLED */
#ifdef HAL_OPAMP_MODULE_ENABLED
#include "stm32l1xx_hal_opamp.h"
#endif /* HAL_OPAMP_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32l1xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32l1xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32l1xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32l1xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32l1xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32l1xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32l1xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32l1xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32l1xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32l1xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32l1xx_hal_pcd.h"
#endif /* HAL_PCD_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)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* __STM32L1xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,72 @@
/**
******************************************************************************
* @file Templates/Inc/stm32l1xx_it.h
* @author MCD Application Team
* @version V1.0.0
* @date 5-September-2014
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L1xx_IT_H
#define __STM32L1xx_IT_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
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);
void EXTI0_IRQHandler(void);
void EXTI1_IRQHandler(void);
void I2Cx_EV_IRQHandler(void);
void I2Cx_ER_IRQHandler(void);
#ifdef __cplusplus
}
#endif
#endif /* __STM32L1xx_IT_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,649 @@
/**
******************************************************************************
* @file spirit1_appli.c
* @author System Lab - NOIDA
* @version V1.1.0
* @date 14-Aug-2014
* @brief user file to configure Spirit1 transceiver.
*
@verbatim
===============================================================================
##### How to use this driver #####
===============================================================================
[..]
This file is generated automatically by STM32CubeMX and eventually modified
by the user
@endverbatim
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32l152xe.h"
#include "spirit1_appli.h"
#include "MCU_Interface.h"
#include "SPIRIT1_Util.h"
#include "lib/sensors.h"
extern const struct sensors_sensor button_sensor;
/** @addtogroup USER
* @{
*/
/** @defgroup SPIRIT1_APPLI
* @brief User file to configure spirit1 tranceiver for desired frequency and
* @feature.
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/**
* @brief RadioDriver_t structure fitting
*/
RadioDriver_t spirit_cb =
{
.Init = Spirit1InterfaceInit,
.GpioIrq = Spirit1GpioIrqInit,
.RadioInit = Spirit1RadioInit,
.SetRadioPower = Spirit1SetPower,
.PacketConfig = Spirit1PacketConfig,
.SetPayloadLen = Spirit1SetPayloadlength,
.SetDestinationAddress = Spirit1SetDestinationAddress,
.EnableTxIrq = Spirit1EnableTxIrq,
.EnableRxIrq = Spirit1EnableRxIrq,
.DisableIrq = Spirit1DisableIrq,
.SetRxTimeout = Spirit1SetRxTimeout,
.EnableSQI = Spirit1EnableSQI,
.SetRssiThreshold = Spirit1SetRssiTH,
.ClearIrqStatus = Spirit1ClearIRQ,
.StartRx = Spirit1StartRx,
.StartTx = Spirit1StartTx,
.GetRxPacket = Spirit1GetRxPacket
};
/**
* @brief MCULowPowerMode_t structure fitting
*/
MCULowPowerMode_t MCU_LPM_cb =
{
.McuStopMode = MCU_Enter_StopMode,
.McuStandbyMode = MCU_Enter_StandbyMode,
.McuSleepMode = MCU_Enter_SleepMode
};
/**
* @brief RadioLowPowerMode_t structure fitting
*/
RadioLowPowerMode_t Radio_LPM_cb =
{
.RadioShutDown = RadioPowerOFF,
.RadioStandBy = RadioStandBy,
.RadioSleep = RadioSleep,
.RadioPowerON = RadioPowerON
};
/**
* @brief GPIO structure fitting
*/
SGpioInit xGpioIRQ={
SPIRIT_GPIO_IRQ,
SPIRIT_GPIO_MODE_DIGITAL_OUTPUT_LP,
SPIRIT_GPIO_DIG_OUT_IRQ
};
/**
* @brief Radio structure fitting
*/
SRadioInit xRadioInit = {
XTAL_OFFSET_PPM,
BASE_FREQUENCY,
CHANNEL_SPACE,
CHANNEL_NUMBER,
MODULATION_SELECT,
DATARATE,
FREQ_DEVIATION,
BANDWIDTH
};
#if defined(USE_STack_PROTOCOL)
/**
* @brief Packet Basic structure fitting
*/
PktStackInit xStackInit={
PREAMBLE_LENGTH,
SYNC_LENGTH,
SYNC_WORD,
LENGTH_TYPE,
LENGTH_WIDTH,
CRC_MODE,
CONTROL_LENGTH,
EN_FEC,
EN_WHITENING
};
/* LLP structure fitting */
PktStackLlpInit xStackLLPInit ={
EN_AUTOACK,
EN_PIGGYBACKING,
MAX_RETRANSMISSIONS
};
/**
* @brief Address structure fitting
*/
PktStackAddressesInit xAddressInit={
EN_FILT_MY_ADDRESS,
MY_ADDRESS,
EN_FILT_MULTICAST_ADDRESS,
MULTICAST_ADDRESS,
EN_FILT_BROADCAST_ADDRESS,
BROADCAST_ADDRESS
};
#elif defined(USE_BASIC_PROTOCOL)
/**
* @brief Packet Basic structure fitting
*/
PktBasicInit xBasicInit={
PREAMBLE_LENGTH,
SYNC_LENGTH,
SYNC_WORD,
LENGTH_TYPE,
LENGTH_WIDTH,
CRC_MODE,
CONTROL_LENGTH,
EN_ADDRESS,
EN_FEC,
EN_WHITENING
};
/**
* @brief Address structure fitting
*/
PktBasicAddressesInit xAddressInit={
EN_FILT_MY_ADDRESS,
MY_ADDRESS,
EN_FILT_MULTICAST_ADDRESS,
MULTICAST_ADDRESS,
EN_FILT_BROADCAST_ADDRESS,
BROADCAST_ADDRESS
};
#endif
/* Private define ------------------------------------------------------------*/
#define TIME_UP 0x01
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
RadioDriver_t *pRadioDriver;
MCULowPowerMode_t *pMCU_LPM_Comm;
RadioLowPowerMode_t *pRadio_LPM_Comm;
/*Flags declarations*/
volatile FlagStatus xRxDoneFlag = RESET, xTxDoneFlag=RESET, cmdFlag=RESET;
volatile FlagStatus xStartRx=RESET, rx_timeout=RESET, exitTime=RESET;
volatile FlagStatus datasendFlag=RESET, wakeupFlag=RESET;
volatile FlagStatus PushButtonStatusWakeup=RESET;
volatile FlagStatus PushButtonStatusData=RESET;
/*IRQ status struct declaration*/
SpiritIrqs xIrqStatus;
static __IO uint32_t KEYStatusData = 0x00;
AppliFrame_t xTxFrame, xRxFrame;
uint8_t TxFrameBuff[MAX_BUFFER_LEN] = {0x00};
uint16_t exitCounter = 0;
uint16_t txCounter = 0;
uint16_t wakeupCounter = 0;
uint16_t dataSendCounter = 0x00;
/* Private function prototypes -----------------------------------------------*/
void HAL_Spirit1_Init(void);
void Data_Comm_On(uint8_t *pTxBuff, uint8_t cTxlen, uint8_t* pRxBuff, uint8_t cRxlen);
void Enter_LP_mode(void);
void Exit_LP_mode(void);
void MCU_Enter_StopMode(void);
void MCU_Enter_StandbyMode(void);
void MCU_Enter_SleepMode(void);
void RadioPowerON(void);
void RadioPowerOFF(void);
void RadioStandBy(void);
void RadioSleep(void);
void SPIRIT1_Init(void);
void STackProtocolInit(void);
void BasicProtocolInit(void);
void P2PInterruptHandler(void);
void Set_KeyStatus(FlagStatus val);
void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin);
void HAL_SYSTICK_Callback(void);
/* Private functions ---------------------------------------------------------*/
/** @defgroup SPIRIT1_APPLI_Private_Functions
* @{
*/
/**
* @brief Initializes RF Transceiver's HAL.
* @param None
* @retval None.
*/
void HAL_Spirit1_Init(void)
{
pRadioDriver = &spirit_cb;
pRadioDriver->Init( );
}
/**
* @brief This function initializes the protocol for point-to-point
* communication
* @param None
* @retval None
*/
void SPIRIT1_Init(void)
{
pRadioDriver = &spirit_cb;
/* Spirit IRQ config */
pRadioDriver->GpioIrq(&xGpioIRQ);
/* Spirit Radio config */
pRadioDriver->RadioInit(&xRadioInit);
/* Spirit Radio set power */
pRadioDriver->SetRadioPower(POWER_INDEX, POWER_DBM);
/* Spirit Packet config */
pRadioDriver->PacketConfig();
pRadioDriver->EnableSQI();
pRadioDriver->SetRssiThreshold(RSSI_THRESHOLD);
}
/**
* @brief This function initializes the BASIC Packet handler of spirit1
* @param None
* @retval None
*/
void BasicProtocolInit(void)
{
#if defined(USE_BASIC_PROTOCOL)
/* Spirit Packet config */
SpiritPktBasicInit(&xBasicInit);
SpiritPktBasicAddressesInit(&xAddressInit);
#endif
}
/**
* @brief This routine will put the radio and mcu in LPM
* @param None
* @retval None
*/
void Enter_LP_mode(void)
{
pMCU_LPM_Comm = &MCU_LPM_cb;
pRadio_LPM_Comm = &Radio_LPM_cb;
#if defined(MCU_STOP_MODE)&&defined(RF_SHUTDOWN)
{
pRadio_LPM_Comm->RadioShutDown();
pMCU_LPM_Comm->McuStopMode();
}
#elif defined(MCU_STOP_MODE)&&defined(RF_STANDBY)
{
pRadio_LPM_Comm->RadioStandBy();
pMCU_LPM_Comm->McuStopMode();
}
#elif defined(MCU_STOP_MODE)&&defined(RF_SLEEP)
{
pRadio_LPM_Comm->RadioSleep();
pMCU_LPM_Comm->McuStopMode();
}
#elif defined(MCU_STANDBY_MODE)&&defined(RF_SHUTDOWN)
{
pRadio_LPM_Comm->RadioShutDown();
pMCU_LPM_Comm->McuStandbyMode();
}
#elif defined(MCU_STANDBY_MODE)&&defined(RF_STANDBY)
{
pRadio_LPM_Comm->RadioStandBy();
pMCU_LPM_Comm->McuStandbyMode();
}
#elif defined(MCU_STANDBY_MODE)&&defined(RF_SLEEP)
{
pRadio_LPM_Comm->RadioSleep();
pMCU_LPM_Comm->McuStandbyMode();
}
#elif defined(MCU_SLEEP_MODE)&&defined(RF_SHUTDOWN)
{
pRadio_LPM_Comm->RadioShutDown();
pMCU_LPM_Comm->McuSleepMode();
}
#elif defined(MCU_SLEEP_MODE)&&defined(RF_STANDBY)
{
pRadio_LPM_Comm->RadioStandBy();
pMCU_LPM_Comm->McuSleepMode();
}
#elif defined(MCU_SLEEP_MODE)&&defined(RF_SLEEP)
{
pRadio_LPM_Comm->RadioSleep();
pMCU_LPM_Comm->McuSleepMode();
}
#elif defined(MCU_STOP_MODE)
pMCU_LPM_Comm->McuStopMode();
#elif defined(MCU_STANDBY_MODE)
pMCU_LPM_Comm->McuStandbyMode();
#else
pMCU_LPM_Comm->McuSleepMode();
#endif
}
/**
* @brief This routine wake-up the mcu and radio from LPM
* @param None
* @retval None
*/
void Exit_LP_mode(void)
{
pRadio_LPM_Comm = &Radio_LPM_cb;
pRadio_LPM_Comm->RadioPowerON();
}
/**
* @brief This routine puts the MCU in stop mode
* @param None
* @retval None
*/
void MCU_Enter_StopMode(void)
{
HAL_PWR_EnterSTOPMode(PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI); /* Infinite loop */
}
/**
* @brief This routine puts the MCU in standby mode
* @param None
* @retval None
*/
void MCU_Enter_StandbyMode(void)
{
HAL_PWR_EnterSTANDBYMode(); /* Infinite loop */
}
/**
* @brief This routine puts the MCU in sleep mode
* @param None
* @retval None
*/
void MCU_Enter_SleepMode(void)
{
/*Suspend Tick increment to prevent wakeup by Systick interrupt.
Otherwise the Systick interrupt will wake up the device within 1ms (HAL time base)*/
HAL_SuspendTick();
HAL_PWR_EnterSLEEPMode(PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI); /* Infinite loop */
}
/**
* @brief This function will turn on the radio and waits till it enters the Ready state.
* @param Param:None.
* @retval None
*
*/
void RadioPowerON(void)
{
SpiritCmdStrobeReady();
do{
/* Delay for state transition */
for(volatile uint8_t i=0; i!=0xFF; i++);
/* Reads the MC_STATUS register */
SpiritRefreshStatus();
}
while(g_xStatus.MC_STATE!=MC_STATE_READY);
}
/**
* @brief This function will Shut Down the radio.
* @param Param:None.
* @retval None
*
*/
void RadioPowerOFF(void)
{
SpiritEnterShutdown();
}
/**
* @brief This function will put the radio in standby state.
* @param None.
* @retval None
*
*/
void RadioStandBy(void)
{
SpiritCmdStrobeStandby();
#if 0
do{
/* Delay for state transition */
for(volatile uint8_t i=0; i!=0xFF; i++);
/* Reads the MC_STATUS register */
SpiritRefreshStatus();
}
while(g_xStatus.MC_STATE!=MC_STATE_STANDBY);
#endif
}
/**
* @brief This function will put the radio in sleep state.
* @param None.
* @retval None
*
*/
void RadioSleep(void)
{
SpiritCmdStrobeSleep();
#if 0
do{
/* Delay for state transition */
for(volatile uint8_t i=0; i!=0xFF; i++);
/* Reads the MC_STATUS register */
SpiritRefreshStatus();
}
while(g_xStatus.MC_STATE!=MC_STATE_SLEEP);
#endif
}
/**
* @brief This routine updates the respective status for key press.
* @param None
* @retval None
*/
void Set_KeyStatus(FlagStatus val)
{
if(val==SET)
{
KEYStatusData = 1;
}
else
KEYStatusData = 0;
}
/**
* @brief SYSTICK callback.
* @param None
* @retval None
*/
void HAL_SYSTICK_Callback(void)
{
if(exitTime)
{
/*Decreament the counter to check when 3 seconds has been elapsed*/
exitCounter--;
/*3 seconds has been elapsed*/
if(exitCounter <= TIME_UP)
{
exitTime = RESET;
}
}
#if defined(RF_STANDBY)
/*Check if Push Button pressed for wakeup or to send data*/
if(PushButtonStatusWakeup)
{
/*Decreament the counter to check when 5 seconds has been elapsed*/
wakeupCounter--;
/*5seconds has been elapsed*/
if(wakeupCounter<=TIME_UP)
{
/*Perform wakeup opeartion*/
wakeupFlag = SET;
Exit_LP_mode();
BSP_LED_Toggle(LED2);
PushButtonStatusWakeup = RESET;
PushButtonStatusData = SET;
}
}
else if(PushButtonStatusData)
{
dataSendCounter--;
if(dataSendCounter<=TIME_UP)
{
datasendFlag = SET;
PushButtonStatusWakeup = RESET;
PushButtonStatusData = RESET;
}
}
#endif
}
/**
* @}
*/
/**
* @brief GPIO EXTI callback
* @param uint16_t GPIO_Pin
* @retval None
*/
void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
{
#if defined(MCU_STOP_MODE)/*if MCU is in stop mode*/
/* Clear Wake Up Flag */
__HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU);
/* Configures system clock after wake-up from STOP: enable HSE, PLL and select
PLL as system clock source (HSE and PLL are disabled in STOP mode) */
SystemClockConfig_STOP();
#endif
#if defined(MCU_SLEEP_MODE)
/* Resume Tick interrupt if disabled prior to sleep mode entry*/
HAL_ResumeTick();
#endif
/* Initialize LEDs*/
RadioShieldLedInit(RADIO_SHIELD_LED);
//BSP_LED_Init(LED2);
if (GPIO_Pin == USER_BUTTON_PIN)
{
sensors_changed(&button_sensor);
}
}
/**
* @}
*/
/**
* @brief Configures system clock after wake-up from STOP: enable HSI, PLL
* and select PLL as system clock source.
* @param None
* @retval None
*/
#if defined(MCU_STOP_MODE)/*if MCU is in stop mode*/
static void SystemClockConfig_STOP(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_OscInitTypeDef RCC_OscInitStruct;
/* Enable Power Control clock */
__PWR_CLK_ENABLE();
/* The voltage scaling allows optimizing the power consumption when the device is
clocked below the maximum system frequency, to update the voltage scaling value
regarding system frequency refer to product datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/* Get the Oscillators configuration according to the internal RCC registers */
HAL_RCC_GetOscConfig(&RCC_OscInitStruct);
/* After wake-up from STOP reconfigure the system clock: Enable HSI and PLL */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSEState = RCC_HSE_OFF;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLLMUL_4;
RCC_OscInitStruct.PLL.PLLDIV = RCC_PLLDIV_2;
RCC_OscInitStruct.HSICalibrationValue = 0x10;
HAL_RCC_OscConfig(&RCC_OscInitStruct);
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
clocks dividers */
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1);
}
#endif
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,334 @@
/**
******************************************************************************
* @file stm32cube_hal_init.c
* @author System LAB
* @version V1.0.0
* @date 17-June-2015
* @brief STM32 Cube HAL Init Source file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stdio.h"
#include "string.h"
#include "stdlib.h"
#include "stm32cube_hal_init.h"
#include "stm32l1xx_nucleo.h"
#include "radio_shield_config.h"
#include "spirit1_appli.h"
extern UART_HandleTypeDef UartHandle;
FlagStatus TamperStatus = RESET;
volatile uint8_t scheduler_started=0;
RTC_HandleTypeDef RtcHandle;
int dec_precision = 2;
volatile float UVI_Value;
static void RTC_Config(void);
static void RTC_TimeStampConfig(void);
static void SystemClock_Config(void);
static void MX_GPIO_Init(void);
void BSP_PB_Init(Button_TypeDef Button, ButtonMode_TypeDef Button_Mode);
void BSP_LED_Init(Led_TypeDef Led);
void BSP_LED_Off(Led_TypeDef Led);
void BSP_LED_On(Led_TypeDef Led);
void BSP_LED_Toggle(Led_TypeDef Led);
void USARTConfig(void);
void Stack_6LoWPAN_Init(void);
static void Error_Handler();
I2C_HandleTypeDef I2cHandle;
#define I2C_ADDRESS 0x30F
/* I2C SPEEDCLOCK define to max value: 400 KHz on STM32L1xx*/
#define I2C_SPEEDCLOCK 400000
#define I2C_DUTYCYCLE I2C_DUTYCYCLE_2
/**
* @brief stm32cube_hal_init()
* @param None
* @retval None
*/
void stm32cube_hal_init()
{
HAL_Init();
/* Configure the system clock */
SystemClock_Config();
HAL_EnableDBGStopMode();
MX_GPIO_Init();
HAL_Spirit1_Init();
SPIRIT1_Init();
USARTConfig();
/* Initialize RTC */
RTC_Config();
RTC_TimeStampConfig();
}
/**
* @brief Configure the RTC peripheral by selecting the clock source.
* @param None
* @retval None
*/
void RTC_Config(void)
{
/*##-1- Configure the RTC peripheral #######################################*/
RtcHandle.Instance = RTC;
/* Configure RTC prescaler and RTC data registers */
/* RTC configured as follow:
- Hour Format = Format 12
- Asynch Prediv = Value according to source clock
- Synch Prediv = Value according to source clock
- OutPut = Output Disable
- OutPutPolarity = High Polarity
- OutPutType = Open Drain */
RtcHandle.Init.HourFormat = RTC_HOURFORMAT_12;
RtcHandle.Init.AsynchPrediv = RTC_ASYNCH_PREDIV;
RtcHandle.Init.SynchPrediv = RTC_SYNCH_PREDIV;
RtcHandle.Init.OutPut = RTC_OUTPUT_DISABLE;
RtcHandle.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH;
RtcHandle.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN;
if(HAL_RTC_Init(&RtcHandle) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
}
/**
* @brief Configures the current time and date.
* @param None
* @retval None
*/
static void RTC_TimeStampConfig(void)
{
RTC_DateTypeDef sdatestructure;
RTC_TimeTypeDef stimestructure;
/*##-3- Configure the Date #################################################*/
/* Set Date: Tuesday February 18th 2014 */
sdatestructure.Year = 0x14;
sdatestructure.Month = RTC_MONTH_FEBRUARY;
sdatestructure.Date = 0x18;
sdatestructure.WeekDay = RTC_WEEKDAY_TUESDAY;
if(HAL_RTC_SetDate(&RtcHandle,&sdatestructure,FORMAT_BCD) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
/*##-4- Configure the Time #################################################*/
/* Set Time: 08:10:00 */
stimestructure.Hours = 0x08;
stimestructure.Minutes = 0x10;
stimestructure.Seconds = 0x00;
stimestructure.TimeFormat = RTC_HOURFORMAT12_AM;
stimestructure.DayLightSaving = RTC_DAYLIGHTSAVING_NONE ;
stimestructure.StoreOperation = RTC_STOREOPERATION_RESET;
if(HAL_RTC_SetTime(&RtcHandle,&stimestructure,FORMAT_BCD) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
}
/**
* @brief System Clock Configuration
* The system Clock is configured as follow :
* System Clock source = PLL (HSI)
* SYSCLK(Hz) = 32000000
* HCLK(Hz) = 32000000
* AHB Prescaler = 1
* APB1 Prescaler = 1
* APB2 Prescaler = 1
* HSI Frequency(Hz) = 16000000
* PLL_MUL = 4
* PLL_DIV = 2
* Flash Latency(WS) = 1
* Main regulator output voltage = Scale1 mode
* @param None
* @retval None
*/
void SystemClock_Config(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
/* Enable HSE Oscillator and Activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSEState = RCC_HSE_OFF;
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.PLLMUL = RCC_PLL_MUL6;
RCC_OscInitStruct.PLL.PLLDIV = RCC_PLL_DIV3;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
Error_Handler();
}
/* Set Voltage scale1 as MCU will run at 32MHz */
__PWR_CLK_ENABLE();
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/* Poll VOSF bit of in PWR_CSR. Wait until it is reset to 0 */
while (__HAL_PWR_GET_FLAG(PWR_FLAG_VOS) != RESET) {};
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
clocks dividers */
RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK)
{
Error_Handler();
}
}
/**
* @brief This function is executed in case of error occurrence.
* @param None
* @retval None
*/
static void Error_Handler(void)
{
/* User may add here some code to deal with this error */
while(1)
{
}
}
/**
* @brief RTC MSP Initialization
* This function configures the hardware resources used in this example
* @param hrtc: RTC handle pointer
*
* @note Care must be taken when HAL_RCCEx_PeriphCLKConfig() is used to select
* the RTC clock source; in this case the Backup domain will be reset in
* order to modify the RTC Clock source, as consequence RTC registers (including
* the backup registers) and RCC_BDCR register are set to their reset values.
*
* @retval None
*/
void HAL_RTC_MspInit(RTC_HandleTypeDef *hrtc)
{
RCC_OscInitTypeDef RCC_OscInitStruct;
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
/*##-1- Configue LSE as RTC clock soucre ###################################*/
#ifdef RTC_CLOCK_SOURCE_LSE
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI | RCC_OSCILLATORTYPE_LSE;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
RCC_OscInitStruct.LSEState = RCC_LSE_ON;
RCC_OscInitStruct.LSIState = RCC_LSI_OFF;
if(HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC;
PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
if(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
#elif defined (RTC_CLOCK_SOURCE_LSI)
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI | RCC_OSCILLATORTYPE_LSE;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
RCC_OscInitStruct.LSEState = RCC_LSE_OFF;
if(HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_RTC;
PeriphClkInitStruct.RTCClockSelection = RCC_RTCCLKSOURCE_LSI;
if(HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
/* Initialization Error */
Error_Handler();
}
#else
#error Please select the RTC Clock source inside the stm32cube_hal_init.h file
#endif /*RTC_CLOCK_SOURCE_LSE*/
/*##-2- Enable RTC peripheral Clocks #######################################*/
/* Enable RTC Clock */
__HAL_RCC_RTC_ENABLE();
/*##-3- Configure the NVIC for RTC TimeStamp ###################################*/
HAL_NVIC_SetPriority(/*TAMP_STAMP_IRQn*/2, 0x0F, 0);
HAL_NVIC_EnableIRQ(/*TAMP_STAMP_IRQn*/2);
}
/** Configure pins as
* Analog
* Input
* Output
* EVENT_OUT
* EXTI
*/
void MX_GPIO_Init(void)
{
/* GPIO Ports Clock Enable */
__GPIOA_CLK_ENABLE();
__GPIOC_CLK_ENABLE();
__GPIOD_CLK_ENABLE();
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,319 @@
/**
******************************************************************************
* @file stm32l1xx_hal_msp.c
* @author System LAB
* @version V1.0.0
* @date 17-June-2015
* @brief HAL MSP file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32cube_hal_init.h"
#include "stm32l1xx_hal.h"
#include "hw-config.h"
/** @addtogroup STM32L1xx_HAL_Examples
* @{
*/
/** @addtogroup Templates
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
volatile uint8_t UART_RxBuffer[UART_RxBufferSize];
volatile uint32_t Usart_BaudRate = 115200;
UART_HandleTypeDef UartHandle;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/** @defgroup HAL_MSP_Private_Functions
* @{
*/
/**
* @brief Initializes the Global MSP.
* @param None
* @retval None
*/
void HAL_MspInit(void)
{
/* NOTE : This function is generated automatically by MicroXplorer and eventually
modified by the user
*/
GPIO_InitTypeDef GPIO_InitStruct;
/*##-2- Enable peripherals and GPIO Clocks #################################*/
/* Enable GPIO TX/RX clock */
/* GPIO Ports Clock Enable */
__GPIOA_CLK_ENABLE();
__GPIOC_CLK_ENABLE();
__GPIOD_CLK_ENABLE();
I2Cx_SCL_GPIO_CLK_ENABLE();
I2Cx_SDA_GPIO_CLK_ENABLE();
/* Enable I2Cx clock */
I2Cx_CLK_ENABLE();
/*##-3- Configure peripheral GPIO ##########################################*/
/* I2C TX GPIO pin configuration */
GPIO_InitStruct.Pin = I2Cx_SCL_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = I2Cx_SCL_SDA_AF;
HAL_GPIO_Init(I2Cx_SCL_GPIO_PORT, &GPIO_InitStruct);
/* I2C RX GPIO pin configuration */
GPIO_InitStruct.Pin = I2Cx_SDA_PIN;
GPIO_InitStruct.Alternate = I2Cx_SCL_SDA_AF;
HAL_GPIO_Init(I2Cx_SDA_GPIO_PORT, &GPIO_InitStruct);
/*##-4- Configure the NVIC for I2C ########################################*/
/* NVIC for I2Cx */
HAL_NVIC_SetPriority(I2Cx_ER_IRQn, 0, 1);
HAL_NVIC_EnableIRQ(I2Cx_ER_IRQn);
HAL_NVIC_SetPriority(I2Cx_EV_IRQn, 0, 2);
HAL_NVIC_EnableIRQ(I2Cx_EV_IRQn);
}
/**
* @brief DeInitializes the Global MSP.
* @param None
* @retval None
*/
void HAL_MspDeInit(void)
{
/* NOTE : This function is generated automatically by MicroXplorer and eventually
modified by the user
*/
/*##-1- Reset peripherals ##################################################*/
I2Cx_FORCE_RESET();
I2Cx_RELEASE_RESET();
/*##-2- Disable peripherals and GPIO Clocks #################################*/
/* Configure I2C Tx as alternate function */
HAL_GPIO_DeInit(I2Cx_SCL_GPIO_PORT, I2Cx_SCL_PIN);
/* Configure I2C Rx as alternate function */
HAL_GPIO_DeInit(I2Cx_SDA_GPIO_PORT, I2Cx_SDA_PIN);
/*##-3- Disable the NVIC for I2C ##########################################*/
HAL_NVIC_DisableIRQ(I2Cx_ER_IRQn);
HAL_NVIC_DisableIRQ(I2Cx_EV_IRQn);
}
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base)
{
if(htim_base->Instance==TIM2)
{
/* Peripheral clock enable */
__TIM2_CLK_ENABLE();
/**TIM2 GPIO Configuration
PA0-WKUP ------> TIM2_CH1
*/
/* Peripheral interrupt init*/
HAL_NVIC_SetPriority(TIM2_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(TIM2_IRQn);
}
}
void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base)
{
if(htim_base->Instance==TIM2)
{
/* Peripheral clock disable */
__TIM2_CLK_DISABLE();
/**TIM2 GPIO Configuration
PA0-WKUP ------> TIM2_CH1
*/
/* Peripheral interrupt Deinit*/
HAL_NVIC_DisableIRQ(TIM2_IRQn);
}
}
/**
* @brief UART MSP Initialization
* This function configures the hardware resources used in this example:
* - Peripheral's clock enable
* - Peripheral's GPIO Configuration
* - NVIC configuration for UART interrupt request enable
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspInit(UART_HandleTypeDef *huart)
{
GPIO_InitTypeDef GPIO_InitStruct;
/*##-1- Enable peripherals and GPIO Clocks #################################*/
/* Enable GPIO TX/RX clock */
USARTx_TX_GPIO_CLK_ENABLE();
USARTx_RX_GPIO_CLK_ENABLE();
/* Enable USARTx clock */
USARTx_CLK_ENABLE();
/*##-2- Configure peripheral GPIO ##########################################*/
/* UART TX GPIO pin configuration */
GPIO_InitStruct.Pin = USARTx_TX_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = USARTx_TX_AF;
HAL_GPIO_Init(USARTx_TX_GPIO_PORT, &GPIO_InitStruct);
/* UART RX GPIO pin configuration */
GPIO_InitStruct.Pin = USARTx_RX_PIN;
GPIO_InitStruct.Alternate = USARTx_RX_AF;
HAL_GPIO_Init(USARTx_RX_GPIO_PORT, &GPIO_InitStruct);
/*##-3- Configure the NVIC for UART ########################################*/
/* NVIC for USART */
HAL_NVIC_SetPriority(USARTx_IRQn, 0, 1);
HAL_NVIC_EnableIRQ(USARTx_IRQn);
}
/**
* @brief UART MSP De-Initialization
* This function frees the hardware resources used in this example:
* - Disable the Peripheral's clock
* - Revert GPIO and NVIC configuration to their default state
* @param huart: UART handle pointer
* @retval None
*/
void HAL_UART_MspDeInit(UART_HandleTypeDef *huart)
{
/*##-1- Reset peripherals ##################################################*/
USARTx_FORCE_RESET();
USARTx_RELEASE_RESET();
/*##-2- Disable peripherals and GPIO Clocks #################################*/
/* Configure UART Tx as alternate function */
HAL_GPIO_DeInit(USARTx_TX_GPIO_PORT, USARTx_TX_PIN);
/* Configure UART Rx as alternate function */
HAL_GPIO_DeInit(USARTx_RX_GPIO_PORT, USARTx_RX_PIN);
/*##-3- Disable the NVIC for UART ##########################################*/
HAL_NVIC_DisableIRQ(USARTx_IRQn);
}
/**
* @brief Configure the USART
* @param None
* @retval None
*/
void USARTConfig(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
/*##-1- Enable peripherals and GPIO Clocks #################################*/
/* Enable GPIO TX/RX clock */
USARTx_TX_GPIO_CLK_ENABLE();
USARTx_RX_GPIO_CLK_ENABLE();
/* Enable USART2 clock */
USARTx_CLK_ENABLE();
/* Enable DMA1 clock */
DMAx_CLK_ENABLE();
/*##-2- Configure peripheral GPIO ##########################################*/
/* UART TX GPIO pin configuration */
GPIO_InitStruct.Pin = USARTx_TX_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
GPIO_InitStruct.Alternate = USARTx_TX_AF;
HAL_GPIO_Init(USARTx_TX_GPIO_PORT, &GPIO_InitStruct);
/* UART RX GPIO pin configuration */
GPIO_InitStruct.Pin = USARTx_RX_PIN;
GPIO_InitStruct.Alternate = USARTx_RX_AF;
HAL_GPIO_Init(USARTx_RX_GPIO_PORT, &GPIO_InitStruct);
/*##-1- Configure the UART peripheral ######################################*/
/* Put the USART peripheral in the Asynchronous mode (UART Mode) */
UartHandle.Instance = USARTx;
UartHandle.Init.BaudRate = Usart_BaudRate;
UartHandle.Init.WordLength = UART_WORDLENGTH_8B;
UartHandle.Init.StopBits = UART_STOPBITS_1;
UartHandle.Init.Parity = UART_PARITY_NONE;
UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
UartHandle.Init.Mode = UART_MODE_TX_RX;
if(HAL_UART_Init(&UartHandle) != HAL_OK)
{
// Error_Handler();
while(1);
}
UartHandle.pRxBuffPtr = (uint8_t*)UART_RxBuffer;
UartHandle.RxXferSize = UART_RxBufferSize;
UartHandle.ErrorCode = HAL_UART_ERROR_NONE;
//HAL_UART_Receive_IT(&UartHandle, (uint8_t*)UART_RxBuffer, UART_RxBufferSize);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,363 @@
/**
******************************************************************************
* @file stm32l1xx_it.c
* @author System LAB
* @version V1.0.0
* @date 17-June-2015
* @brief Main Interrupt Service Routines
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2014 STMicroelectronics</center></h2>
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32cube_hal_init.h"
#include "stm32l1xx_it.h"
#include "stm32l1xx_nucleo.h"
#include "radio_gpio.h"
#include "spirit1.h"
extern UART_HandleTypeDef UartHandle;
/** @addtogroup STM32L1xx_HAL_Examples
* @{
*/
/** @addtogroup Templates
* @{
*/
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/******************************************************************************/
/* Cortex-M3 Processor Exceptions Handlers */
/******************************************************************************/
extern I2C_HandleTypeDef I2cHandle;
/**
* @brief This function handles NMI exception.
* @param None
* @retval None
*/
void NMI_Handler(void)
{
}
void WWDG_IRQHandler(void)
{
while(1);
}
/**
* @brief This function handles Hard Fault exception.
* @param None
* @retval None
*/
void HardFault_Handler(void)
{
/* Go to infinite loop when Hard Fault exception occurs */
while (1)
{
}
}
/**
* @brief This function handles Memory Manage exception.
* @param None
* @retval None
*/
void MemManage_Handler(void)
{
/* Go to infinite loop when Memory Manage exception occurs */
while (1)
{
}
}
/**
* @brief This function handles Bus Fault exception.
* @param None
* @retval None
*/
void BusFault_Handler(void)
{
/* Go to infinite loop when Bus Fault exception occurs */
while (1)
{
}
}
/**
* @brief This function handles Usage Fault exception.
* @param None
* @retval None
*/
void UsageFault_Handler(void)
{
/* Go to infinite loop when Usage Fault exception occurs */
while (1)
{
}
}
/**
* @brief This function handles SVCall exception.
* @param None
* @retval None
*/
void SVC_Handler(void)
{
}
/**
* @brief This function handles Debug Monitor exception.
* @param None
* @retval None
*/
void DebugMon_Handler(void)
{
}
/**
* @brief This function handles PendSVC exception.
* @param None
* @retval None
*/
void PendSV_Handler(void)
{
}
/******************************************************************************/
/* STM32L1xx Peripherals Interrupt Handlers */
/* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */
/* available peripheral interrupt handler's name please refer to the startup */
/* file (startup_stm32l1xx.s). */
/******************************************************************************/
/**
* @brief This function handles I2C event interrupt request.
* @param None
* @retval None
* @Note This function is redefined in "stm32cube_hal_init.h" and related to I2C data transmission
*/
void I2Cx_EV_IRQHandler(void)
{
HAL_I2C_EV_IRQHandler(& I2cHandle);
}
/**
* @brief This function handles I2C error interrupt request.
* @param None
* @retval None
* @Note This function is redefined in "stm32cube_hal_init.h" and related to I2C error
*/
void I2Cx_ER_IRQHandler(void)
{
HAL_I2C_ER_IRQHandler(& I2cHandle);
}
/**
* @brief This function handles External lines 15 to 4 interrupt request.
* @param None
* @retval None
*/
void EXTI0_IRQHandler(void)
{
/* EXTI line interrupt detected */
if(__HAL_GPIO_EXTI_GET_IT(GPIO_PIN_0) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_0);
}
while(1);
}
void EXTI1_IRQHandler(void)
{
/* EXTI line interrupt detected */
if(__HAL_GPIO_EXTI_GET_IT(GPIO_PIN_1) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_1);
}
while(1);
}
void EXTI2_IRQHandler(void)
{
/* EXTI line interrupt detected */
if(__HAL_GPIO_EXTI_GET_IT(GPIO_PIN_2) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_2);
}
while(1);
}
void EXTI3_IRQHandler(void)
{
/* EXTI line interrupt detected */
if(__HAL_GPIO_EXTI_GET_IT(GPIO_PIN_3) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_3);
}
while(1);
}
/**
* @brief This function handles External lines 15 to 4 interrupt request.
* @param None
* @retval None
*/
void EXTI9_5_IRQHandler(void)
{
/* EXTI line 7 interrupt detected */
if(__HAL_GPIO_EXTI_GET_IT(RADIO_GPIO_3_EXTI_LINE))
{
__HAL_GPIO_EXTI_CLEAR_IT(RADIO_GPIO_3_EXTI_LINE);
HAL_GPIO_EXTI_Callback(RADIO_GPIO_3_EXTI_LINE);
spirit1_interrupt_callback();
}
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_9);
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_8);
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_7);
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_6);
__HAL_GPIO_EXTI_CLEAR_IT(GPIO_PIN_5);
#ifndef LPM_ENABLE
// if(__HAL_GPIO_EXTI_GET_IT(KEY_BUTTON_EXTI_LINE) != RESET)
// {
// __HAL_GPIO_EXTI_CLEAR_IT(KEY_BUTTON_EXTI_LINE);
//
// Set_KeyStatus(SET);
// }
//
#else /*Low Power mode enabled*/
#if defined(RF_STANDBY)/*if spirit1 is in standby*/
if(EXTI->PR & KEY_BUTTON_EXTI_LINE)
{
HAL_GPIO_EXTI_Callback(KEY_BUTTON_EXTI_LINE);
/* EXTI line 13 interrupt detected */
if(HAL_GPIO_ReadPin(KEY_BUTTON_GPIO_PORT, KEY_BUTTON_PIN) == 0x01) //0x00
{
HAL_GPIO_EXTI_Callback(KEY_BUTTON_EXTI_LINE);
PushButtonStatusWakeup = SET;
PushButtonStatusData = RESET;
wakeupCounter = LPM_WAKEUP_TIME;
dataSendCounter = DATA_SEND_TIME;
dataSendCounter++;
}
__HAL_GPIO_EXTI_CLEAR_IT(KEY_BUTTON_EXTI_LINE);
}
#else /*if spirit1 is not in standby or sleep mode but MCU is in LPM*/
if(__HAL_GPIO_EXTI_GET_IT(KEY_BUTTON_EXTI_LINE) != RESET)
{
__HAL_GPIO_EXTI_CLEAR_IT(KEY_BUTTON_EXTI_LINE);
HAL_GPIO_EXTI_Callback(KEY_BUTTON_EXTI_LINE);
Set_KeyStatus(SET);
}
#endif
#endif
}
/**
* @brief This function handles EXTI15_10_IRQHandler
* @param None
* @retval None
*/
void EXTI15_10_IRQHandler(void)
{
HAL_GPIO_EXTI_IRQHandler(USER_BUTTON_PIN);
}
/**
* @brief This function handles UART interrupt request.
* @param None
* @retval None
* @Note This function is redefined in "stm32cube_hal_init.h" and related to DMA
* used for USART data transmission
*/
void USART2_IRQHandler()
{
slip_input_byte(UartHandle.Instance->DR);
return;
//HAL_UART_IRQHandler(&UartHandle);
}
/**
* @brief UART error callbacks
* @param UartHandle: UART handle
* @note This example shows a simple way to report transfer error, and you can
* add your own implementation.
* @retval None
*/
void HAL_UART_ErrorCallback(UART_HandleTypeDef *UartHandle)
{
// Error_Handler();
}
/**
* @brief Tx Transfer completed callback
* @param UartHandle: UART handle.
* @note This example shows a simple way to report end of IT Tx transfer, and
* you can add your own implementation.
* @retval None
*/
void HAL_UART_TxCpltCallback(UART_HandleTypeDef *UartHandle)
{
}
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/