This commit is contained in:
xavie
2025-12-05 17:08:34 +01:00
commit 6ff7181a1e
348 changed files with 308857 additions and 0 deletions

43
.gitignore vendored Normal file
View File

@@ -0,0 +1,43 @@
# STM32CubeIDE - Fichiers de projet
###################################
# Fichiers de configuration IDE
.cproject
.mxproject
.project
.settings/
# Dossiers de compilation
/Debug/
/Release/
/build/
# Fichiers générés par le lien et les outils
*.map
*.elf
*.bin
*.hex
*.lst
*.o
*.srec
# Fichiers temporaires
*~
#*#
# Eclipse Workspace files (STM32CubeIDE est basé sur Eclipse)
.metadata
LocalHistory/
# KiCad - Fichiers temporaires et de sauvegarde
###############################################
*.bak
*-bak.pro
*-save.pro
*.dcm
*.net
*.rpt
*.bck
*.cmp
*.log
*.zip

View File

@@ -0,0 +1 @@
/Debug/

View File

@@ -0,0 +1,45 @@
/**
******************************************************************************
* File Name : app_bluenrg_ms.h
* Description : Header file
*
******************************************************************************
*
* COPYRIGHT 2021 STMicroelectronics
*
* 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 APP_BLUENRG_MS_H
#define APP_BLUENRG_MS_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* Exported Functions --------------------------------------------------------*/
void MX_BlueNRG_MS_Init(void);
void MX_BlueNRG_MS_Process(void);
#ifdef __cplusplus
}
#endif
#endif /* APP_BLUENRG_MS_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,150 @@
/**
******************************************************************************
* @file sample_service.h
* @author CL
* @version V1.0.0
* @date 04-July-2014
* @brief
******************************************************************************
* @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 SAMPLE_SERVICE_H
#define SAMPLE_SERVICE_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include <stdio.h>
#include "bluenrg_gap.h"
#include "bluenrg_aci_const.h"
#include "hci.h"
#include "hci_le.h"
#include "sm.h"
#include "cmsis_os.h"
#include "commonMsg.h"
/** @addtogroup Applications
* @{
*/
/** @addtogroup SampleApp
* @{
*/
/** @addtogroup SAMPLE_SERVICE
* @{
*/
/** @addtogroup SAMPLE_SERVICE_Exported_Defines
* @{
*/
#define IDB04A1 0
#define IDB05A1 1
/** @brief Macro that stores Value into a buffer in Little Endian Format (2 bytes)*/
#define HOST_TO_LE_16(buf, val) ( ((buf)[0] = (uint8_t) (val) ) , \
((buf)[1] = (uint8_t) (val>>8) ) )
/** @brief Macro that stores Value into a buffer in Little Endian Format (4 bytes) */
#define HOST_TO_LE_32(buf, val) ( ((buf)[0] = (uint8_t) (val) ) , \
((buf)[1] = (uint8_t) (val>>8) ) , \
((buf)[2] = (uint8_t) (val>>16) ) , \
((buf)[3] = (uint8_t) (val>>24) ) )
/**
* @brief Handle of TX Characteristic on the Server. The handle should be
* discovered, but it is fixed only for this demo.
*/
//#define TX_HANDLE 0x0011
/**
* @brief Handle of RX Characteristic on the Client. The handle should be
* discovered, but it is fixed only for this demo.
*/
//#define RX_HANDLE 0x0014
/**
* @}
*/
/** @addtogroup SAMPLE_SERVICE_Exported_Functions
* @{
*/
tBleStatus Add_Sample_Service(void);
void Make_Connection(void);
void receiveData(uint8_t* data_buffer, uint8_t Nb_bytes);
uint32_t extractNum( char* src, uint8_t p );
void receiveDateTime(char* data_buffer);
void driveActuator(char* data_buffer);
void sendData(uint8_t* data_buffer, uint8_t Nb_bytes);
void sendBLEerror( uint16_t errno );
void updateFSM();
void startReadTXCharHandle(void);
void startReadRXCharHandle(void);
void enableNotification(void);
void Attribute_Modified_CB(uint16_t handle, uint8_t data_length,
uint8_t *att_data);
void GAP_ConnectionComplete_CB(uint8_t addr[6], uint16_t handle);
void GAP_DisconnectionComplete_CB(void);
void GATT_Notification_CB(uint16_t attr_handle, uint8_t attr_len,
uint8_t *attr_value);
void user_notify(void * pData);
void readATcommand( uint8_t data_length, uint8_t *att_data );
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* SAMPLE_SERVICE_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,38 @@
/**
******************************************************************************
* File Name Target/ble_list_utils.h
* @author CL
* @version V1.0.0
* @date 12-Oct-2018
* @brief
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef BLE_LIST_UTILS_H
#define BLE_LIST_UTILS_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l4xx_hal.h"
#ifdef __cplusplus
}
#endif
#endif /* BLE_LIST_UTILS_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,95 @@
/**
******************************************************************************
* File Name Target/bluenrg_conf.h
* @author CL
* @version V1.0.0
* @date 05-Mar-2018
* @brief
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef BLUENRG_CONF_H
#define BLUENRG_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l4xx_hal.h"
#include <string.h>
/*---------- Print messages from BLE1 files at user level -----------*/
#define BLE1_DEBUG 1
/*---------- Print the data travelling over the SPI in the .csv format compatible with the ST BlueNRG GUI -----------*/
#define PRINT_CSV_FORMAT 0
/*---------- Number of Bytes reserved for HCI Read Packet -----------*/
#define HCI_READ_PACKET_SIZE 128
/*---------- Number of Bytes reserved for HCI Max Payload -----------*/
#define HCI_MAX_PAYLOAD_SIZE 128
/*---------- Scan Interval: time interval from when the Controller started its last scan until it begins the subsequent scan (for a number N, Time = N x 0.625 msec) -----------*/
#define SCAN_P 16384
/*---------- Scan Window: amount of time for the duration of the LE scan (for a number N, Time = N x 0.625 msec) -----------*/
#define SCAN_L 16384
/*---------- Supervision Timeout for the LE Link (for a number N, Time = N x 10 msec) -----------*/
#define SUPERV_TIMEOUT 60
/*---------- Minimum Connection Period (for a number N, Time = N x 1.25 msec) -----------*/
#define CONN_P1 40
/*---------- Maximum Connection Period (for a number N, Time = N x 1.25 msec) -----------*/
#define CONN_P2 40
/*---------- Minimum Connection Length (for a number N, Time = N x 0.625 msec) -----------*/
#define CONN_L1 2000
/*---------- Maximum Connection Length (for a number N, Time = N x 0.625 msec) -----------*/
#define CONN_L2 2000
/*---------- Advertising Type -----------*/
#define ADV_DATA_TYPE ADV_IND
/*---------- Minimum Advertising Interval (for a number N, Time = N x 0.625 msec) -----------*/
#define ADV_INTERV_MIN 32 //2048
/*---------- Maximum Advertising Interval (for a number N, Time = N x 0.625 msec) -----------*/
#define ADV_INTERV_MAX 4096
/*---------- Minimum Connection Event Interval (for a number N, Time = N x 1.25 msec) -----------*/
#define L2CAP_INTERV_MIN 9
/*---------- Maximum Connection Event Interval (for a number N, Time = N x 1.25 msec) -----------*/
#define L2CAP_INTERV_MAX 20
/*---------- Timeout Multiplier (for a number N, Time = N x 10 msec) -----------*/
#define L2CAP_TIMEOUT_MULTIPLIER 600
/*---------- HCI Default Timeout -----------*/
#define HCI_DEFAULT_TIMEOUT_MS 1000
#define BLUENRG_memcpy memcpy
#define BLUENRG_memset memset
#if (BLE1_DEBUG == 1)
#include <stdio.h>
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...)
#endif
#if PRINT_CSV_FORMAT
#include <stdio.h>
#define PRINT_CSV(...) printf(__VA_ARGS__)
void print_csv_time(void);
#else
#define PRINT_CSV(...)
#endif
#ifdef __cplusplus
}
#endif
#endif /* BLUENRG_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,82 @@
/**
******************************************************************************
* @file : hci_tl_interface.h
* @brief : This file contains all the functions prototypes for the STM32
* BlueNRG HCI Transport Layer interface
******************************************************************************
*
* COPYRIGHT 2021 STMicroelectronics
*
* 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 HCI_TL_INTERFACE_H
#define HCI_TL_INTERFACE_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include <stm32_nucleo_bus.h>
/* Exported Defines ----------------------------------------------------------*/
#define HCI_TL_SPI_EXTI_PORT GPIOB
#define HCI_TL_SPI_EXTI_PIN GPIO_PIN_2
#define HCI_TL_SPI_EXTI_IRQn EXTI2_IRQn
#define HCI_TL_SPI_IRQ_PORT GPIOB
#define HCI_TL_SPI_IRQ_PIN GPIO_PIN_2
#define HCI_TL_SPI_CS_PORT GPIOB
#define HCI_TL_SPI_CS_PIN GPIO_PIN_13
#define HCI_TL_RST_PORT GPIOB
#define HCI_TL_RST_PIN GPIO_PIN_14
/* Exported variables --------------------------------------------------------*/
extern EXTI_HandleTypeDef hexti2;
#define H_EXTI_2 hexti2
/* Exported Functions --------------------------------------------------------*/
int32_t HCI_TL_SPI_Init (void* pConf);
int32_t HCI_TL_SPI_DeInit (void);
int32_t HCI_TL_SPI_Receive (uint8_t* buffer, uint16_t size);
int32_t HCI_TL_SPI_Send (uint8_t* buffer, uint16_t size);
int32_t HCI_TL_SPI_Reset (void);
/**
* @brief Register hci_tl_interface IO bus services
*
* @param None
* @retval None
*/
void hci_tl_lowlevel_init(void);
/**
* @brief HCI Transport Layer Low Level Interrupt Service Routine
*
* @param None
* @retval None
*/
void hci_tl_lowlevel_isr(void);
#ifdef __cplusplus
}
#endif
#endif /* HCI_TL_INTERFACE_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,148 @@
/* USER CODE BEGIN Header */
/*
* FreeRTOS Kernel V10.2.1
* Portion Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
* Portion Copyright (C) 2019 StMicroelectronics, Inc. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/* USER CODE END Header */
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* These parameters and more are described within the 'configuration' section of the
* FreeRTOS API documentation available on the FreeRTOS.org web site.
*
* See http://www.freertos.org/a00110.html
*----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* Section where include file can be added */
/* USER CODE END Includes */
/* Ensure definitions are only used by the compiler, and not by the assembler. */
#if defined(__ICCARM__) || defined(__CC_ARM) || defined(__GNUC__)
#include <stdint.h>
extern uint32_t SystemCoreClock;
#endif
#define configENABLE_FPU 0
#define configENABLE_MPU 0
#define configUSE_PREEMPTION 1
#define configSUPPORT_STATIC_ALLOCATION 0
#define configSUPPORT_DYNAMIC_ALLOCATION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ ( SystemCoreClock )
#define configTICK_RATE_HZ ((TickType_t)1000)
#define configMAX_PRIORITIES ( 7 )
#define configMINIMAL_STACK_SIZE ((uint16_t)128)
#define configTOTAL_HEAP_SIZE ((size_t)65000)
#define configMAX_TASK_NAME_LEN ( 16 )
#define configUSE_16_BIT_TICKS 0
#define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
/* USER CODE BEGIN MESSAGE_BUFFER_LENGTH_TYPE */
/* Defaults to size_t for backward compatibility, but can be changed
if lengths will always be less than the number of bytes in a size_t. */
#define configMESSAGE_BUFFER_LENGTH_TYPE size_t
/* USER CODE END MESSAGE_BUFFER_LENGTH_TYPE */
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
/* Software timer definitions. */
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY ( 6 )
#define configTIMER_QUEUE_LENGTH 10
#define configTIMER_TASK_STACK_DEPTH 256
/* The following flag must be enabled only when using newlib */
#define configUSE_NEWLIB_REENTRANT 1
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
/* Cortex-M specific definitions. */
#ifdef __NVIC_PRIO_BITS
/* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */
#define configPRIO_BITS __NVIC_PRIO_BITS
#else
#define configPRIO_BITS 4
#endif
/* The lowest interrupt priority that can be used in a call to a "set priority"
function. */
#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 15
/* The highest interrupt priority that can be used by any interrupt service
routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL
INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER
PRIORITY THAN THIS! (higher priorities are lower numeric values. */
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
/* Interrupt priorities used by the kernel port layer itself. These are generic
to all Cortex-M ports, and do not rely on any particular library functions. */
#define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */
/* USER CODE BEGIN 1 */
#define configASSERT( x ) if ((x) == 0) {taskDISABLE_INTERRUPTS(); for( ;; );}
/* USER CODE END 1 */
/* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS
standard names. */
#define vPortSVCHandler SVC_Handler
#define xPortPendSVHandler PendSV_Handler
/* IMPORTANT: This define is commented when used with STM32Cube firmware, when the timebase source is SysTick,
to prevent overwriting SysTick_Handler defined within STM32Cube HAL */
#define xPortSysTickHandler SysTick_Handler
/* USER CODE BEGIN Defines */
/* Section where parameter definitions can be added (for instance, to override default ones in FreeRTOS.h) */
/* USER CODE END Defines */
#endif /* FREERTOS_CONFIG_H */

View File

@@ -0,0 +1,98 @@
/*!
* @file CayenneLpp.h
*
* @brief Implements the Cayenne Low Power Protocol
*
* @copyright Revised BSD License, see section \ref LICENSE.
*
* @code
* ______ _
* / _____) _ | |
* ( (____ _____ ____ _| |_ _____ ____| |__
* \____ \| ___ | (_ _) ___ |/ ___) _ \
* _____) ) ____| | | || |_| ____( (___| | | |
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
* (C)2013-2018 Semtech
*
* @endcode
*
* @author Miguel Luis ( Semtech )
*/
#ifndef __CAYENNE_LPP_H__
#define __CAYENNE_LPP_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include <stdint.h>
/* 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 */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void CayenneLppInit(void);
void CayenneLppReset(void);
uint8_t CayenneLppGetSize(void);
uint8_t *CayenneLppGetBuffer(void);
uint8_t CayenneLppCopy(uint8_t *buffer);
uint8_t CayenneLppAddDigitalInput(uint8_t channel, uint8_t value);
uint8_t CayenneLppAddDigitalOutput(uint8_t channel, uint8_t value);
uint8_t CayenneLppAddAnalogInput(uint8_t channel, float value);
uint8_t CayenneLppAddAnalogOutput(uint8_t channel, uint16_t value);
uint8_t CayenneLppAddLuminosity(uint8_t channel, uint16_t lux);
uint8_t CayenneLppAddPresence(uint8_t channel, uint8_t value);
uint8_t CayenneLppAddTemperature(uint8_t channel, int16_t celsius);
uint8_t CayenneLppAddRelativeHumidity(uint8_t channel, uint16_t rh);
uint8_t CayenneLppAddAccelerometer(uint8_t channel, int16_t x, int16_t y, int16_t z);
uint8_t CayenneLppAddBarometricPressure(uint8_t channel, uint16_t hpa);
uint8_t CayenneLppAddGyrometer(uint8_t channel, int16_t x, int16_t y, int16_t z);
uint8_t CayenneLppAddGps(uint8_t channel, int32_t latitude, int32_t longitude, int32_t meters);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __CAYENNE_LPP_H__ */

View File

@@ -0,0 +1,82 @@
/*!
* \file Commissioning.h
*
* \brief End-device commissioning parameters
*
* \copyright Revised BSD License, see section \ref LICENSE.
*
* \code
* ______ _
* / _____) _ | |
* ( (____ _____ ____ _| |_ _____ ____| |__
* \____ \| ___ | (_ _) ___ |/ ___) _ \
* _____) ) ____| | | || |_| ____( (___| | | |
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
* (C)2013-2020 Semtech
*
* \endcode
*/
/**
******************************************************************************
*
* Portions COPYRIGHT 2020 STMicroelectronics
*
* @file Commissioning.h
* @author MCD Application Team
* @brief End-device commissioning parameters
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __COMMISSIONING_H__
#define __COMMISSIONING_H__
/*!
******************************************************************************
********************************** WARNING ***********************************
******************************************************************************
The LoRaWAN AES128 keys are stored and provisioned on secure-elements.
This project provides a software emulated secure-element.
The LoRaWAN AES128 keys SHALL be updated under
src/peripherals/<secure-element name>-se\se-identity.h file.
******************************************************************************
******************************************************************************
******************************************************************************
*/
#include "se-identity.h"
/* USER CODE BEGIN EC1 */
/* USER CODE END EC1 */
/*!
* When using ABP activation the MAC layer must know in advance to which server
* version it will be connected.
*/
#define ABP_ACTIVATION_LRWAN_VERSION_V10x 0x01000300 /* 1.0.3.0 */
#define ABP_ACTIVATION_LRWAN_VERSION ABP_ACTIVATION_LRWAN_VERSION_V10x
/*!
* Indicates if the end-device support the operation with repeaters
*/
#define LORAWAN_REPEATER_SUPPORT false
/*!
* Indicates if the end-device is to be connected to a private or public network
*/
#define LORAWAN_PUBLIC_NETWORK true
/*!
* Current network ID
*/
#define LORAWAN_NETWORK_ID ( uint32_t )0
/* USER CODE BEGIN EC2 */
/* USER CODE END EC2 */
#endif /* __COMMISSIONING_H__ */

View File

@@ -0,0 +1,76 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file app_lorawan.h
* @author MCD Application Team
* @brief Header of application of the LRWAN Middleware
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __APP_LORAWAN_H__
#define __APP_LORAWAN_H__
#ifdef __cplusplus
extern "C" {
#endif
/* 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 */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported Functions Prototypes------------------------------------------------------- */
/**
* @brief Init Lora Application
*/
void MX_LoRaWAN_Init(void);
/**
* @brief Entry Lora Process or scheduling
*/
void MX_LoRaWAN_Process(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /*__APP_LORAWAN_H__*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,133 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file lora_app.h
* @author MCD Application Team
* @brief Header of application of the LRWAN Middleware
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __LORA_APP_H__
#define __LORA_APP_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* LoraWAN application configuration (Mw is configured by lorawan_conf.h) */
#define ACTIVE_REGION LORAMAC_REGION_EU868
/*!
* CAYENNE_LPP is myDevices Application server.
*/
#define CAYENNE_LPP
/*!
* Defines the application data transmission duty cycle. 60s, value in [ms].
*/
#define APP_TX_DUTYCYCLE 60000
/*!
* LoRaWAN User application port
* @note do not use 224. It is reserved for certification
*/
#define LORAWAN_USER_APP_PORT 2
/*!
* LoRaWAN Switch class application port
* @note do not use 224. It is reserved for certification
*/
#define LORAWAN_SWITCH_CLASS_PORT 3
/*!
* LoRaWAN default endNode class port
*/
#define LORAWAN_DEFAULT_CLASS CLASS_B
/*!
* LoRaWAN default confirm state
*/
#define LORAWAN_DEFAULT_CONFIRMED_MSG_STATE LORAMAC_HANDLER_UNCONFIRMED_MSG
/*!
* LoRaWAN Adaptive Data Rate
* @note Please note that when ADR is enabled the end-device should be static
*/
#define LORAWAN_ADR_STATE LORAMAC_HANDLER_ADR_ON
/*!
* LoRaWAN Default data Rate Data Rate
* @note Please note that LORAWAN_DEFAULT_DATA_RATE is used only when LORAWAN_ADR_STATE is disabled
*/
#define LORAWAN_DEFAULT_DATA_RATE DR_0
/*!
* LoRaWAN default activation type
*/
#define LORAWAN_DEFAULT_ACTIVATION_TYPE ACTIVATION_TYPE_OTAA
//#define LORAWAN_DEFAULT_ACTIVATION_TYPE ACTIVATION_TYPE_ABP
/*!
* User application data buffer size
*/
#define LORAWAN_APP_DATA_BUFFER_MAX_SIZE 242
/*!
* Default Unicast ping slots periodicity
*
* \remark periodicity is equal to 2^LORAWAN_DEFAULT_PING_SLOT_PERIODICITY seconds
* example: 2^3 = 8 seconds. The end-device will open an Rx slot every 8 seconds.
*/
#define LORAWAN_DEFAULT_PING_SLOT_PERIODICITY 4
/* USER CODE BEGIN EC */
enum { LED_BLUE, LED_RED1, LED_RED2 };
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/**
* @brief Init Lora Application
*/
void LoRaWAN_Init(void);
void LoRaWAN_Sleep(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /*__LORA_APP_H__*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,90 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file lora_app_version.h
* @author MCD Application Team
* @brief Definition the version of the application
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __APP_VERSION_H__
#define __APP_VERSION_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
#define __APP_VERSION_MAIN (0x01U) /*!< [31:24] main version */
#define __APP_VERSION_SUB1 (0x01U) /*!< [23:16] sub1 version */
#define __APP_VERSION_SUB2 (0x00U) /*!< [15:8] sub2 version */
#define __APP_VERSION_RC (0x00U) /*!< [7:0] release candidate */
#define __APP_VERSION_MAIN_SHIFT 24 /*!< main byte shift */
#define __APP_VERSION_SUB1_SHIFT 16 /*!< sub1 byte shift */
#define __APP_VERSION_SUB2_SHIFT 8 /*!< sub2 byte shift */
#define __APP_VERSION_RC_SHIFT 0 /*!< release candidate byte shift */
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macros -----------------------------------------------------------*/
/**
* @brief Application version
*/
#define __APP_VERSION ((__APP_VERSION_MAIN << __APP_VERSION_MAIN_SHIFT)\
|(__APP_VERSION_SUB1 << __APP_VERSION_SUB1_SHIFT)\
|(__APP_VERSION_SUB2 << __APP_VERSION_SUB2_SHIFT)\
|(__APP_VERSION_RC << __APP_VERSION_RC_SHIFT))
/**
* @brief LoRaWAN application version
*/
#define __LORA_APP_VERSION __APP_VERSION
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /*__APP_VERSION_H__*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,94 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file lora_info.h
* @author MCD Application Team
* @brief To give info to the application about LoRaWAN configuration
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
#ifndef __LORA_INFO_H__
#define __LORA_INFO_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include <stdint.h>
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported types ------------------------------------------------------------*/
/*!
* To give info to the application about LoraWAN capability
* it can depend how it has been compiled (e.g. compiled regions ...)
* Params should be better uint32_t foe easier alignment with info_table concept
*/
typedef struct
{
uint32_t ActivationMode; /*!< 1: ABP, 2 : OTAA, 3: ABP & OTAA */
uint32_t Region; /*!< Combination of regions compiled on MW */
uint32_t ClassB; /*!< 0: not compiled in Mw, 1 : compiled in MW */
uint32_t Kms; /*!< 0: not compiled in Mw, 1 : compiled in MW */
} LoraInfo_t;
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macros -----------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions ------------------------------------------------------- */
/**
* @brief initialize the LoraInfo table
*/
void LoraInfo_Init(void);
/**
* @brief returns the pointer to the LoraInfo capabilities table
* @retval LoraInfo pointer
*/
LoraInfo_t *LoraInfo_GetPtr(void);
/* USER CODE BEGIN EF */
/* USER CODE END EF */
#ifdef __cplusplus
}
#endif
#endif /* __LORA_INFO_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,398 @@
/*!
* \file se-identity.h
*
* \brief Secure Element identity and keys
*
* \copyright Revised BSD License, see section \ref LICENSE.
*
* \code
* ______ _
* / _____) _ | |
* ( (____ _____ ____ _| |_ _____ ____| |__
* \____ \| ___ | (_ _) ___ |/ ___) _ \
* _____) ) ____| | | || |_| ____( (___| | | |
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
* (C)2020 Semtech
*
* ___ _____ _ ___ _ _____ ___ ___ ___ ___
* / __|_ _/_\ / __| |/ / __/ _ \| _ \/ __| __|
* \__ \ | |/ _ \ (__| ' <| _| (_) | / (__| _|
* |___/ |_/_/ \_\___|_|\_\_| \___/|_|_\\___|___|
* embedded.connectivity.solutions===============
*
* \endcode
*
*/
/**
******************************************************************************
*
* Portions COPYRIGHT 2020 STMicroelectronics
*
* @file se-identity.h
* @author MCD Application Team
* @brief Secure Element identity and keys
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SOFT_SE_IDENTITY_H__
#define __SOFT_SE_IDENTITY_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Exported Includes --------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/*!
******************************************************************************
********************************** WARNING ***********************************
******************************************************************************
The secure-element implementation supports both 1.0.x and 1.1.x LoRaWAN
versions of the specification.
Thus it has been decided to use the 1.1.x keys and EUI name definitions.
The below table shows the names equivalence between versions:
+---------------------+-------------------------+
| 1.0.x | 1.1.x |
+=====================+=========================+
| LORAWAN_DEVICE_EUI | LORAWAN_DEVICE_EUI |
+---------------------+-------------------------+
| LORAWAN_APP_EUI | LORAWAN_JOIN_EUI |
+---------------------+-------------------------+
| LORAWAN_GEN_APP_KEY | LORAWAN_APP_KEY |
+---------------------+-------------------------+
| LORAWAN_APP_KEY | LORAWAN_NWK_KEY |
+---------------------+-------------------------+
| LORAWAN_NWK_S_KEY | LORAWAN_F_NWK_S_INT_KEY |
+---------------------+-------------------------+
| LORAWAN_NWK_S_KEY | LORAWAN_S_NWK_S_INT_KEY |
+---------------------+-------------------------+
| LORAWAN_NWK_S_KEY | LORAWAN_NWK_S_ENC_KEY |
+---------------------+-------------------------+
| LORAWAN_APP_S_KEY | LORAWAN_APP_S_KEY |
+---------------------+-------------------------+
******************************************************************************
******************************************************************************
******************************************************************************
*/
/*!
* When set to 1 DevEui is LORAWAN_DEVICE_EUI
* When set to 0 DevEui is automatically set with a value provided by MCU platform
*/
#define STATIC_DEVICE_EUI 1
/*!
* end-device IEEE EUI (big endian)
*/
#define LORAWAN_DEVICE_EUI { 0x12, 0x50, 0x4B, 0x42, 0xB1, 0x37, 0x79, 0x20 }
/*!
* App/Join server IEEE EUI (big endian)
*/
#define LORAWAN_JOIN_EUI { 0xC3, 0x76, 0xEF, 0x9A, 0xA9, 0xDF, 0x9E, 0xDC } //{ 0x70, 0xB3, 0xD5, 0x7E, 0xD0, 0x02, 0x23, 0x64 }
/*!
* When set to 1 DevAddr is LORAWAN_DEVICE_ADDRESS
* When set to 0 DevAddr is automatically set with a value provided by a pseudo
* random generator seeded with a value provided by the MCU platform
*/
#define STATIC_DEVICE_ADDRESS 0
/*!
* Device address on the network (big endian)
*/
#define LORAWAN_DEVICE_ADDRESS ( uint32_t )0x0100000A
/*!
* Application root key
*/
#define LORAWAN_APP_KEY 2B,7E,15,16,28,AE,D2,A6,AB,F7,15,88,09,CF,4F,3C
/*!
* Network root key
*/
#define LORAWAN_NWK_KEY 2B,7E,15,16,28,AE,D2,A6,AB,F7,15,88,09,CF,4F,3C
/*!
* Forwarding Network session key
*/
#define LORAWAN_NWK_S_KEY 2B,7E,15,16,28,AE,D2,A6,AB,F7,15,88,09,CF,4F,3C
/*!
* Application session key
*/
#define LORAWAN_APP_S_KEY 2B,7E,15,16,28,AE,D2,A6,AB,F7,15,88,09,CF,4F,3C
/*!
* Format commissioning keys
*/
#define RAW_TO_INT8A(a,b,c,d,e,f,g,h,i,j,k,l,m,n,o,p) {0x##a,0x##b,0x##c,0x##d,\
0x##e,0x##f,0x##g,0x##h,\
0x##i,0x##j,0x##k,0x##l,\
0x##m,0x##n,0x##o,0x##p}
#define FORMAT_KEY(...) RAW_TO_INT8A(__VA_ARGS__)
#if (USE_LRWAN_1_1_X_CRYPTO == 1)
#define SESSION_KEYS_LIST \
{ \
/*! \
* Join session integrity key (Dynamically updated) \
* WARNING: NOT USED FOR 1.0.x DEVICES \
*/ \
.KeyID = J_S_INT_KEY, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Join session encryption key (Dynamically updated) \
* WARNING: NOT USED FOR 1.0.x DEVICES \
*/ \
.KeyID = J_S_ENC_KEY, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Forwarding Network session integrity key \
* WARNING: NWK_S_KEY FOR 1.0.x DEVICES \
*/ \
.KeyID = F_NWK_S_INT_KEY, \
.KeyValue = FORMAT_KEY(LORAWAN_NWK_S_KEY), \
}, \
{ \
/*! \
* Serving Network session integrity key \
* WARNING: NOT USED FOR 1.0.x DEVICES. MUST BE THE SAME AS \ref LORAWAN_F_NWK_S_INT_KEY \
*/ \
.KeyID = S_NWK_S_INT_KEY, \
.KeyValue = { 0x2B, 0x7E, 0x15, 0x16, 0x28, 0xAE, 0xD2, 0xA6, 0xAB, 0xF7, 0x15, 0x88, 0x09, 0xCF, 0x4F, \
0x3C }, \
}, \
{ \
/*! \
* Network session encryption key \
* WARNING: NOT USED FOR 1.0.x DEVICES. MUST BE THE SAME AS \ref LORAWAN_F_NWK_S_INT_KEY \
*/ \
.KeyID = NWK_S_ENC_KEY, \
.KeyValue = { 0x2B, 0x7E, 0x15, 0x16, 0x28, 0xAE, 0xD2, 0xA6, 0xAB, 0xF7, 0x15, 0x88, 0x09, 0xCF, 0x4F, \
0x3C }, \
}, \
{ \
/*! \
* Application session key \
*/ \
.KeyID = APP_S_KEY, \
.KeyValue = FORMAT_KEY(LORAWAN_APP_S_KEY), \
},
#else /* USE_LRWAN_1_1_X_CRYPTO == 0 */
#define SESSION_KEYS_LIST \
{ \
/*! \
* Network session key \
*/ \
.KeyID = NWK_S_KEY, \
.KeyValue = FORMAT_KEY(LORAWAN_NWK_S_KEY), \
}, \
{ \
/*! \
* Application session key \
*/ \
.KeyID = APP_S_KEY, \
.KeyValue = FORMAT_KEY(LORAWAN_APP_S_KEY), \
},
#endif /* USE_LRWAN_1_1_X_CRYPTO */
#if (LORAMAC_MAX_MC_CTX == 1)
#define SESSION_MC_KEYS_LIST \
{ \
/*! \
* Multicast group #0 root key (Dynamically updated) \
*/ \
.KeyID = MC_KEY_0, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #0 application session key (Dynamically updated) \
*/ \
.KeyID = MC_APP_S_KEY_0, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #0 network session key (Dynamically updated) \
*/ \
.KeyID = MC_NWK_S_KEY_0, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
},
#else /* LORAMAC_MAX_MC_CTX > 1 */
#define SESSION_MC_KEYS_LIST \
{ \
/*! \
* Multicast group #0 root key (Dynamically updated) \
*/ \
.KeyID = MC_KEY_0, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #0 application session key (Dynamically updated) \
*/ \
.KeyID = MC_APP_S_KEY_0, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #0 network session key (Dynamically updated) \
*/ \
.KeyID = MC_NWK_S_KEY_0, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #1 root key (Dynamically updated) \
*/ \
.KeyID = MC_KEY_1, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #1 application session key (Dynamically updated) \
*/ \
.KeyID = MC_APP_S_KEY_1, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #1 network session key (Dynamically updated) \
*/ \
.KeyID = MC_NWK_S_KEY_1, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #2 root key (Dynamically updated) \
*/ \
.KeyID = MC_KEY_2, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #2 application session key (Dynamically updated) \
*/ \
.KeyID = MC_APP_S_KEY_2, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #2 network session key (Dynamically updated) \
*/ \
.KeyID = MC_NWK_S_KEY_2, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #3 root key (Dynamically updated) \
*/ \
.KeyID = MC_KEY_3, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #3 application session key (Dynamically updated) \
*/ \
.KeyID = MC_APP_S_KEY_3, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast group #3 network session key (Dynamically updated) \
*/ \
.KeyID = MC_NWK_S_KEY_3, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
},
#endif /* LORAMAC_MAX_MC_CTX */
#define SOFT_SE_KEY_LIST \
{ \
{ \
/*! \
* Application root key \
* WARNING: FOR 1.0.x DEVICES IT IS THE \ref LORAWAN_GEN_APP_KEY \
*/ \
.KeyID = APP_KEY, \
.KeyValue = FORMAT_KEY(LORAWAN_APP_KEY), \
}, \
{ \
/*! \
* Network root key \
* WARNING: FOR 1.0.x DEVICES IT IS THE \ref LORAWAN_APP_KEY \
*/ \
.KeyID = NWK_KEY, \
.KeyValue = FORMAT_KEY(LORAWAN_NWK_KEY), \
}, \
SESSION_KEYS_LIST \
{ \
/*! \
* Multicast root key (Dynamically updated) \
*/ \
.KeyID = MC_ROOT_KEY, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
{ \
/*! \
* Multicast key encryption key (Dynamically updated) \
*/ \
.KeyID = MC_KE_KEY, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
SESSION_MC_KEYS_LIST \
{ \
/*! \
* All zeros key. (ClassB usage)(constant) \
*/ \
.KeyID = SLOT_RAND_ZERO_KEY, \
.KeyValue = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, \
0x00 }, \
}, \
}
/* USER CODE BEGIN EC */
/* USER CODE END EC */
#ifdef __cplusplus
}
#endif
#endif /* __SOFT_SE_IDENTITY_H__ */

View File

@@ -0,0 +1,192 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file frag_decoder_if.h
* @author MCD Application Team
* @brief Applicative interfaces of LoRa-Alliance fragmentation decoder
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __FRAG_DECODER_IF_H__
#define __FRAG_DECODER_IF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "LmhpFragmentation.h"
/* USER CODE BEGIN include */
/* USER CODE END include */
/* Exported defines ----------------------------------------------------------*/
/*!
* Within this mode we define the fragment number and the fragment size applicable
* for the interop test and final CRC computation on the received interop file.
*/
#define INTEROP_TEST_MODE 0
/*!
* Caching mode allows to put in RAM the received FW file. Afterwaht, the FW file is
* copied from RAM to FLAH
* SFU_HEADER & FW code will be copied at the rigth place in Flash
*/
#define CACHING_MODE 1
#if (INTEROP_TEST_MODE == 1)
/*!
* Maximum number of fragment that can be handled.
*
* \remark This parameter has an impact on the memory footprint.
*/
#define FRAG_MAX_NB 21
/*!
* Maximum fragment size that can be handled.
*
* \remark This parameter has an impact on the memory footprint.
*/
#define FRAG_MAX_SIZE 48
/*!
* Maximum number of extra frames that can be handled.
*
* \remark This parameter has an impact on the memory footprint.
*/
#define FRAG_MAX_REDUNDANCY 5
#else /* INTEROP_TEST_MODE == 0 */
/*!
* Maximum number of fragment that can be handled.
*
* \remark This parameter has an impact on the memory footprint.
* \note FRAG_MAX_NB = (SLOT_DWL_1_END - SLOT_DWL_1_START) / FRAG_MAX_SIZE
*/
#define FRAG_MAX_NB 1382 /* for DR2*/ /*350*/ /* for DR7-DR4*/ /*313*/
/*!
* Maximum fragment size that can be handled.
*
* \remark This parameter has an impact on the memory footprint.
*/
#define FRAG_MAX_SIZE 48 /* for DR2*/ /*219*/ /* for DR7-DR4*/ /*120*/
/*!
* Maximum number of extra frames that can be handled.
*
* \remark This parameter has an impact on the memory footprint.
* \note FRAG_MAX_NB * 0.10 (with redundancy = 10 %)
*/
#define FRAG_MAX_REDUNDANCY 100 /* for DR2*/ /*40*/ /* for DR7 - DR4*/ /*72*/
#endif /* INTEROP_TEST_MODE */
#define FRAG_DECODER_SWAP_REGION_START ((uint32_t)(SlotStartAdd[SLOT_SWAP]))
#define FRAG_DECODER_SWAP_REGION_SIZE ((uint32_t)(SlotEndAdd[SLOT_SWAP] - SlotStartAdd[SLOT_SWAP] + 1U))
#define FRAG_DECODER_DWL_REGION_START ((uint32_t)(SlotStartAdd[SLOT_DWL_1]))
#define FRAG_DECODER_DWL_REGION_SIZE ((uint32_t)(SlotEndAdd[SLOT_DWL_1] - SlotStartAdd[SLOT_DWL_1] + 1U))
/* USER CODE BEGIN ED */
/* USER CODE END ED */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
extern const LmhpFragmentationParams_t FRAG_DECODER_IF_FragmentationParams;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions ------------------------------------------------------- */
/**
* Initialize final uncoded data buffer
*
* \retval status Write operation status [0: Success, -1 Fail]
*/
int32_t FRAG_DECODER_IF_Erase(void);
/**
* Writes `data` buffer of `size` starting at address `addr`
*
* \param [IN] addr Address start index to write to.
* \param [IN] data Data buffer to be written.
* \param [IN] size Size of data buffer to be written.
*
* \retval status Write operation status [0: Success, -1 Fail]
*/
int32_t FRAG_DECODER_IF_Write(uint32_t addr, uint8_t *data, uint32_t size);
/**
* Reads `data` buffer of `size` starting at address `addr`
*
* \param [IN] addr Address start index to read from.
* \param [IN] data Data buffer to be read.
* \param [IN] size Size of data buffer to be read.
*
* \retval status Read operation status [0: Success, -1 Fail]
*/
int32_t FRAG_DECODER_IF_Read(uint32_t addr, uint8_t *data, uint32_t size);
/**
* Notifies the progress of the current fragmentation session
*
* \param [IN] fragCounter Fragment counter
* \param [IN] fragNb Number of fragments
* \param [IN] fragSize Size of fragments
* \param [IN] fragNbLost Number of lost fragments
*/
void FRAG_DECODER_IF_OnProgress(uint16_t fragCounter, uint16_t fragNb, uint8_t fragSize, uint16_t fragNbLost);
/**
* Notifies that the fragmentation session is finished
*
* \param [IN] status Fragmentation session status [FRAG_SESSION_ONGOING,
* FRAG_SESSION_FINISHED or
* FragDecoder.Status.FragNbLost]
* \param [IN] size Received file size
*/
void FRAG_DECODER_IF_OnDone(int32_t status, uint32_t size);
#ifdef __cplusplus
}
#endif
#endif /* __FRAG_DECODER_IF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,132 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file lorawan_conf.h
* @author MCD Application Team
* @brief Header for LoRaWAN middleware instances
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __LORAWAN_CONF_H__
#define __LORAWAN_CONF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* Region ------------------------------------*/
/* the region listed here will be linked in the MW code */
/* the application (on sys_conf.h) shall just configure one region at the time */
/*#define REGION_AS923*/
/*#define REGION_AU915*/
/*#define REGION_CN470*/
/*#define REGION_CN779*/
/*#define REGION_EU433*/
#define REGION_EU868
/*#define REGION_KR920*/
/*#define REGION_IN865*/
/*#define REGION_US915*/
/*#define REGION_RU864*/
/**
* \brief Limits the number usable channels by default for AU915, CN470 and US915 regions
* \note the default channel mask with this option activates the first 8 channels. \
* this default mask can be modified in the RegionXXXXXInitDefaults function associated with the active region.
*/
#define HYBRID_ENABLED 0
/**
* \brief Define the read access of the keys in memory
* \note this value should be disabled after the development process
*/
#define KEY_EXTRACTABLE 1
/*!
* Enables/Disables the context storage management storage.
* Must be enabled for LoRaWAN 1.0.4 or later.
*/
#define CONTEXT_MANAGEMENT_ENABLED 0
/* Class B ------------------------------------*/
#define LORAMAC_CLASSB_ENABLED 0
#if ( LORAMAC_CLASSB_ENABLED == 1 )
/* CLASS B LSE crystal calibration*/
/**
* \brief Temperature coefficient of the clock source
*/
#define RTC_TEMP_COEFFICIENT ( -0.035 )
/**
* \brief Temperature coefficient deviation of the clock source
*/
#define RTC_TEMP_DEV_COEFFICIENT ( 0.0035 )
/**
* \brief Turnover temperature of the clock source
*/
#define RTC_TEMP_TURNOVER ( 25.0 )
/**
* \brief Turnover temperature deviation of the clock source
*/
#define RTC_TEMP_DEV_TURNOVER ( 5.0 )
#endif /* LORAMAC_CLASSB_ENABLED == 1 */
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
#ifndef CRITICAL_SECTION_BEGIN
#define CRITICAL_SECTION_BEGIN( ) UTILS_ENTER_CRITICAL_SECTION( )
#endif /* !CRITICAL_SECTION_BEGIN */
#ifndef CRITICAL_SECTION_END
#define CRITICAL_SECTION_END( ) UTILS_EXIT_CRITICAL_SECTION( )
#endif /* !CRITICAL_SECTION_END */
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __LORAWAN_CONF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,75 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file mw_log_conf.h
* @author MCD Application Team
* @brief Configure (enable/disable) traces
*******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MW_LOG_CONF_H__
#define __MW_LOG_CONF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "../../Utils/Inc/stm32_adv_trace.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
#define MW_LOG_ENABLED
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
#ifdef MW_LOG_ENABLED
#define MW_LOG(TS,VL, ...) do{ {UTIL_ADV_TRACE_COND_FSend(VL, T_REG_OFF, TS, __VA_ARGS__);} }while(0)
#else /* MW_LOG_ENABLED */
#define MW_LOG(TS,VL, ...)
#endif /* MW_LOG_ENABLED */
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /*__MW_LOG_CONF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,205 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file radio_board_if.h
* @author MCD Application Team
* @brief Header for Radio interface configuration
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef RADIO_BOARD_IF_H
#define RADIO_BOARD_IF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#ifdef SX1276MB1LAS
#include "sx1276mb1las.h"
#define Sx_Board_IoInit SX1276MB1LAS_RADIO_IoInit
#define Sx_Board_IoDeInit SX1276MB1LAS_RADIO_IoDeInit
#define Sx_Board_IoIrqInit SX1276MB1LAS_RADIO_IoIrqInit
#define Sx_Board_SendRecv SX1276MB1LAS_RADIO_SendRecv
#define Sx_Board_ChipSelect SX1276MB1LAS_RADIO_ChipSelect
#define Sx_Board_CheckRfFrequency SX1276MB1LAS_RADIO_CheckRfFrequency
#define Sx_Board_Reset SX1276MB1LAS_RADIO_Reset
#define Sx_Board_SetXO SX1276MB1LAS_RADIO_SetXO
#define Sx_Board_GetWakeUpTime SX1276MB1LAS_RADIO_GetWakeUpTime
#define Sx_Board_GetPaSelect SX1276MB1LAS_RADIO_GetPaSelect
#define Sx_Board_SetAntSw SX1276MB1LAS_RADIO_SetAntSw
#define Sx_Board_Bus_Init SX1276MB1LAS_RADIO_Bus_Init
#define Sx_Board_Bus_deInit SX1276MB1LAS_RADIO_Bus_deInit
#define Sx_Board_GetDio1PinState SX1276MB1LAS_RADIO_GetDio1PinState
#elif SX1276MB1MAS
#include "../../Drivers/BSP/sx1276mb1mas/sx1276mb1mas.h"
#define Sx_Board_IoInit SX1276MB1MAS_RADIO_IoInit
#define Sx_Board_IoDeInit SX1276MB1MAS_RADIO_IoDeInit
#define Sx_Board_IoIrqInit SX1276MB1MAS_RADIO_IoIrqInit
#define Sx_Board_SendRecv SX1276MB1MAS_RADIO_SendRecv
#define Sx_Board_ChipSelect SX1276MB1MAS_RADIO_ChipSelect
#define Sx_Board_CheckRfFrequency SX1276MB1MAS_RADIO_CheckRfFrequency
#define Sx_Board_Reset SX1276MB1MAS_RADIO_Reset
#define Sx_Board_SetXO SX1276MB1MAS_RADIO_SetXO
#define Sx_Board_GetWakeUpTime SX1276MB1MAS_RADIO_GetWakeUpTime
#define Sx_Board_GetPaSelect SX1276MB1MAS_RADIO_GetPaSelect
#define Sx_Board_SetAntSw SX1276MB1MAS_RADIO_SetAntSw
#define Sx_Board_Bus_Init SX1276MB1MAS_RADIO_Bus_Init
#define Sx_Board_Bus_deInit SX1276MB1MAS_RADIO_Bus_deInit
#define Sx_Board_GetDio1PinState SX1276MB1MAS_RADIO_GetDio1PinState
#elif CMWX1ZZABZ0XX
#include "cmwx1zzabz_0xx.h"
#define Sx_Board_IoInit CMWX1ZZABZ0XX_RADIO_IoInit
#define Sx_Board_IoDeInit CMWX1ZZABZ0XX_RADIO_IoDeInit
#define Sx_Board_IoIrqInit CMWX1ZZABZ0XX_RADIO_IoIrqInit
#define Sx_Board_SendRecv CMWX1ZZABZ0XX_RADIO_SendRecv
#define Sx_Board_ChipSelect CMWX1ZZABZ0XX_RADIO_ChipSelect
#define Sx_Board_CheckRfFrequency CMWX1ZZABZ0XX_RADIO_CheckRfFrequency
#define Sx_Board_Reset CMWX1ZZABZ0XX_RADIO_Reset
#define Sx_Board_SetXO CMWX1ZZABZ0XX_RADIO_SetXO
#define Sx_Board_GetWakeUpTime CMWX1ZZABZ0XX_RADIO_GetWakeUpTime
#define Sx_Board_GetPaSelect CMWX1ZZABZ0XX_RADIO_GetPaSelect
#define Sx_Board_SetAntSw CMWX1ZZABZ0XX_RADIO_SetAntSw
#define Sx_Board_Bus_Init CMWX1ZZABZ0XX_RADIO_Bus_Init
#define Sx_Board_Bus_deInit CMWX1ZZABZ0XX_RADIO_Bus_deInit
#define Sx_Board_GetDio1PinState CMWX1ZZABZ0XX_RADIO_GetDio1PinState
#elif SX1272MB2DAS
#include "../../Drivers/BSP/sx1272mb2das/sx1272mb2das.h"
#define Sx_Board_IoInit SX1272MB2DAS_RADIO_IoInit
#define Sx_Board_IoDeInit SX1272MB2DAS_RADIO_IoDeInit
#define Sx_Board_IoIrqInit SX1272MB2DAS_RADIO_IoIrqInit
#define Sx_Board_SendRecv SX1272MB2DAS_RADIO_SendRecv
#define Sx_Board_ChipSelect SX1272MB2DAS_RADIO_ChipSelect
#define Sx_Board_CheckRfFrequency SX1272MB2DAS_RADIO_CheckRfFrequency
#define Sx_Board_Reset SX1272MB2DAS_RADIO_Reset
#define Sx_Board_SetXO SX1272MB2DAS_RADIO_SetXO
#define Sx_Board_GetWakeUpTime SX1272MB2DAS_RADIO_GetWakeUpTime
#define Sx_Board_GetPaSelect SX1272MB2DAS_RADIO_GetPaSelect
#define Sx_Board_SetAntSw SX1272MB2DAS_RADIO_SetAntSw
#define Sx_Board_Bus_Init SX1272MB2DAS_RADIO_Bus_Init
#define Sx_Board_Bus_deInit SX1272MB2DAS_RADIO_Bus_deInit
#define Sx_Board_GetDio1PinState SX1272MB2DAS_RADIO_GetDio1PinState
#elif SX1262DVK1DAS
#include "sx1262dvk1das.h"
#define Sx_Board_IoInit SX1262DVK1DAS_RADIO_IoInit
#define Sx_Board_IoDeInit SX1262DVK1DAS_RADIO_IoDeInit
#define Sx_Board_IoIrqInit SX1262DVK1DAS_RADIO_IoIrqInit
#define Sx_Board_SendRecv SX1262DVK1DAS_RADIO_SendRecv
#define Sx_Board_ChipSelect SX1262DVK1DAS_RADIO_ChipSelect
#define Sx_Board_CheckRfFrequency SX1262DVK1DAS_RADIO_CheckRfFrequency
#define Sx_Board_Reset SX1262DVK1DAS_RADIO_Reset
#define Sx_Board_SetXO SX1262DVK1DAS_RADIO_SetXO
#define Sx_Board_GetWakeUpTime SX1262DVK1DAS_RADIO_GetWakeUpTime
#define Sx_Board_GetPaSelect SX1262DVK1DAS_RADIO_GetPaSelect
#define Sx_Board_SetAntSw SX1262DVK1DAS_RADIO_SetAntSw
#define Sx_Board_Bus_Init SX1262DVK1DAS_RADIO_Bus_Init
#define Sx_Board_Bus_deInit SX1262DVK1DAS_RADIO_Bus_deInit
#define Sx_Board_WaitOnBusy SX1262DVK1DAS_RADIO_WaitOnBusy
#define Sx_Board_WakeUp SX1262DVK1DAS_RADIO_WakeUp
#define Sx_Board_IsTcxo SX1262DVK1DAS_RADIO_BoardIsTcxo
#define Sx_Board_SetLedRx SX1262DVK1DAS_RADIO_BoardSetLedRx
#define Sx_Board_SetLedTx SX1262DVK1DAS_RADIO_BoardSetLedTx
#elif SX1262DVK1CAS
#include "sx1262dvk1cas.h"
#define Sx_Board_IoInit SX1262DVK1CAS_RADIO_IoInit
#define Sx_Board_IoDeInit SX1262DVK1CAS_RADIO_IoDeInit
#define Sx_Board_IoIrqInit SX1262DVK1CAS_RADIO_IoIrqInit
#define Sx_Board_SendRecv SX1262DVK1CAS_RADIO_SendRecv
#define Sx_Board_ChipSelect SX1262DVK1CAS_RADIO_ChipSelect
#define Sx_Board_CheckRfFrequency SX1262DVK1CAS_RADIO_CheckRfFrequency
#define Sx_Board_Reset SX1262DVK1CAS_RADIO_Reset
#define Sx_Board_SetXO SX1262DVK1CAS_RADIO_SetXO
#define Sx_Board_GetWakeUpTime SX1262DVK1CAS_RADIO_GetWakeUpTime
#define Sx_Board_GetPaSelect SX1262DVK1CAS_RADIO_GetPaSelect
#define Sx_Board_SetAntSw SX1262DVK1CAS_RADIO_SetAntSw
#define Sx_Board_Bus_Init SX1262DVK1CAS_RADIO_Bus_Init
#define Sx_Board_Bus_deInit SX1262DVK1CAS_RADIO_Bus_deInit
#define Sx_Board_WaitOnBusy SX1262DVK1CAS_RADIO_WaitOnBusy
#define Sx_Board_WakeUp SX1262DVK1CAS_RADIO_WakeUp
#define Sx_Board_IsTcxo SX1262DVK1CAS_RADIO_BoardIsTcxo
#define Sx_Board_SetLedRx SX1262DVK1CAS_RADIO_BoardSetLedRx
#define Sx_Board_SetLedTx SX1262DVK1CAS_RADIO_BoardSetLedTx
#elif SX1261DVK1BAS
#include "sx1261dvk1bas.h"
#define Sx_Board_IoInit SX1261DVK1BAS_RADIO_IoInit
#define Sx_Board_IoDeInit SX1261DVK1BAS_RADIO_IoDeInit
#define Sx_Board_IoIrqInit SX1261DVK1BAS_RADIO_IoIrqInit
#define Sx_Board_SendRecv SX1261DVK1BAS_RADIO_SendRecv
#define Sx_Board_ChipSelect SX1261DVK1BAS_RADIO_ChipSelect
#define Sx_Board_CheckRfFrequency SX1261DVK1BAS_RADIO_CheckRfFrequency
#define Sx_Board_Reset SX1261DVK1BAS_RADIO_Reset
#define Sx_Board_SetXO SX1261DVK1BAS_RADIO_SetXO
#define Sx_Board_GetWakeUpTime SX1261DVK1BAS_RADIO_GetWakeUpTime
#define Sx_Board_GetPaSelect SX1261DVK1BAS_RADIO_GetPaSelect
#define Sx_Board_SetAntSw SX1261DVK1BAS_RADIO_SetAntSw
#define Sx_Board_Bus_Init SX1261DVK1BAS_RADIO_Bus_Init
#define Sx_Board_Bus_deInit SX1261DVK1BAS_RADIO_Bus_deInit
#define Sx_Board_WaitOnBusy SX1261DVK1BAS_RADIO_WaitOnBusy
#define Sx_Board_WakeUp SX1261DVK1BAS_RADIO_WakeUp
#define Sx_Board_IsTcxo SX1261DVK1BAS_RADIO_BoardIsTcxo
#define Sx_Board_SetLedRx SX1261DVK1BAS_RADIO_BoardSetLedRx
#define Sx_Board_SetLedTx SX1261DVK1BAS_RADIO_BoardSetLedTx
#else
#error "include your board here"
#endif
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions ------------------------------------------------------- */
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* RADIO_BOARD_IF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,108 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file radio_conf.h
* @author MCD Application Team
* @brief Header of Radio configuration
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __RADIO_CONF_H__
#define __RADIO_CONF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "platform.h"
#include "../../Utils/Inc/stm32_mem.h" /* RADIO_MEMSET8 def in this file */
#include "mw_log_conf.h" /* mw trace conf */
#include "radio_board_if.h" /* low layer api (bsp) */
#include "utilities_def.h" /* low layer api (bsp) */
//#include "sys_debug.h"
/* USER CODE BEGIN include */
/* USER CODE END include */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
#if( RADIO_DIOn > 4 )
#define RADIO_DIO_4_ACTIVE
#endif
#if( RADIO_DIOn > 5 )
#define RADIO_DIO_5_ACTIVE
#endif
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macros -----------------------------------------------------------*/
#ifndef CRITICAL_SECTION_BEGIN
/**
* @brief macro used to enter the critical section
*/
#define CRITICAL_SECTION_BEGIN( ) UTILS_ENTER_CRITICAL_SECTION( )
#endif /* !CRITICAL_SECTION_BEGIN */
#ifndef CRITICAL_SECTION_END
/**
* @brief macro used to exit the critical section
*/
#define CRITICAL_SECTION_END( ) UTILS_EXIT_CRITICAL_SECTION( )
#endif /* !CRITICAL_SECTION_END */
/* Function mapping */
/**
* @brief Delay interface to radio Middleware
*/
#define RADIO_DELAY_MS HAL_Delay
/**
* @brief Memset utilities interface to radio Middleware
*/
#define RADIO_MEMSET8( dest, value, size ) UTIL_MEM_set_8( dest, value, size )
/**
* @brief Memcpy utilities interface to radio Middleware
*/
#define RADIO_MEMCPY8( dest, src, size ) UTIL_MEM_cpy_8( dest, src, size )
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __RADIO_CONF_H__*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,114 @@
/**
******************************************************************************
* @file : sx1276mb1mas_conf.h
* @brief : This file provides code for the configuration
* of the shield instances (pin mapping).
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2019 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
#ifndef __SX1276MB1MAS_CONF_H__
#define __SX1276MB1MAS_CONF_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "platform.h"
#include "radio_conf.h"
/* Defines ---------------------------------------------------------------*/
#define RADIO_DIO_0_IT_PRIO 6
#define RADIO_DIO_1_IT_PRIO 6
#define RADIO_DIO_2_IT_PRIO 6
#define RADIO_DIO_3_IT_PRIO 6
/* Daughter board Pin mapping --------------------------------------------*/
/* SPI functions redefinition */
#define RADIO_SPI_Init BSP_SPI3_Init
#define RADIO_SPI_DeInit BSP_SPI3_DeInit
#define RADIO_SPI_SendRecv BSP_SPI3_SendRecv
#define RADIO_SPI_SCK_GPIO_PIN BUS_SPI3_SCK_GPIO_PIN
#define RADIO_SPI_MISO_GPIO_PIN BUS_SPI3_MISO_GPIO_PIN
#define RADIO_SPI_MOSI_GPIO_PIN BUS_SPI3_MOSI_GPIO_PIN
#define RADIO_SPI_SCK_GPIO_PORT BUS_SPI3_SCK_GPIO_PORT
#define RADIO_SPI_MISO_GPIO_PORT BUS_SPI3_MISO_GPIO_PORT
#define RADIO_SPI_MOSI_GPIO_PORT BUS_SPI3_MOSI_GPIO_PORT
#define RADIO_SPI_SCK_GPIO_AF BUS_SPI3_SCK_GPIO_AF
#define RADIO_SPI_MOSI_GPIO_AF BUS_SPI3_MOSI_GPIO_AF
#define RADIO_SPI_MISO_GPIO_AF BUS_SPI3_MISO_GPIO_AF
#define RADIO_SPI_SCK_GPIO_CLK_ENABLE() BUS_SPI3_SCK_GPIO_CLK_ENABLE()
#define RADIO_SPI_MOSI_GPIO_CLK_ENABLE() BUS_SPI3_MOSI_GPIO_CLK_ENABLE()
#define RADIO_SPI_MISO_GPIO_CLK_ENABLE() BUS_SPI3_MISO_GPIO_CLK_ENABLE()
/* SPIx Bus Pin mapping */
#define RADIO_NSS_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
#define RADIO_NSS_PORT GPIOA
#define RADIO_NSS_PIN GPIO_PIN_7
/* LORA I/O pin mapping */
#define RADIO_RESET_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
#define RADIO_RESET_PORT GPIOA
#define RADIO_RESET_PIN GPIO_PIN_1
#define RADIO_DIOn 4U
#define RADIO_DIO_0_PORT GPIOA
#define RADIO_DIO_0_PIN GPIO_PIN_10
#define RADIO_DIO_0_GPIO_CLK_ENABLE() __HAL_RCC_GPIOA_CLK_ENABLE()
#define RADIO_DIO_0_EXTI_LINE EXTI_LINE_10
#define RADIO_DIO_0_IRQn EXTI15_10_IRQn
#define H_EXTI_10 hRADIO_DIO_exti[0]
#define RADIO_DIO_1_PORT GPIOB
#define RADIO_DIO_1_PIN GPIO_PIN_3
#define RADIO_DIO_1_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define RADIO_DIO_1_EXTI_LINE EXTI_LINE_3
#define RADIO_DIO_1_IRQn EXTI3_IRQn
#define H_EXTI_3 hRADIO_DIO_exti[1]
#define RADIO_DIO_2_PORT GPIOB
#define RADIO_DIO_2_PIN GPIO_PIN_5
#define RADIO_DIO_2_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define RADIO_DIO_2_EXTI_LINE EXTI_LINE_5
#define RADIO_DIO_2_IRQn EXTI9_5_IRQn
#define H_EXTI_5 hRADIO_DIO_exti[2]
#define RADIO_DIO_3_PORT GPIOB
#define RADIO_DIO_3_PIN GPIO_PIN_4
#define RADIO_DIO_3_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define RADIO_DIO_3_EXTI_LINE EXTI_LINE_4
#define RADIO_DIO_3_IRQn EXTI4_IRQn
#define H_EXTI_4 hRADIO_DIO_exti[3]
#ifdef RFM95
#define RADIO_ANT_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define RADIO_ANT_SWITCH_PORT GPIOB
#define RADIO_ANT_SWITCH_PIN GPIO_PIN_0
#endif
#define RADIO_LED0_Port GPIOC
#define RADIO_LED0_Pin GPIO_PIN_0
#define RADIO_LED1_Port GPIOC
#define RADIO_LED1_Pin GPIO_PIN_1
#define RADIO_LED2_Port GPIOB
#define RADIO_LED2_Pin GPIO_PIN_0
#ifdef __cplusplus
}
#endif
#endif /* __SX1276MB1MAS_CONF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,67 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file systime.h
* @author MCD Application Team
* @brief Map middleware systime
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SYSTIME_H__
#define __SYSTIME_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32_systime.h"
/* 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 */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /*__SYSTIME_H__*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,120 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file timer.h
* @author MCD Application Team
* @brief Wrapper to timer server
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __TIMER_H__
#define __TIMER_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "../../Utils/Inc/stm32_timer.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/**
* @brief Max timer mask
*/
#define TIMERTIME_T_MAX ( ( uint32_t )~0 )
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/**
* @brief Timer value on 32 bits
*/
#define TimerTime_t UTIL_TIMER_Time_t
/**
* @brief Timer object description
*/
#define TimerEvent_t UTIL_TIMER_Object_t
/**
* @brief Create the timer object
*/
#define TimerInit(HANDLE, CB) do {\
UTIL_TIMER_Create( HANDLE, TIMERTIME_T_MAX, UTIL_TIMER_ONESHOT, CB, NULL);\
} while(0)
/**
* @brief update the period and start the timer
*/
#define TimerSetValue(HANDLE, TIMEOUT) do{ \
UTIL_TIMER_SetPeriod(HANDLE, TIMEOUT);\
} while(0)
/**
* @brief Start and adds the timer object to the list of timer events
*/
#define TimerStart(HANDLE) do {\
UTIL_TIMER_Start(HANDLE);\
} while(0)
/**
* @brief Stop and removes the timer object from the list of timer events
*/
#define TimerStop(HANDLE) do {\
UTIL_TIMER_Stop(HANDLE);\
} while(0)
/**
* @brief return the current time
*/
#define TimerGetCurrentTime UTIL_TIMER_GetCurrentTime
/**
* @brief return the elapsed time
*/
#define TimerGetElapsedTime UTIL_TIMER_GetElapsedTime
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __TIMER_H__*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,44 @@
/**
******************************************************************************
* @file
* @author MCD Application Team
* @version V2.0.0
******************************************************************************
* @attention
*
* COPYRIGHT(c) 2021 STMicroelectronics
*
* 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 __RTE_COMPONENTS_H__
#define __RTE_COMPONENTS_H__
/* Defines ------------------------------------------------------------------*/
/* STMicroelectronics.X-CUBE-BLE1.6.1.0 */
#define SAMPLE_APP
#define HCI_TL
#define HCI_TL_INTERFACE
#endif /* __RTE_COMPONENTS_H__ */

View File

@@ -0,0 +1,30 @@
/*
* actuator_mgr.h
*
* Created on: 18 sept. 2022
* Author: xavie
*/
#ifndef INC_ACTUATOR_MGR_H_
#define INC_ACTUATOR_MGR_H_
#include <stdbool.h>
#include <stdint.h>
typedef enum {
PORT0_8A, // Fan
PORT1_8A, // Soil heating
PORT2_16A, // Auxiliary pump
PORT3_8A, // Reserved - Sump pump
PORT4_2A // Auxiliary 230VAC on timer
} PowerPort;
#define AUX_230VAC_PORT PORT4_2A
void actuator_AAR_OVER( uint16_t id, uint16_t reference, uint16_t hysteresis );
void actuator_AAR_OUTOFRANGE( uint16_t id, uint16_t reference, uint16_t hysteresis );
void actuator_AAR_ON( uint16_t id );
void actuator_AAR_OFF( uint16_t id );
#endif /* INC_ACTUATOR_MGR_H_ */

View File

@@ -0,0 +1,225 @@
/*
FreeRTOS V7.4.0 - Copyright (C) 2013 Real Time Engineers Ltd.
FEATURES AND PORTS ARE ADDED TO FREERTOS ALL THE TIME. PLEASE VISIT
http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License (version 2) as published by the
Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
>>>>>>NOTE<<<<<< The modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel.
FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details. You should have received a copy of the GNU General Public License
and the FreeRTOS license exception along with FreeRTOS; if not itcan be
viewed here: http://www.freertos.org/a00114.html and also obtained by
writing to Real Time Engineers Ltd., contact details for whom are available
on the FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong?" *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, books, training, latest versions,
license and Real Time Engineers Ltd. contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool, and our new
fully thread aware and reentrant UDP/IP stack.
http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High
Integrity Systems, who sell the code with commercial support,
indemnification and middleware, under the OpenRTOS brand.
http://www.SafeRTOS.com - High Integrity Systems also provide a safety
engineered and independently SIL3 certified version for use in safety and
mission critical applications that require provable dependability.
*/
#ifndef INC_AUTOM_H
#define INC_AUTOM_H
/* Header file includes */
#include "FreeRTOS.h"
#include "cmsis_os.h"
#include "time.h"
#include "task.h"
#include "queue.h"
#include "stdbool.h"
#include "commonMsg.h"
#define DATA_VERSION 0x30313250
#define ACTIVE_LOW // comment out this line if your relays are active high
//
#define VALVES_MASK 0x00FF // Flushing valve is excluded
#define ALL_VALVES_MASK (VALVES_MASK|0x8000) // Flushing valve is included
#define VALVES_ON (VALVES_MASK)
#define ACTUATORS_MASK (0x1F00)
#define BITSHIFT_OUTPUT(a) (1U << a)
#define ALL_OUTPUTS_OFF (0x0000)
#define UNDEF_FLOWRATE 255
#ifdef ACTIVE_LOW
// Valve output pin is high when valve is closed
// Actuator output pins is low when actuator is stopped
#define CONVERT_STATE(a) ((~(a) & ALL_VALVES_MASK) | (a & ACTUATORS_MASK))
#else
#define CONVERT_STATE(a) (~(a & ACTUATORS_MASK) | (a & ALL_VALVES_MASK))
#endif
#define BYTE_TO_BINARY_PATTERN "%c%c%c%c%c%c%c%c"
#define BYTE_TO_BINARY(byte) \
(byte & 0x80 ? '8' : '.'), \
(byte & 0x40 ? '7' : '.'), \
(byte & 0x20 ? '6' : '.'), \
(byte & 0x10 ? '5' : '.'), \
(byte & 0x08 ? '4' : '.'), \
(byte & 0x04 ? '3' : '.'), \
(byte & 0x02 ? '2' : '.'), \
(byte & 0x01 ? '1' : '.')
/* Features */
#define AUTO_COOLING 0x0300 // Binary
#define AUTO_CABLE_HEATING 0x0301 // Binary
#define AUTO_SUMP_PUMPING 0x0302
#define CALIBRATION 0x0305 // Module calibration
typedef enum {
AAR_DISABLE=0x00,
// actuators will auto start if ...
AAR_OVER, // over first setpoint - hysteresis with second setpoint
AAR_ABOVE, // above first setpoint - hysteresis with second setpoint
AAR_INRANGE, // in range of setpoints
AAR_OUTOFRANGE // out of range of setpoints
} ActuatorAutoRunning;
typedef enum {
PER_SELECT,
PER_EVEN,
PER_ODD,
PER_ODD31,
OVER_2_DAYS,
OVER_3_DAYS,
OVER_4_DAYS,
OVER_5_DAYS
} SelectDays;
typedef struct {
uint8_t id;
uint8_t wateringWeekDay;
uint8_t period;
uint8_t dummy;
uint8_t nStartTimes;
uint16_t startTimes[8]; // in minutes past 00:00
uint8_t seasonalAdjust;
bool monthlySeasonalAdjust;
uint8_t valveDelay;
} WATERING_PROGRAM;
typedef struct {
uint8_t outputNum; // ID
bool autoRunEnabled;
uint8_t setpoints[2]; // Setpoints used to start and stop the actuator
uint8_t autoRunFeature;
float avgCurrentConsumption; // Average current consumption. Used to safety stop the actuator if overload
} WATERING_ACTUATOR;
typedef struct {
uint16_t startYearDay; // Starting at year day - 0 means start only this one immediately
uint8_t cycleTime; // Cycle+Soak parameters allow pulsed watering
uint8_t soakTime; // in minutes
uint16_t runTime[4]; // in minutes - 4 programs
} WATERING_SEQUENCE;
typedef struct {
uint8_t id;
bool MV_Pump;
bool sensorsOverride; // Allow to bypass rain gauge sensor driver (watering even if it is raining)
bool dummy;
WATERING_SEQUENCE sequence[4];
uint8_t pumpAdjust;
} WATERING_VALVE;
typedef struct {
uint32_t versionID; // Data version
int8_t PumpStartDelay; // Starting pump delay at first valve opening in seconds (+:after -:before)
int8_t PumpStopDelay; // Stopping pump delay af last valve closing in seconds (+:after -:before)
uint8_t FlushingTime; // Flushing pipes time in seconds
uint16_t auxStartTime; // Enable AUX output at specified time, in minutes past 00:00
uint16_t auxEndTime; // Disable AUX output at specified time, in minutes past 00:00
int8_t timeZoneOffset; // timezone offset in hour
WATERING_ACTUATOR actuators[5]; // Auxilary actuators( fan, second pump, ...)
WATERING_VALVE valves[8]; // Watering valves
WATERING_PROGRAM programs[4]; // Watering programs
uint16_t seasonalMonthlyParam[12]; // Seasonal monthly watering correction
} WATERING_GENERAL;
typedef struct {
time_t jTime; // Start time from 00:00
char progId; // Active programs ID
uint8_t valves; // Valves selected (bitfield)
bool tempState; // ON/OFF Valve
uint8_t pumpRate; // From 600 to 100, Default: 90
} WATERING_OF_THE_DAY_STRUCT;
typedef struct {
WATERING_GENERAL settings;
PARAM_SYS_STRUCT paramSys;
} FLASH_STRUCT __attribute__((__aligned__(8)));
int8_t getCaseTemperature(void);
uint16_t findValvesStepState( uint8_t step );
void wateringStats( uint16_t month_id );
int dailyStepWatering( uint8_t step, char* buffer );
void dailyWatering( char* buffer );
int dayCycleRemaining( time_t current_t, int programId );
bool isWateringDay( WATERING_PROGRAM* o, struct tm* t );
int compareWateringList(const void *s1, const void *s2);
uint16_t wateringList( struct tm* current_time, WATERING_OF_THE_DAY_STRUCT list[] );
WATERING_OF_THE_DAY_STRUCT findFirstStartAtNextWatering( time_t t_day );
int findDayDelay( uint8_t st );
uint16_t optimizeWatering( WATERING_OF_THE_DAY_STRUCT list[] );
uint16_t initDaylyWateringList();
uint8_t findSprinklingStep();
uint8_t findAverageFlowRate( uint16_t );
void initCurrentDayCycle( void* ptr );
void Automation_sendCommandToActuators( uint16_t id, ActuatorStates state, uint8_t pumpRate );
void updateAUXtimer( uint16_t actuatorId );
void mainStatement(ActuatorStates state);
bool saveSettings( FLASH_STRUCT* data );
void actuator_reset_state();
void actuator_process( uint8_t id, uint16_t reference );
void vAutomationTask( void *pvParameters );
extern xQueueHandle AutomationQueue;
#endif /* INC_AUTOM_H */

View File

@@ -0,0 +1,74 @@
/*
FreeRTOS V7.4.0 - Copyright (C) 2013 Real Time Engineers Ltd.
FEATURES AND PORTS ARE ADDED TO FREERTOS ALL THE TIME. PLEASE VISIT
http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License (version 2) as published by the
Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
>>>>>>NOTE<<<<<< The modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel.
FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details. You should have received a copy of the GNU General Public License
and the FreeRTOS license exception along with FreeRTOS; if not itcan be
viewed here: http://www.freertos.org/a00114.html and also obtained by
writing to Real Time Engineers Ltd., contact details for whom are available
on the FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong?" *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, books, training, latest versions,
license and Real Time Engineers Ltd. contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool, and our new
fully thread aware and reentrant UDP/IP stack.
http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High
Integrity Systems, who sell the code with commercial support,
indemnification and middleware, under the OpenRTOS brand.
http://www.SafeRTOS.com - High Integrity Systems also provide a safety
engineered and independently SIL3 certified version for use in safety and
mission critical applications that require provable dependability.
*/
#ifndef INC_BLE_H
#define INC_BLE_H
/* Header file includes */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
void vBleTask( void *pvParameters );
extern xQueueHandle BleQueue;
#endif /* INC_BLE_H */

View File

@@ -0,0 +1,101 @@
/*
FreeRTOS V7.4.0 - Copyright (C) 2013 Real Time Engineers Ltd.
FEATURES AND PORTS ARE ADDED TO FREERTOS ALL THE TIME. PLEASE VISIT
http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License (version 2) as published by the
Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
>>>>>>NOTE<<<<<< The modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel.
FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details. You should have received a copy of the GNU General Public License
and the FreeRTOS license exception along with FreeRTOS; if not itcan be
viewed here: http://www.freertos.org/a00114.html and also obtained by
writing to Real Time Engineers Ltd., contact details for whom are available
on the FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong?" *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, books, training, latest versions,
license and Real Time Engineers Ltd. contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool, and our new
fully thread aware and reentrant UDP/IP stack.
http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High
Integrity Systems, who sell the code with commercial support,
indemnification and middleware, under the OpenRTOS brand.
http://www.SafeRTOS.com - High Integrity Systems also provide a safety
engineered and independently SIL3 certified version for use in safety and
mission critical applications that require provable dependability.
*/
#ifndef INC_CAN_BUS_H
#define INC_CAN_BUS_H
/* Header file includes */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
typedef enum {
UNKNOWN=0x00, SOIL, AIR, METEO, LEVEL
} SensorType;
typedef struct {
uint16_t address; // Sensor address
SensorType type; // Type of sensor
uint16_t nParam; // number of parameters max. 8
float params[8]; // Measured values
uint16_t pollingTime; // Polling time in minutes
} SENSITIVE_STRUCT;
typedef struct {
uint8_t nbSensors; // Nb Sensors
SENSITIVE_STRUCT sensors[5]; // Sensors list
} GREEN_HOUSE_SENSORS_STRUCT;
int findIndexDiscoveringStationsByID( uint16_t id );
void newCANbusStation( uint16_t id );
void discoveringStation( uint16_t id );
void CanTimeoutCallback( void const * arg );
int findSensorIdByAddress( uint16_t addr );
void echoCanMessage( uint16_t addr, uint8_t* data, uint16_t sz);
int CAN_filterConfig(void);
//int pcan_rx_frame( uint8_t channel, struct t_can_msg *pmsg );
static void Can_Bus_processMsg(MSG_STRUCT *p_msg);
static void Can_Bus_processFrame();
void vCanBusTask( void *pvParameters );
extern xQueueHandle CanBusQueue;
#endif /* INC_CAN_BUS_H */

View File

@@ -0,0 +1,79 @@
/*
* commonMsg.h
*
* Created on: 2020/01/15
* Author: x.walter
*/
#ifndef COMMONMSG_H_
#define COMMONMSG_H_
#include "time.h"
typedef enum {
DUMMY,
BLE_COMM,
CAN_COMM,
OUTPUTS,
AUTOMATION,
LORA_COMM,
ADC_MEAS
} MODULE_ID;
typedef enum {
V_LIGHT, V_SETTINGS
} MsgType;
typedef enum {
Z_ALL_OFF, Z_RESTART, Z_UPDATE, Z_START, Z_STOP, E_STOP, UPDATE_SETTINGS
} ActuatorStates;
typedef enum {
OP_MAIN=0x0100, OP_RTC, OP_FEATURE, OP_OUTPUT_ONCHANGE, CAN_ECHO, CAN_NOECHO, OP_CAN, OP_LORA_EVENT1
} CommandOpcode;
typedef enum {
IDLE = 0x00, PERIODIC, APERIODIC, ESTOP
} states;
typedef struct {
CommandOpcode opcode;
union {
uint16_t errorNo;
struct {
union {
/*struct {
uint16_t actuatorsBitField;
ActuatorStates changeState;
};*/
struct {
uint16_t outputs; // bit 0 to 7 and bit 15: 24VAC devices, bit 8 to 12: 230VAC devices according to ActuatorStates
ActuatorStates changeState;
uint8_t pumpRate;
};
uint16_t lParam[6];
uint32_t wParam[3];
char data[21]; // Data to transmit
};
};
};
} MSG_STRUCT;
typedef struct {
time_t currentDayCycle[4]; // Day cycle for each program
} PARAM_SYS_STRUCT;
#ifdef __cplusplus
extern "C" {
#endif
osMessageQId getQueueId(MODULE_ID moduleId);
MSG_STRUCT *allocMemoryPoolMessage();
void freeMemoryPoolMessage(MSG_STRUCT *p_message);
#ifdef __cplusplus
}
#endif
#endif /* COMMONMSG_H_ */

View File

@@ -0,0 +1,23 @@
/*
* crc32.h
*
* Created on: 13 août 2022
* Author: xavie
*/
#ifndef INC_CRC32_H_
#define INC_CRC32_H_
#include <stdint.h>
#ifdef SYS_CRC
uint32_t TM_CRC_Calculate32(uint32_t* arr, uint32_t count, uint8_t reset);
uint32_t crc32_check (CRC_HandleTypeDef *hcrc, uint8_t* buf, uint16_t len);
#endif
uint8_t reflect8(uint8_t val);
uint32_t reflect32(uint32_t val);
uint32_t calcCRC32stm(void *data, uint32_t len, uint32_t poly, uint32_t seed, uint32_t initCRC, uint32_t inR, uint32_t outR);
uint32_t calcCRC32std(void *data, uint32_t len, uint32_t poly, uint32_t seed, uint32_t initCRC, uint32_t inR, uint32_t outR);
#endif /* INC_CRC32_H_ */

View File

@@ -0,0 +1,31 @@
#ifndef INC_CURRENT_MEAS_H
#define INC_CURRENT_MEAS_H
/* Header file includes */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#define CURRENT_VALVE_REF 260 // valve current consumption in mA
#define CURRENT_VALVE_UPPER_LIMIT (CURRENT_VALVE_REF * 12 / 10)
#define CURRENT_VALVE_LOWER_LIMIT (CURRENT_VALVE_REF * 8 / 10)
#define CURRENT_ACTUATOR_REF 3000 // actuator current consumption in mA
#define CURRENT_ACTUATOR_UPPER_LIMIT (CURRENT_ACTUATOR_REF * 12 / 10)
#define CURRENT_ACTUATOR_LOWER_LIMIT (CURRENT_ACTUATOR_REF * 8 / 10)
#define CURRENT_AT_REST_THRESHOLD_MA 90 // Noisy signal from current sensor IC
typedef struct {
uint16_t currentRef;
uint16_t currentUpperLimit;
uint16_t currentLowerLimit;
} CURRENT_THRESHOLD_STRUCT;
typedef enum {
VALVE_DEVICE, ACTUATOR_DEVICE
} CURRENT_DEVICE_TYPE;
void vCurrentMeasTask( void *pvParameters );
#endif /* INC_CURRENT_MEAS_H */

View File

@@ -0,0 +1,36 @@
/*
* env_sensors.h
*
* Created on: 13 mai 2023
* Author: xavie
*/
#ifndef INC_ENV_SENSORS_H_
#define INC_ENV_SENSORS_H_
#include <stdint.h>
#define ENV_SENSORS_NBR 10
typedef struct env_sensor_def {
uint16_t can_address;
uint8_t param_id;
} env_sensors_t;
typedef struct {
uint16_t nbr;
env_sensors_t env_sensors[ENV_SENSORS_NBR];
} FLASH_ENV_SENSORS __attribute__((__aligned__(8)));
typedef enum {
NONE,
DRIZZLING,
SMALL_DROP,
BIG_DROP,
REGULAR,
SHOWER
} RAINING_CONDITIONS;
extern FLASH_ENV_SENSORS env_sensors_tab;
#endif /* INC_ENV_SENSORS_H_ */

View File

@@ -0,0 +1,28 @@
/*
* flash_page.h
*
* Created on: May 13, 2021
* Author: xavie
*/
#ifndef INC_FLASH_PAGE_H_
#define INC_FLASH_PAGE_H_
#include "stm32l4xx_hal.h"
#define __IO volatile
#define FLASH_USER_START_ADDR 0x080FF800
#define FLASH_LORA_START_ADDR 0x080FFA00
uint32_t Flash_Write_Data (uint32_t StartPageAddress, __IO uint64_t * DATA_32, uint16_t bsize);
void Flash_Read_Data (uint32_t StartPageAddress, __IO uint32_t * DATA_32, uint16_t bsize);
/******************** FLASH_Error_Codes ***********************//*
HAL_FLASH_ERROR_NONE 0x00U // No error
HAL_FLASH_ERROR_PROG 0x01U // Programming error
HAL_FLASH_ERROR_WRP 0x02U // Write protection error
HAL_FLASH_ERROR_OPTV 0x04U // Option validity error
*/
#endif /* INC_FLASH_PAGE_H_ */

View File

@@ -0,0 +1,161 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.h
* @brief : Header for main.c file.
* This file contains the common defines of the application.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l4xx_hal.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "hci_tl_interface.h"
#include "stm32_adv_trace.h"
#include "utilities_conf.h"
///#include "stm32f4xx_nucleo.h"
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/**
* @brief Verbose level for all trace logs
*/
#define VERBOSE_LEVEL VLEVEL_H
/**
* @brief Enable trace logs
*/
#define APP_LOG_ENABLED 1
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
#define APP_PPRINTF(...) do{ } while( UTIL_ADV_TRACE_OK \
!= UTIL_ADV_TRACE_COND_FSend(VLEVEL_ALWAYS, T_REG_OFF, TS_OFF, __VA_ARGS__) ) /* Polling Mode */
#define APP_TPRINTF(...) do{ {UTIL_ADV_TRACE_COND_FSend(VLEVEL_ALWAYS, T_REG_OFF, TS_ON, __VA_ARGS__);} }while(0); /* with timestamp */
#define APP_PRINTF(...) do{ {UTIL_ADV_TRACE_COND_FSend(VLEVEL_ALWAYS, T_REG_OFF, TS_OFF, __VA_ARGS__);} }while(0);
#if defined (APP_LOG_ENABLED) && (APP_LOG_ENABLED == 1)
#define APP_LOG(TS,VL,...) do{ {UTIL_ADV_TRACE_COND_FSend(VL, T_REG_OFF, TS, __VA_ARGS__);} }while(0);
#elif defined (APP_LOG_ENABLED) && (APP_LOG_ENABLED == 0) /* APP_LOG disabled */
#define APP_LOG(TS,VL,...)
#else
#error "APP_LOG_ENABLED not defined or out of range <0,1>"
#endif /* APP_LOG_ENABLED */
/* USER CODE END EM */
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);
void MX_RTC_Init(void);
void MX_USART2_UART_Init(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
#define USR_BTN_Pin GPIO_PIN_13
#define USR_BTN_GPIO_Port GPIOC
#define USR_BTN_EXTI_IRQn EXTI15_10_IRQn
#define RADIO_LED0_Pin GPIO_PIN_0
#define RADIO_LED0_GPIO_Port GPIOC
#define RADIO_LED1_Pin GPIO_PIN_1
#define RADIO_LED1_GPIO_Port GPIOC
#define AIN_I_Drives_Pin GPIO_PIN_2
#define AIN_I_Drives_GPIO_Port GPIOC
#define AIN_I_Valves_Pin GPIO_PIN_3
#define AIN_I_Valves_GPIO_Port GPIOC
#define VCC_ON_Pin GPIO_PIN_0
#define VCC_ON_GPIO_Port GPIOA
#define VCC_ON_EXTI_IRQn EXTI0_IRQn
#define RADIO_RESET_Pin GPIO_PIN_1
#define RADIO_RESET_GPIO_Port GPIOA
#define LD2_Pin GPIO_PIN_5
#define LD2_GPIO_Port GPIOA
#define RADIO_NSS_Pin GPIO_PIN_7
#define RADIO_NSS_GPIO_Port GPIOA
#define PWR_EN_Pin GPIO_PIN_4
#define PWR_EN_GPIO_Port GPIOC
#define LATCH_OUT_Pin GPIO_PIN_5
#define LATCH_OUT_GPIO_Port GPIOC
#define RADIO_LED2_Pin GPIO_PIN_0
#define RADIO_LED2_GPIO_Port GPIOB
#define DBG1_Pin GPIO_PIN_1
#define DBG1_GPIO_Port GPIOB
#define BLE_INT_Pin GPIO_PIN_2
#define BLE_INT_GPIO_Port GPIOB
#define BLE_INT_EXTI_IRQn EXTI2_IRQn
#define DBG5_Pin GPIO_PIN_10
#define DBG5_GPIO_Port GPIOB
#define BLE_CS_Pin GPIO_PIN_13
#define BLE_CS_GPIO_Port GPIOB
#define BLE_RST_Pin GPIO_PIN_14
#define BLE_RST_GPIO_Port GPIOB
#define ZeroCrossing_Pin GPIO_PIN_6
#define ZeroCrossing_GPIO_Port GPIOC
#define AC_MOTOR_DRIVE_Pin GPIO_PIN_7
#define AC_MOTOR_DRIVE_GPIO_Port GPIOC
#define CLK_OUT_Pin GPIO_PIN_8
#define CLK_OUT_GPIO_Port GPIOC
#define DATA_OUT_Pin GPIO_PIN_9
#define DATA_OUT_GPIO_Port GPIOC
#define OE_Pin GPIO_PIN_8
#define OE_GPIO_Port GPIOA
#define RADIO_DIO0_Pin GPIO_PIN_10
#define RADIO_DIO0_GPIO_Port GPIOA
#define RADIO_DIO0_EXTI_IRQn EXTI15_10_IRQn
#define CAN_LED_Pin GPIO_PIN_15
#define CAN_LED_GPIO_Port GPIOA
#define ERR_LED_Pin GPIO_PIN_2
#define ERR_LED_GPIO_Port GPIOD
#define RADIO_DIO1_Pin GPIO_PIN_3
#define RADIO_DIO1_GPIO_Port GPIOB
#define RADIO_DIO1_EXTI_IRQn EXTI3_IRQn
#define RADIO_DIO3_Pin GPIO_PIN_4
#define RADIO_DIO3_GPIO_Port GPIOB
#define RADIO_DIO3_EXTI_IRQn EXTI4_IRQn
#define RADIO_DIO2_Pin GPIO_PIN_5
#define RADIO_DIO2_GPIO_Port GPIOB
#define RADIO_DIO2_EXTI_IRQn EXTI9_5_IRQn
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */

View File

@@ -0,0 +1,74 @@
/*
FreeRTOS V7.4.0 - Copyright (C) 2013 Real Time Engineers Ltd.
FEATURES AND PORTS ARE ADDED TO FREERTOS ALL THE TIME. PLEASE VISIT
http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
***************************************************************************
* *
* FreeRTOS tutorial books are available in pdf and paperback. *
* Complete, revised, and edited pdf reference manuals are also *
* available. *
* *
* Purchasing FreeRTOS documentation will not only help you, by *
* ensuring you get running as quickly as possible and with an *
* in-depth knowledge of how to use FreeRTOS, it will also help *
* the FreeRTOS project to continue with its mission of providing *
* professional grade, cross platform, de facto standard solutions *
* for microcontrollers - completely free of charge! *
* *
* >>> See http://www.FreeRTOS.org/Documentation for details. <<< *
* *
* Thank you for using FreeRTOS, and thank you for your support! *
* *
***************************************************************************
This file is part of the FreeRTOS distribution.
FreeRTOS is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License (version 2) as published by the
Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
>>>>>>NOTE<<<<<< The modification to the GPL is included to allow you to
distribute a combined work that includes FreeRTOS without being obliged to
provide the source code for proprietary components outside of the FreeRTOS
kernel.
FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more
details. You should have received a copy of the GNU General Public License
and the FreeRTOS license exception along with FreeRTOS; if not itcan be
viewed here: http://www.freertos.org/a00114.html and also obtained by
writing to Real Time Engineers Ltd., contact details for whom are available
on the FreeRTOS WEB site.
1 tab == 4 spaces!
***************************************************************************
* *
* Having a problem? Start by reading the FAQ "My application does *
* not run, what could be wrong?" *
* *
* http://www.FreeRTOS.org/FAQHelp.html *
* *
***************************************************************************
http://www.FreeRTOS.org - Documentation, books, training, latest versions,
license and Real Time Engineers Ltd. contact details.
http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
including FreeRTOS+Trace - an indispensable productivity tool, and our new
fully thread aware and reentrant UDP/IP stack.
http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High
Integrity Systems, who sell the code with commercial support,
indemnification and middleware, under the OpenRTOS brand.
http://www.SafeRTOS.com - High Integrity Systems also provide a safety
engineered and independently SIL3 certified version for use in safety and
mission critical applications that require provable dependability.
*/
#ifndef INC_OUT_H
#define INC_OUT_H
/* Header file includes */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
void vOutputsTask( void *pvParameters );
extern xQueueHandle OutputsQueue;
#endif /* INC_OUT_H */

View File

@@ -0,0 +1,31 @@
/*
* parcelize.h
*
* Created on: 8 août 2022
* Author: xavie
*/
#ifndef INC_PARCELIZE_H_
#define INC_PARCELIZE_H_
#include "utils.h"
#include "env_sensors.h"
#define SETTINGS_BUFFER_SIZE 2048
void ActuatorParcelize( char* out, int id );
void ActuatorUnparcelize( char* in, WATERING_ACTUATOR* o );
void SequenceParcelize( char* out, int id );
void SequenceUnparcelize( char* in, WATERING_SEQUENCE* o );
void ValveParcelize( char* buff, int id );
void ValveUnparcelize( char* in, WATERING_VALVE* o );
void ProgramParcelize( char* buff, int id );
void ProgramUnparcelize( char* in, WATERING_PROGRAM* o );
int GeneralParcelize( char* buff );
bool GeneralUnparcelize( char* in, WATERING_GENERAL* o );
void EnvSensorsParcelize( char* buff );
void EnvSensorsUnparcelize( char* in, FLASH_ENV_SENSORS* o );
#endif /* INC_PARCELIZE_H_ */

View File

@@ -0,0 +1,78 @@
#pragma once
#include <stdint.h>
#define INTERNAL_CAN_IT_FLAGS ( CAN_IT_TX_MAILBOX_EMPTY |\
CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_RX_FIFO1_MSG_PENDING |\
CAN_IT_ERROR_WARNING |\
CAN_IT_ERROR_PASSIVE |\
CAN_IT_LAST_ERROR_CODE |\
CAN_IT_ERROR )
#define CAN2_FILTER_START (14u)
#define CAN_WITHOUT_ISR 0
enum
{
CAN_BUS_1,
// CAN_BUS_2,
CAN_BUS_TOTAL
};
#define CAN_PAYLOAD_MAX_SIZE (8u)
struct t_can_msg
{
// uint32_t timestamp;
uint32_t id;
uint8_t flags;
uint8_t size;
uint8_t dummy;
uint8_t data[CAN_PAYLOAD_MAX_SIZE];
};
struct t_can_stats
{
uint32_t tx_msgs;
uint32_t tx_errs;
uint32_t rx_msgs;
uint32_t rx_errs;
uint32_t rx_ovfs;
};
struct t_can_bitrate
{
uint16_t brp;
uint16_t tseg1;
uint8_t tseg2;
uint8_t sjw;
};
#define MSG_FLAG_STD (0<<0)
#define MSG_FLAG_EXT (1<<0)
#define MSG_FLAG_RTR (1<<1)
#define MSG_FLAG_ECHO (1<<3)
/* FDCAN */
#define MSG_FLAG_BRS (1<<4)
#define MSG_FLAG_FD (1<<5)
#define MSG_FLAG_ESI (1<<6)
#define CAN_INT_FILTER_MAX (14)
#define CAN_EXT_FILTER_MAX (2)
void pcan_can_poll( void );
uint32_t pcan_can_msg_time( const struct t_can_msg *pmsg, uint32_t nt, uint32_t dt );
int pcan_can_stats( int bus, struct t_can_stats *p_stats );
int pcan_can_init_ex( int bus, uint32_t bitrate );
void pcan_can_set_silent( int bus, uint8_t silent_mode );
void pcan_can_set_iso_mode( int bus, uint8_t iso_mode );
void pcan_can_set_loopback( int bus, uint8_t loopback );
void pcan_can_set_bus_active( int bus, uint16_t mode );
void pcan_can_set_bitrate( int bus, uint32_t bitrate, int is_data_bitrate );
void pcan_can_set_bitrate_ex( int bus, uint16_t brp, uint8_t tseg1, uint8_t tseg2, uint8_t sjw );
int pcan_can_write( int bus, struct t_can_msg *p_msg );
void pcan_can_install_rx_callback( int bus, int (*rx_isr)( uint8_t, struct t_can_msg* ));
void pcan_can_install_tx_callback( int bus, int (*rx_isr)( uint8_t, struct t_can_msg* ));
void pcan_can_install_err_callback( int bus, void (*cb)( int, uint32_t ) );
int pcan_can_set_filter_mask( int bus, int num, int format, uint32_t id, uint32_t mask );
int pcan_can_filter_init_stdid_list( int bus, const uint16_t *id_list, int id_len );

View File

@@ -0,0 +1,72 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file platform.h
* @author MCD Application Team
* @brief Header for General HW instances configuration
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __PLATFORM_H__
#define __PLATFORM_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Includes ------------------------------------------------------------------*/
#include <stdbool.h>
#include "stm32l4xx.h"
#include "main.h"
#include "stm32_nucleo_bus.h"
/* USER CODE BEGIN include */
/* USER CODE END include */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __PLATFORM_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,21 @@
/*
* rtc.h
*
* Created on: Apr 10, 2021
* Author: xavie
*/
#ifndef INC_RTC_H_
#define INC_RTC_H_
#include <time.h>
uint8_t get_weekday( RTC_DateTypeDef sDate );
uint8_t now( struct tm *tm );
void set_time( uint8_t dd, uint8_t mm, uint8_t yy, uint8_t hh, uint8_t min, uint8_t sec);
void get_alarmA_time( int *hr, int *min );
void get_time(void);
void set_alarm( uint8_t hour, uint8_t min, uint8_t wday );
#endif /* INC_RTC_H_ */

View File

@@ -0,0 +1,208 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file rtc_if.h
* @author MCD Application Team
* @brief configuration of the rtc_if.c instances
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __RTC_IF_H__
#define __RTC_IF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32_systime.h"
/* USER CODE BEGIN Includes */
#include <time.h>
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
#define RTC_N_PREDIV_S 10
#define RTC_PREDIV_S ((1<<RTC_N_PREDIV_S)-1)
#define RTC_PREDIV_A ((1<<(15-RTC_N_PREDIV_S))-1)
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/**
* @brief Timer driver definition
*/
typedef struct
{
void (* InitTimer )( void ); /*!< Initialisation of the low layer timer */
uint32_t (* SetTimerContext)( void ); /*!< Set the timer context */
uint32_t (* GetTimerContext)( void ); /*!< Get the timer context */
uint32_t (* GetTimerElapsedTime)( void ); /*!< Get elapsed time */
uint32_t (* GetTimerValue)( void ); /*!< Get timer value */
uint32_t (* GetMinimumTimeout)( void ); /*!< Get Minimum timeout */
uint32_t (* ms2Tick)( uint32_t timeMicroSec ); /*!< convert ms to tick */
uint32_t (* Tick2ms)( uint32_t tick ); /*!< convert tick into ms */
} UTIL_TIMER_Driver_s;
/**
* @brief Timer value on 32 bits
*/
typedef uint32_t UTIL_TIMER_Time_t;
/**
* @}
*/
/*!
* @brief Init RTC hardware
* @param none
* @retval none
*/
void RTC_IF_Init(void);
/*!
* @brief set timer Reference (TimerContext)
* @param none
* @retval Timer Reference Value in Ticks
*/
uint32_t RTC_IF_SetTimerContext(void);
/*!
* @brief Get the RTC timer Reference
* @param none
* @retval Timer Value in Ticks
*/
uint32_t RTC_IF_GetTimerContext(void);
/*!
* @brief Get the timer elapsed time since timer Reference (TimerContext) was set
* @param none
* @retval RTC Elapsed time in ticks
*/
uint32_t RTC_IF_GetTimerElapsedTime(void);
/*!
* @brief Get the timer value
* @param none
* @retval RTC Timer value in ticks
*/
uint32_t RTC_IF_GetTimerValue(void);
/*!
* @brief Return the minimum timeout in ticks the RTC is able to handle
* @param none
* @retval minimum value for a timeout in ticks
*/
uint32_t RTC_IF_GetMinimumTimeout(void);
/*!
* @brief converts time in ms to time in ticks
* @param [IN] time in milliseconds
* @retval returns time in timer ticks
*/
uint32_t RTC_IF_Convert_ms2Tick(uint32_t timeMilliSec);
/*!
* @brief converts time in ticks to time in ms
* @param [IN] time in timer ticks
* @retval returns time in timer milliseconds
*/
uint32_t RTC_IF_Convert_Tick2ms(uint32_t tick);
/*!
* @brief Get rtc time
* @param [OUT] subSeconds in ticks
* @retval returns time seconds
*/
uint32_t RTC_IF_GetTime(uint16_t *subSeconds);
/*!
* @brief write seconds in backUp register
* @Note Used to store seconds difference between RTC time and Unix time
* @param [IN] time in seconds
* @retval None
*/
void RTC_IF_BkUp_Write_Seconds(uint32_t Seconds);
/*!
* @brief reads seconds from backUp register
* @Note Used to store seconds difference between RTC time and Unix time
* @param [IN] None
* @retval Time in seconds
*/
uint32_t RTC_IF_BkUp_Read_Seconds(void);
/*!
* @brief writes SubSeconds in backUp register
* @Note Used to store SubSeconds difference between RTC time and Unix time
* @param [IN] time in SubSeconds
* @retval None
*/
void RTC_IF_BkUp_Write_SubSeconds(uint32_t SubSeconds);
/*!
* @brief reads SubSeconds from backUp register
* @Note Used to store SubSeconds difference between RTC time and Unix time
* @param [IN] None
* @retval Time in SubSeconds
*/
uint32_t RTC_IF_BkUp_Read_SubSeconds(void);
void TimestampNow(uint8_t *buff, uint16_t *size);
void RTC_calibration( int16_t cal );
int16_t RTC_get_calibration();
uint8_t get_weekday( RTC_DateTypeDef sDate );
uint8_t now( struct tm *tm );
void set_time( uint8_t dd, uint8_t mm, uint8_t yy, uint8_t hh, uint8_t min, uint8_t sec);
uint8_t get_alarmA_time( uint8_t *hr, uint8_t *min, uint8_t *sec );
void stop_alarmA(void);
void stop_alarmB(void);
int get_time(void);
uint32_t get_EpochTime(void);
void set_alarmA( struct tm* alarm_tm );
void set_alarmB( struct tm* alarm_tm );
void newDay();
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __RTC_IF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,221 @@
/*
* signals.h
*
* Created on: Jan 28, 2022
* Author: xavie
*/
#ifndef SRC_SIGNALS_H_
#define SRC_SIGNALS_H_
#include "main.h"
#include "cmsis_os.h"
#include <stdint.h>
#include <stdbool.h>
#include "commonMsg.h"
#define SOIL_SENSORS 6
#define AIR_SENSORS 2
#define WATER_SENSORS 2
#define MCU_S_ANEMOMETER 0x110
#define MCU_S_RAINGAUGE 0x111
#define MCU_S_WATERTANK 0x210
#define MCU_S_DISDROMETER 0x211
#define MCU_S_TEST 0x215
#define MCU_S_PYRANOMETER 0x221
#define MCU_S_THERMOMETER 0x222
#define MCU_S_SUBSONICGAUGE 0x250
//#define MCU_S_FRAME1 0x311
//#define MCU_S_FRAME2 0x312
//#define MCU_S_FRAME3 0x313
//#define MCU_S_FRAME4 0x314
//#define MCU_S_FRAME5 0x315
//#define MCU_S_FRAME6 0x316
//#define MCU_S_SKYDOME1 0x321
//#define MCU_S_SKYDOME2 0x322
#define MCU_R_COMMAND 0x0FE
typedef union{
uint8_t data[1];
struct {
states stm : 2 ;
};
} __attribute__((packed)) FiniteStateMachine;
typedef union{
uint8_t data[5];
struct {
uint16_t MCU_WindSpeed : 9;
uint16_t MCU_WindDir : 9;
uint16_t MCU_OutsideTemp : 7; // -40 to +87°C
uint16_t MCU_AtmPressure : 8;
uint8_t MCU_MaxBeaufort : 4;
} __attribute__((packed));
} dev_anemometer;
typedef union{
uint8_t data[1];
struct {
uint8_t MCU_DropDetection : 1;
uint8_t MCU_CondensationSensing : 1;
uint8_t MCU_RainingCondition : 3;
uint8_t MCU_IceSensing : 1;
} __attribute__((packed));
} dev_rain_gauge;
typedef union{
uint8_t data[5];
struct {
uint32_t MCU_WaterConsumption : 20;
uint8_t MCU_Rain : 1;
uint16_t MCU_WaterTankLevel : 7; // 0 to 100
uint16_t MCU_WaterFlowRate : 6;
uint8_t MCU_State : 4;
} __attribute__((packed));
} dev_watertank;
typedef union{
uint8_t data[2];
struct {
uint16_t MCU_ExternalTemperature : 7;
uint16_t MCU_BusVoltage : 8;
}__attribute__((packed));
} dev_test;
typedef union{
uint8_t data[5];
struct {
uint16_t MCU_SolarIrradiance : 13; // 0.0 to 819.1 W/m²
uint16_t MCU_SolarIrradianceSum : 10; // 0.00 to 10.23 Wh/m²/day
uint8_t dummy : 1;
uint16_t MCU_JunctionTemp : 8;
uint16_t MCU_BusVoltage : 8 ;
} __attribute__((packed));
} dev_pyranometer;
typedef union{
uint8_t data[4];
struct {
uint8_t MCU_InsideTemp : 7; // -40 to +87°C
uint8_t dummy : 1;
uint8_t MCU_InsideHumidity : 7; // 0 to 100%
uint8_t dummy1 : 1;
uint8_t MCU_InsideMaxTemp : 7;
uint8_t dummy2 : 1;
uint8_t MCU_InsideMinTemp : 7;
uint8_t dummy3 : 1;
} __attribute__((packed));
} dev_thermometer;
typedef union{
uint8_t data[2];
struct {
uint16_t MCU_BusVoltage : 8;
uint16_t MCU_AiSimilarity : 8;
} __attribute__((packed));
} dev_subsonic_gauge;
typedef union{
uint8_t data[6];
struct {
uint16_t MCU_AvgRainDropRate : 16;
uint16_t MCU_AvgRainDropSize : 10;
uint16_t MCU_AvgRainDropSpeed : 9;
uint16_t MCU_RainDropCount : 12;
} __attribute__((packed));
} dev_disdrometer;
typedef union{
uint8_t data[6];
struct {
uint16_t RQ_Device : 12;
uint8_t RQ_OpCode: 3;
uint8_t dummy: 1;
uint16_t setpoints[2];
} __attribute__((packed));
} dev_command_request;
/**
* LoRaWAN Sensor data parameters
*/
typedef struct
{
float atmosphericPressure; /*!< in mbar */
float outsideAirTemperature; /*!< all temperature in degC */
float greenHouseAirTemperature;
float windSpeed; /*!< wind speed in m/s */
uint8_t windDirection; /*!< wind direction in 1/10° */
uint8_t maxBeaufort;
uint8_t greenHouseHumidity;
float solarIrradiance; /*!< solar irradiance in W/m² */
int32_t latitude; /*!< latitude converted to binary */
int32_t longitude ; /*!< longitude converted to binary */
uint8_t waterLevel;
bool dropDetection;
float avgRainProbability;
float avgRainDropRate; /*!< in mm/h */
/**more may be added*/
} LoRaWAN_sensor_t;
typedef struct
{
uint8_t subsonic_AI_similarity;
/**more may be added*/
} LoRaWAN_event_sensor_t;
// Function prototypes
float getAvgFloatValue( float tab[], uint16_t size );
float getOutsideTemperature( dev_anemometer s );
uint16_t getAtmPressure( dev_anemometer s );
bool getRain( dev_watertank s );
uint8_t getWaterTankLevel( dev_watertank s );
float getWindSpeed( dev_anemometer s );
uint8_t getWindDirection( dev_anemometer s );
uint8_t getWindBeaufort( dev_anemometer s );
float getSolarIrradiance( dev_pyranometer s );
float getInsideTemperature( dev_thermometer s );
uint8_t getInsideRelativeHumidity( dev_thermometer s );
uint8_t getRainingCondition( dev_rain_gauge s );
uint8_t getSubsonicAiSimilarity( dev_subsonic_gauge s );
float getAvgRainDropRate( dev_disdrometer s );
/**
* @brief System data
*/
extern float meas_case_temperature; // Ampere
extern float meas_valves_current; // Ampere
extern float meas_drives_current; // degree Celsius
extern float meas_battery_voltage; // mV
extern uint16_t VREF; // mV
/**
* @brief Environmental data
*/
extern float gh_outsideTemperature[]; // degree Celsius
extern float gh_insideTemperature[];
extern uint8_t gh_insideHumidity[];
extern float gh_waterTankTemperature[];
extern uint8_t gh_waterTankLevel[]; // Percent
extern uint16_t gh_atmPressure[]; // hecto Pascal
extern uint16_t gh_windSpeed[];
extern uint16_t gh_windDirection[];
extern float gh_soilTemperature[];
extern float gh_solarIrradiance[];
extern uint8_t gh_windMaxBeaufort[];
extern bool gh_dropDetection[]; // No/Yes
extern uint8_t gh_rainingCondition[];
extern uint8_t gh_soilVibesAiSimilarity[];
extern float gh_averageRainDropRate[];
/**
* @brief Environmental sensor read.
* @param sensor_data sensor data
*/
int32_t EnvSensors_Read(LoRaWAN_sensor_t *sensor_data);
int32_t EventSensors_Read(LoRaWAN_event_sensor_t *sensor_data);
#endif /* SRC_SIGNALS_H_ */

View File

@@ -0,0 +1,139 @@
/**
******************************************************************************
* @file : stm32_nucleo_bus.h
* @brief : header file for the BSP BUS IO driver
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32_NUCLEO_BUS_H
#define STM32_NUCLEO_BUS_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include <stm32_nucleo_conf.h>
#include <stm32_nucleo_errno.h>
/** @addtogroup BSP
* @{
*/
/** @addtogroup STM32F4XX_NUCLEO
* @{
*/
/** @defgroup STM32F4XX_NUCLEO_BUS STM32F4XX_NUCLEO BUS
* @{
*/
/** @defgroup STM32F4XX_NUCLEO_BUS_Exported_Constants STM32F4XX_NUCLEO BUS Exported Constants
* @{
*/
#define BUS_SPI3_INSTANCE SPI3
#define BUS_SPI3_SCK_GPIO_PORT GPIOC
#define BUS_SPI3_SCK_GPIO_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE()
#define BUS_SPI3_SCK_GPIO_CLK_DISABLE() __HAL_RCC_GPIOC_CLK_DISABLE()
#define BUS_SPI3_SCK_GPIO_PIN GPIO_PIN_10
#define BUS_SPI3_SCK_GPIO_AF GPIO_AF6_SPI3
#define BUS_SPI3_MISO_GPIO_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE()
#define BUS_SPI3_MISO_GPIO_PIN GPIO_PIN_11
#define BUS_SPI3_MISO_GPIO_PORT GPIOC
#define BUS_SPI3_MISO_GPIO_CLK_DISABLE() __HAL_RCC_GPIOC_CLK_DISABLE()
#define BUS_SPI3_MISO_GPIO_AF GPIO_AF6_SPI3
#define BUS_SPI3_MOSI_GPIO_CLK_ENABLE() __HAL_RCC_GPIOC_CLK_ENABLE()
#define BUS_SPI3_MOSI_GPIO_AF GPIO_AF6_SPI3
#define BUS_SPI3_MOSI_GPIO_PORT GPIOC
#define BUS_SPI3_MOSI_GPIO_PIN GPIO_PIN_12
#define BUS_SPI3_MOSI_GPIO_CLK_DISABLE() __HAL_RCC_GPIOC_CLK_DISABLE()
#ifndef BUS_SPI3_POLL_TIMEOUT
#define BUS_SPI3_POLL_TIMEOUT 0x1000U
#endif
/* SPI3 Baud rate in bps */
#ifndef BUS_SPI3_BAUDRATE
#define BUS_SPI3_BAUDRATE 10000000U /* baud rate of SPIn = 10 Mbps*/
#endif
/**
* @}
*/
/** @defgroup STM32F4XX_NUCLEO_BUS_Private_Types STM32F4XX_NUCLEO BUS Private types
* @{
*/
#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
typedef struct
{
pSPI_CallbackTypeDef pMspInitCb;
pSPI_CallbackTypeDef pMspDeInitCb;
}BSP_SPI_Cb_t;
#endif /* (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) */
/**
* @}
*/
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Exported_Variables LOW LEVEL Exported Constants
* @{
*/
extern SPI_HandleTypeDef hspi3;
/**
* @}
*/
/** @addtogroup STM32F4XX_NUCLEO_BUS_Exported_Functions
* @{
*/
/* BUS IO driver over SPI Peripheral */
//HAL_StatusTypeDef MX_SPI3_Init(SPI_HandleTypeDef* hspi);
int32_t BSP_SPI3_Init(void);
int32_t BSP_SPI3_DeInit(void);
int32_t BSP_SPI3_Send(uint8_t *pData, uint16_t Length);
int32_t BSP_SPI3_Recv(uint8_t *pData, uint16_t Length);
int32_t BSP_SPI3_SendRecv(uint8_t *pTxData, uint8_t *pRxData, uint16_t Length);
#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
int32_t BSP_SPI3_RegisterDefaultMspCallbacks (void);
int32_t BSP_SPI3_RegisterMspCallbacks (BSP_SPI_Cb_t *Callbacks);
#endif /* (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) */
int32_t BSP_GetTick(void);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* STM32_NUCLEO_BUS_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,73 @@
/**
******************************************************************************
* @file : stm32f4xx_nucleo_conf.h
* @brief : Configuration file
******************************************************************************
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32_NUCLEO_CONF_H
#define STM32_NUCLEO_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stm32l4xx_hal.h"
/** @addtogroup BSP
* @{
*/
/** @addtogroup STM32F4XX_NUCLEO
* @{
*/
/** @defgroup STM32F4XX_NUCLEO_CONFIG Config
* @{
*/
/** @defgroup STM32F4XX_NUCLEO_CONFIG_Exported_Constants
* @{
*/
/* COM Feature define */
#define USE_BSP_COM_FEATURE 1U
/* COM define */
#define USE_COM_LOG 1U
/* IRQ priorities */
#define BSP_BUTTON_USER_IT_PRIORITY 15U
/* I2C1 Frequeny in Hz */
#define BUS_I2C1_FREQUENCY 100000U /* Frequency of I2C1 = 100 KHz*/
/* SPI1 Baud rate in bps */
#define BUS_SPI1_BAUDRATE 16000000U /* baud rate of SPIn = 16 Mbps */
/* UART1 Baud rate in bps */
#define BUS_UART1_BAUDRATE 9600U /* baud rate of UARTn = 9600 baud */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* STM32_NUCLEO_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,48 @@
/**
******************************************************************************
* @file : stm32_nucleo_errno.h
* @brief : Error Code
******************************************************************************
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32_NUCLEO_ERRNO_H
#define STM32_NUCLEO_ERRNO_H
#ifdef __cplusplus
extern "C" {
#endif
/* BSP Common Error codes */
#define BSP_ERROR_NONE 0
#define BSP_ERROR_NO_INIT -1
#define BSP_ERROR_WRONG_PARAM -2
#define BSP_ERROR_BUSY -3
#define BSP_ERROR_PERIPH_FAILURE -4
#define BSP_ERROR_COMPONENT_FAILURE -5
#define BSP_ERROR_UNKNOWN_FAILURE -6
#define BSP_ERROR_UNKNOWN_COMPONENT -7
#define BSP_ERROR_BUS_FAILURE -8
#define BSP_ERROR_CLOCK_FAILURE -9
#define BSP_ERROR_MSP_FAILURE -10
#define BSP_ERROR_FEATURE_NOT_SUPPORTED -11
/* BSP BUS error codes */
#define BSP_ERROR_BUS_TRANSACTION_FAILURE -100
#define BSP_ERROR_BUS_ARBITRATION_LOSS -101
#define BSP_ERROR_BUS_ACKNOWLEDGE_FAILURE -102
#define BSP_ERROR_BUS_PROTOCOL_FAILURE -103
#define BSP_ERROR_BUS_MODE_FAULT -104
#define BSP_ERROR_BUS_FRAME_ERROR -105
#define BSP_ERROR_BUS_CRC_ERROR -106
#define BSP_ERROR_BUS_DMA_FAILURE -107
#ifdef __cplusplus
}
#endif
#endif /*STM32_NUCLEO_ERRNO_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,482 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32l4xx_hal_conf.h
* @author MCD Application Team
* @brief HAL configuration template file.
* This file should be copied to the application folder and renamed
* to stm32l4xx_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 STM32L4xx_HAL_CONF_H
#define STM32L4xx_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_CRYP_MODULE_ENABLED */
#define HAL_CAN_MODULE_ENABLED
#define HAL_COMP_MODULE_ENABLED
/*#define HAL_I2C_MODULE_ENABLED */
/*#define HAL_CRC_MODULE_ENABLED */
/*#define HAL_CRYP_MODULE_ENABLED */
/*#define HAL_DAC_MODULE_ENABLED */
/*#define HAL_DCMI_MODULE_ENABLED */
/*#define HAL_DMA2D_MODULE_ENABLED */
/*#define HAL_DFSDM_MODULE_ENABLED */
/*#define HAL_DSI_MODULE_ENABLED */
/*#define HAL_FIREWALL_MODULE_ENABLED */
/*#define HAL_GFXMMU_MODULE_ENABLED */
/*#define HAL_HCD_MODULE_ENABLED */
/*#define HAL_HASH_MODULE_ENABLED */
/*#define HAL_I2S_MODULE_ENABLED */
/*#define HAL_IRDA_MODULE_ENABLED */
#define HAL_IWDG_MODULE_ENABLED
/*#define HAL_LTDC_MODULE_ENABLED */
/*#define HAL_LCD_MODULE_ENABLED */
/*#define HAL_LPTIM_MODULE_ENABLED */
/*#define HAL_MMC_MODULE_ENABLED */
/*#define HAL_NAND_MODULE_ENABLED */
/*#define HAL_NOR_MODULE_ENABLED */
/*#define HAL_OPAMP_MODULE_ENABLED */
/*#define HAL_OSPI_MODULE_ENABLED */
/*#define HAL_OSPI_MODULE_ENABLED */
/*#define HAL_PCD_MODULE_ENABLED */
/*#define HAL_PKA_MODULE_ENABLED */
/*#define HAL_QSPI_MODULE_ENABLED */
/*#define HAL_QSPI_MODULE_ENABLED */
/*#define HAL_RNG_MODULE_ENABLED */
#define HAL_RTC_MODULE_ENABLED
/*#define HAL_SAI_MODULE_ENABLED */
/*#define HAL_SD_MODULE_ENABLED */
/*#define HAL_SMBUS_MODULE_ENABLED */
/*#define HAL_SMARTCARD_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
/*#define HAL_SRAM_MODULE_ENABLED */
/*#define HAL_SWPMI_MODULE_ENABLED */
#define HAL_TIM_MODULE_ENABLED
/*#define HAL_TSC_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
/*#define HAL_USART_MODULE_ENABLED */
/*#define HAL_WWDG_MODULE_ENABLED */
/*#define HAL_EXTI_MODULE_ENABLED */
/*#define HAL_PSSI_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
/* ########################## 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)8000000U) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< 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)4000000U) /*!< 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)16000000U) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and RNG.
* This internal oscillator is mainly dedicated to provide a high precision clock to
* the USB peripheral by means of a special Clock Recovery System (CRS) circuitry.
* When the CRS is not used, the HSI48 RC oscillator runs on it default frequency
* which is subject to manufacturing process variations.
*/
#if !defined (HSI48_VALUE)
#define HSI48_VALUE ((uint32_t)48000000U) /*!< Value of the Internal High Speed oscillator for USB FS/SDMMC/RNG in Hz.
The real value my vary depending on manufacturing process variations.*/
#endif /* HSI48_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.
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE 32768U /*!< Value of the External 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 /* HSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for SAI1 peripheral
* This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source
* frequency.
*/
#if !defined (EXTERNAL_SAI1_CLOCK_VALUE)
#define EXTERNAL_SAI1_CLOCK_VALUE 2097000U /*!< Value of the SAI1 External clock source in Hz*/
#endif /* EXTERNAL_SAI1_CLOCK_VALUE */
/**
* @brief External clock source for SAI2 peripheral
* This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source
* frequency.
*/
#if !defined (EXTERNAL_SAI2_CLOCK_VALUE)
#define EXTERNAL_SAI2_CLOCK_VALUE 2097000U /*!< Value of the SAI2 External clock source in Hz*/
#endif /* EXTERNAL_SAI2_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 15U /*!< tick interrupt priority */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 1U
#define INSTRUCTION_CACHE_ENABLE 1U
#define DATA_CACHE_ENABLE 1U
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* ################## Register callback feature configuration ############### */
/**
* @brief Set below the peripheral configuration to "1U" to add the support
* of HAL callback registration/deregistration feature for the HAL
* driver(s). This allows user application to provide specific callback
* functions thanks to HAL_PPP_RegisterCallback() rather than overwriting
* the default weak callback functions (see each stm32l4xx_hal_ppp.h file
* for possible callback identifiers defined in HAL_PPP_CallbackIDTypeDef
* for each PPP peripheral).
*/
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U
#define USE_HAL_CAN_REGISTER_CALLBACKS 0U
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U
#define USE_HAL_GFXMMU_REGISTER_CALLBACKS 0U
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U
#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U
#define USE_HAL_OSPI_REGISTER_CALLBACKS 0U
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U
#define USE_HAL_SD_REGISTER_CALLBACKS 0U
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U
#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U
#define USE_HAL_TSC_REGISTER_CALLBACKS 0U
#define USE_HAL_UART_REGISTER_CALLBACKS 0U
#define USE_HAL_USART_REGISTER_CALLBACKS 0U
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U
/* ################## 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 "stm32l4xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32l4xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32l4xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_DFSDM_MODULE_ENABLED
#include "stm32l4xx_hal_dfsdm.h"
#endif /* HAL_DFSDM_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32l4xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32l4xx_hal_adc.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CAN_MODULE_ENABLED
#include "stm32l4xx_hal_can.h"
#endif /* HAL_CAN_MODULE_ENABLED */
#ifdef HAL_CAN_LEGACY_MODULE_ENABLED
#include "Legacy/stm32l4xx_hal_can_legacy.h"
#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32l4xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32l4xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32l4xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32l4xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_DCMI_MODULE_ENABLED
#include "stm32l4xx_hal_dcmi.h"
#endif /* HAL_DCMI_MODULE_ENABLED */
#ifdef HAL_DMA2D_MODULE_ENABLED
#include "stm32l4xx_hal_dma2d.h"
#endif /* HAL_DMA2D_MODULE_ENABLED */
#ifdef HAL_DSI_MODULE_ENABLED
#include "stm32l4xx_hal_dsi.h"
#endif /* HAL_DSI_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32l4xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_GFXMMU_MODULE_ENABLED
#include "stm32l4xx_hal_gfxmmu.h"
#endif /* HAL_GFXMMU_MODULE_ENABLED */
#ifdef HAL_FIREWALL_MODULE_ENABLED
#include "stm32l4xx_hal_firewall.h"
#endif /* HAL_FIREWALL_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32l4xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_HASH_MODULE_ENABLED
#include "stm32l4xx_hal_hash.h"
#endif /* HAL_HASH_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32l4xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32l4xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32l4xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32l4xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LCD_MODULE_ENABLED
#include "stm32l4xx_hal_lcd.h"
#endif /* HAL_LCD_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32l4xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_LTDC_MODULE_ENABLED
#include "stm32l4xx_hal_ltdc.h"
#endif /* HAL_LTDC_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32l4xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
#ifdef HAL_NAND_MODULE_ENABLED
#include "stm32l4xx_hal_nand.h"
#endif /* HAL_NAND_MODULE_ENABLED */
#ifdef HAL_NOR_MODULE_ENABLED
#include "stm32l4xx_hal_nor.h"
#endif /* HAL_NOR_MODULE_ENABLED */
#ifdef HAL_OPAMP_MODULE_ENABLED
#include "stm32l4xx_hal_opamp.h"
#endif /* HAL_OPAMP_MODULE_ENABLED */
#ifdef HAL_OSPI_MODULE_ENABLED
#include "stm32l4xx_hal_ospi.h"
#endif /* HAL_OSPI_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32l4xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PKA_MODULE_ENABLED
#include "stm32l4xx_hal_pka.h"
#endif /* HAL_PKA_MODULE_ENABLED */
#ifdef HAL_PSSI_MODULE_ENABLED
#include "stm32l4xx_hal_pssi.h"
#endif /* HAL_PSSI_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32l4xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_QSPI_MODULE_ENABLED
#include "stm32l4xx_hal_qspi.h"
#endif /* HAL_QSPI_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32l4xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32l4xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SAI_MODULE_ENABLED
#include "stm32l4xx_hal_sai.h"
#endif /* HAL_SAI_MODULE_ENABLED */
#ifdef HAL_SD_MODULE_ENABLED
#include "stm32l4xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32l4xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32l4xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32l4xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm32l4xx_hal_sram.h"
#endif /* HAL_SRAM_MODULE_ENABLED */
#ifdef HAL_SWPMI_MODULE_ENABLED
#include "stm32l4xx_hal_swpmi.h"
#endif /* HAL_SWPMI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32l4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_TSC_MODULE_ENABLED
#include "stm32l4xx_hal_tsc.h"
#endif /* HAL_TSC_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32l4xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32l4xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32l4xx_hal_wwdg.h"
#endif /* HAL_WWDG_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 /* STM32L4xx_HAL_CONF_H */

View File

@@ -0,0 +1,77 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32l4xx_it.h
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32L4xx_IT_H
#define __STM32L4xx_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 DebugMon_Handler(void);
void EXTI0_IRQHandler(void);
void EXTI2_IRQHandler(void);
void EXTI3_IRQHandler(void);
void EXTI4_IRQHandler(void);
void DMA1_Channel1_IRQHandler(void);
void DMA1_Channel2_IRQHandler(void);
void DMA1_Channel7_IRQHandler(void);
void CAN1_RX0_IRQHandler(void);
void EXTI9_5_IRQHandler(void);
void USART2_IRQHandler(void);
void EXTI15_10_IRQHandler(void);
void RTC_Alarm_IRQHandler(void);
void TIM7_IRQHandler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __STM32L4xx_IT_H */

View File

@@ -0,0 +1,121 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file sys_app.h
* @author MCD Application Team
* @brief Function prototypes for sys_app.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SYS_APP_H__
#define __SYS_APP_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "stdint.h"
#include "sys_conf.h"
#include "stm32_adv_trace.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported defines ----------------------------------------------------------*/
/* USER CODE BEGIN ED */
#define VDD_BAT 3200
#define VDD_MIN 1800
/* USER CODE END ED */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macros -----------------------------------------------------------*/
#define APP_PPRINTF(...) do{ } while( UTIL_ADV_TRACE_OK \
!= UTIL_ADV_TRACE_COND_FSend(VLEVEL_ALWAYS, T_REG_OFF, TS_OFF, __VA_ARGS__) ) /* Polling Mode */
#define APP_TPRINTF(...) do{ {UTIL_ADV_TRACE_COND_FSend(VLEVEL_ALWAYS, T_REG_OFF, TS_ON, __VA_ARGS__);} }while(0); /* with timestamp */
#define APP_PRINTF(...) do{ {UTIL_ADV_TRACE_COND_FSend(VLEVEL_ALWAYS, T_REG_OFF, TS_OFF, __VA_ARGS__);} }while(0);
#if defined (APP_LOG_ENABLED) && (APP_LOG_ENABLED == 1)
#define APP_LOG(TS,VL,...) do{ {UTIL_ADV_TRACE_COND_FSend(VL, T_REG_OFF, TS, __VA_ARGS__);} }while(0);
#elif defined (APP_LOG_ENABLED) && (APP_LOG_ENABLED == 0) /* APP_LOG disabled */
#define APP_LOG(TS,VL,...)
#else
#error "APP_LOG_ENABLED not defined or out of range <0,1>"
#endif /* APP_LOG_ENABLED */
#define LED_Init( x )
#define LED_Toggle( x ) HAL_GPIO_TogglePin(Sys_Led[x].port, Sys_Led[x].pin)
#define LED_On( x ) HAL_GPIO_WritePin(Sys_Led[x].port, Sys_Led[x].pin, GPIO_PIN_SET)
#define LED_Off( x ) HAL_GPIO_WritePin(Sys_Led[x].port, Sys_Led[x].pin, GPIO_PIN_RESET)
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/**
* @brief initialize the system (dbg pins, trace, mbmux, sys timer, LPM, ...)
*/
void SystemApp_Init(void);
/**
* @brief callback to get the battery level in % of full charge (254 full charge, 0 no charge)
* @retval battery level
*/
uint8_t GetBatteryLevel(void);
/**
* @brief callback to get the current temperature in the MCU
* @retval temperature level
*/
uint16_t GetTemperatureLevel(void);
/**
* @brief callback to get the board 64 bits unique ID
* @param id unique ID
*/
void GetUniqueId(uint8_t *id);
/**
* @brief callback to get the board 32 bits unique ID (LSB)
* @retval devAddr Device Address
*/
uint32_t GetDevAddr(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __SYS_APP_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,98 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file sys_conf.h
* @author MCD Application Team
* @brief Applicative configuration, e.g. : debug, trace, low power, sensors
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SYS_CONF_H__
#define __SYS_CONF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/**
* @brief Temperature and pressure values are retrieved from sensors shield
* (instead of sending dummy values). It requires MEMS IKS shield
*/
#define SENSOR_ENABLED 0
/**
* @brief Verbose level for all trace logs
*/
#define VERBOSE_LEVEL VLEVEL_H
/**
* @brief Enable trace logs
*/
#define APP_LOG_ENABLED 1
/**
* @brief Enable MCU Debugger pins (dbg serial wires, sbg spi, etc)
*/
#define DEBUGGER_ENABLED 0
/**
* @brief Enable four wires usable as probes (two of them PROBE1 and PROBE2 used by the MW)
*/
#define PROBE_PINS_ENABLED 0
/**
* @brief Disable Low Power mode
* @note 0: LowPowerMode enabled. MCU enters stop2 mode, 1: LowPowerMode disabled. MCU enters sleep mode only
*/
#define LOW_POWER_DISABLE 1
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __SYS_CONF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,94 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file sys_sensors.h
* @author MCD Application Team
* @brief Header for sensors application
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SENSORS_H__
#define __SENSORS_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/**
* Sensor data parameters
*/
typedef struct
{
float pressure; /*!< in mbar */
float temperature; /*!< in degC */
float humidity; /*!< in % */
int32_t latitude; /*!< latitude converted to binary */
int32_t longitude ; /*!< longitude converted to binary */
int16_t altitudeGps; /*!< in m */
int16_t altitudeBar ; /*!< in m * 10 */
/**more may be added*/
/* USER CODE BEGIN sensor_t */
/* USER CODE END sensor_t */
} sensor_t;
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/**
* @brief initialize the environmental sensor
*/
int32_t EnvSensors_Init(void);
/**
* @brief Environmental sensor read.
* @param sensor_data sensor data
*/
int32_t EnvSensors_Read(sensor_t *sensor_data);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __SENSORS_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,118 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file usart_if.h
* @author MCD Application Team
* @brief Header for USART interface configuration
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
#include "stm32_adv_trace.h"
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USART_IF_H__
#define __USART_IF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* 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 */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/**
* @brief Init the UART and associated DMA.
* @param cb TxCpltCallback
* @return @ref UTIL_ADV_TRACE_Status_t
*/
UTIL_ADV_TRACE_Status_t vcom_Init(void (*cb)(void *));
/**
* @brief init receiver of vcom
* @param RxCb callback when Rx char is received
* @return @ref UTIL_ADV_TRACE_Status_t
*/
UTIL_ADV_TRACE_Status_t vcom_ReceiveInit(void (*RxCb)(uint8_t *rxChar, uint16_t size, uint8_t error));
/**
* @brief DeInit the UART and associated DMA.
* @return @ref UTIL_ADV_TRACE_Status_t
*/
UTIL_ADV_TRACE_Status_t vcom_DeInit(void);
/**
* @brief send buffer \p p_data of size \p size to vcom in polling mode
* @param p_data data to be sent
* @param size of buffer p_data to be sent
*/
void vcom_Trace(uint8_t *p_data, uint16_t size);
/**
* @brief send buffer \p p_data of size \p size to vcom using DMA
* @param p_data data to be sent
* @param size of buffer p_data to be sent
* @return @ref UTIL_ADV_TRACE_Status_t
*/
UTIL_ADV_TRACE_Status_t vcom_Trace_DMA(uint8_t *p_data, uint16_t size);
/**
* @brief last byte has been sent on the uart line
*/
void vcom_IRQHandler(void);
/**
* @brief last byte has been sent from memory to uart data register
*/
void vcom_DMA_TX_IRQHandler(void);
/**
* @brief Resume the UART and associated DMA (used by LPM)
*/
void vcom_Resume(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __USART_IF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,158 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file utilities_conf.h
* @author MCD Application Team
* @brief Header for configuration file to utilities
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __UTILITIES_CONF_H__
#define __UTILITIES_CONF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "cmsis_compiler.h"
/* definitions to be provided to "sequencer" utility */
#include "../../Utils/Inc/stm32_mem.h"
/* USER CODE BEGIN Includes */
#include "cmsis_os.h"
#include <stdio.h>
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
#define VLEVEL_OFF 0 /*!< used to set UTIL_ADV_TRACE_SetVerboseLevel() (not as message param) */
#define VLEVEL_ALWAYS 0 /*!< used as message params, if this level is given
trace will be printed even when UTIL_ADV_TRACE_SetVerboseLevel(OFF) */
#define VLEVEL_L 1 /*!< just essential traces */
#define VLEVEL_M 2 /*!< functional traces */
#define VLEVEL_H 3 /*!< all traces */
#define TS_OFF 0 /*!< Log without TimeStamp */
#define TS_ON 1 /*!< Log with TimeStamp */
#define T_REG_OFF 0 /*!< Log without bitmask */
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macros -----------------------------------------------------------*/
/**
* @brief Memory placement macro
*/
#if defined(__CC_ARM)
#define UTIL_PLACE_IN_SECTION( __x__ ) __attribute__((section (__x__), zero_init))
#elif defined(__ICCARM__)
#define UTIL_PLACE_IN_SECTION( __x__ ) __attribute__((section (__x__)))
#else /* __GNUC__ */
#define UTIL_PLACE_IN_SECTION( __x__ ) __attribute__((section (__x__)))
#endif /* __CC_ARM | __ICCARM__ | __GNUC__ */
/**
* @brief Memory alignment macro
*/
#undef ALIGN
#ifdef WIN32
#define ALIGN(n)
#else
#define ALIGN(n) __attribute__((aligned(n)))
#endif /* WIN32 */
/**
* @brief macro used to initialize the critical section
*/
#define UTIL_SEQ_INIT_CRITICAL_SECTION( ) UTILS_INIT_CRITICAL_SECTION()
/**
* @brief macro used to enter the critical section
*/
#define UTIL_SEQ_ENTER_CRITICAL_SECTION( ) UTILS_ENTER_CRITICAL_SECTION()
/**
* @brief macro used to exit the critical section
*/
#define UTIL_SEQ_EXIT_CRITICAL_SECTION( ) UTILS_EXIT_CRITICAL_SECTION()
/**
* @brief Memset utilities interface to application
*/
#define UTIL_SEQ_MEMSET8( dest, value, size ) UTIL_MEM_set_8( dest, value, size )
/**
* @brief macro used to initialize the critical section
*/
#define UTILS_INIT_CRITICAL_SECTION()
/**
* @brief macro used to enter the critical section
*/
#define UTILS_ENTER_CRITICAL_SECTION() uint32_t primask_bit= __get_PRIMASK();__disable_irq()
/**
* @brief macro used to exit the critical section
*/
#define UTILS_EXIT_CRITICAL_SECTION() __set_PRIMASK(primask_bit)
/******************************************************************************
* trace\advanced
* the define option
* UTIL_ADV_TRACE_CONDITIONNAL shall be defined if you want use conditional function
* UTIL_ADV_TRACE_UNCHUNK_MODE shall be defined if you want use the unchunk mode
*
******************************************************************************/
#define UTIL_ADV_TRACE_CONDITIONNAL /*!< not used */
#define UTIL_ADV_TRACE_UNCHUNK_MODE /*!< not used */
#define UTIL_ADV_TRACE_DEBUG(...) /*!< not used */
#define UTIL_ADV_TRACE_INIT_CRITICAL_SECTION( ) UTILS_INIT_CRITICAL_SECTION() /*!< init the critical section in trace feature */
#define UTIL_ADV_TRACE_ENTER_CRITICAL_SECTION( ) UTILS_ENTER_CRITICAL_SECTION() /*!< enter the critical section in trace feature */
#define UTIL_ADV_TRACE_EXIT_CRITICAL_SECTION( ) UTILS_EXIT_CRITICAL_SECTION() /*!< exit the critical section in trace feature */
#define UTIL_ADV_TRACE_TMP_BUF_SIZE (512U) /*!< default trace buffer size */
#define UTIL_ADV_TRACE_TMP_MAX_TIMESTMAP_SIZE (15U) /*!< default trace timestamp size */
#define UTIL_ADV_TRACE_FIFO_SIZE (1024U) /*!< default trace fifo size */
#define UTIL_ADV_TRACE_MEMSET8( dest, value, size) UTIL_MEM_set_8((dest),(value),(size)) /*!< memset utilities interface to trace feature */
#define UTIL_ADV_TRACE_VSNPRINTF(...) vsnprintf(__VA_ARGS__) /*!< vsnprintf utilities interface to trace feature */
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /*__UTILITIES_CONF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,118 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file utilities_def.h
* @author MCD Application Team
* @brief Definitions for modules requiring utilities
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __UTILITIES_DEF_H__
#define __UTILITIES_DEF_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/******************************************************************************
* LOW POWER MANAGER
******************************************************************************/
/**
* Supported requester to the MCU Low Power Manager - can be increased up to 32
* It lists a bit mapping of all user of the Low Power Manager
*/
typedef enum
{
/* USER CODE BEGIN CFG_LPM_Id_t_0 */
/* USER CODE END CFG_LPM_Id_t_0 */
CFG_LPM_APPLI_Id,
CFG_LPM_RTC_Id,
CFG_LPM_UART_TX_Id,
CFG_LPM_TCXO_WA_Id,
/* USER CODE BEGIN CFG_LPM_Id_t */
/* USER CODE END CFG_LPM_Id_t */
} CFG_LPM_Id_t;
/*---------------------------------------------------------------------------*/
/* sequencer definitions */
/*---------------------------------------------------------------------------*/
/**
* This is the list of priority required by the application
* Each Id shall be in the range 0..31
*/
typedef enum
{
CFG_SEQ_Prio_0,
/* USER CODE BEGIN CFG_SEQ_Prio_Id_t */
/* USER CODE END CFG_SEQ_Prio_Id_t */
CFG_SEQ_Prio_NBR,
} CFG_SEQ_Prio_Id_t;
/**
* This is the list of task id required by the application
* Each Id shall be in the range 0..31
*/
typedef enum
{
CFG_SEQ_Task_LmHandlerProcess,
CFG_SEQ_Task_LoRaSendOnTxTimerOrButtonEvent,
/* USER CODE BEGIN CFG_SEQ_Task_Id_t */
CFG_SEQ_Task_LoRaSendOnTxSystemEvent,
/* USER CODE END CFG_SEQ_Task_Id_t */
CFG_SEQ_Task_NBR
} CFG_SEQ_Task_Id_t;
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* External variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __UTILITIES_DEF_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,40 @@
/*
* utils.h
*
* Created on: Apr 10, 2021
* Author: xavie
*/
#ifndef INC_UTILS_H_
#define INC_UTILS_H_
#include <stdlib.h>
#include <stdarg.h>
#include <string.h>
#include <stdbool.h>
#include <ctype.h>
#include "stm32_adv_trace.h"
/**
* @brief it calls UTIL_ADV_TRACE_VSNPRINTF
*/
void tiny_snprintf_like(char *buf, uint32_t maxsize, const char *strFormat, ...);
int8_t isAnyError();
int8_t addErrorToList( uint16_t code );
void clearErrorList();
int8_t findErrorByNo( uint16_t code );
uint16_t findErrorById( int8_t id );
void deleteErrorByNo( uint16_t code );
void deleteErrorById( int8_t id );
void substring(char s[], char sub[], int startIndex, int endIndex );
int toInt( char in[], int startIndex, int endIndex );
int toIntLen( char in[], int length );
long toLongLen( char in[], int length );
float toFloat( char in[], int startIndex, int endIndex );
bool toBool( char in[], int startIndex );
#endif /* INC_UTILS_H_ */

View File

@@ -0,0 +1,311 @@
/**
******************************************************************************
* File Name : app_bluenrg_ms.c
* Description : Source file
*
******************************************************************************
*
* COPYRIGHT 2021 STMicroelectronics
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <automation.h>
#include "app_bluenrg_ms.h"
#include "hci_tl.h"
#include "sample_service.h"
#include "bluenrg_utils.h"
#include "bluenrg_gatt_server.h"
#include "bluenrg_gap_aci.h"
#include "bluenrg_gatt_aci.h"
#include "bluenrg_hal_aci.h"
/* USER CODE BEGIN Includes */
#include "cmsis_os.h"
#include "task.h"
#include "signals.h"
#include "utils.h"
/* USER CODE END Includes */
/* Private defines -----------------------------------------------------------*/
#define BDADDR_SIZE 6
/* Private macros ------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
static volatile uint8_t user_button_init_state = 1;
volatile uint8_t user_button_pressed = 0;
static volatile uint8_t errorToDisplay;
extern volatile uint8_t set_connectable;
extern volatile int connected;
extern volatile uint8_t notification_tx_enabled, notification_fsm_enabled;
extern osTimerId ErrorDisplayTimerHandle;
extern osMutexId errorListMutexHandle;
/* USER CODE BEGIN PV */
FiniteStateMachine last_finiteStateMachine = { IDLE };
extern FiniteStateMachine finiteStateMachine;
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
static void User_Process(void);
/* USER CODE BEGIN PFP */
void HAL_Delay(volatile uint32_t millis)
{
/* replace HAL library blocking delay function
* with FreeRTOS thread aware equivalent */
osDelay(millis);
}
/* USER CODE END PFP */
void ErrorDisplayCallback( void const * arg )
{
static bool stopSending = false;
/* Check if any error to display */
if( !connected )
return;
osStatus status = osMutexWait(errorListMutexHandle, 5000);
if (status == osOK)
{
uint8_t maxErr = isAnyError();
if( maxErr > 0 )
{
stopSending = false;
sendBLEerror( findErrorById( errorToDisplay++ ) );
if( errorToDisplay >= maxErr )
errorToDisplay = 0;
}
else if( !stopSending )
{
sendBLEerror( 0 );
stopSending = true;
}
osMutexRelease(errorListMutexHandle);
}
}
void MX_BlueNRG_MS_Init(void)
{
/* USER CODE BEGIN SV */
/* USER CODE END SV */
/* USER CODE BEGIN BlueNRG_MS_Init_PreTreatment */
/* USER CODE END BlueNRG_MS_Init_PreTreatment */
/* Initialize the peripherals and the BLE Stack */
uint8_t SERVER_BDADDR[] = {0xaa, 0x00, 0x00, 0xE1, 0x80, 0xaa};
uint8_t bdaddr[BDADDR_SIZE];
uint16_t service_handle, dev_name_char_handle, appearance_char_handle;
uint8_t hwVersion;
uint16_t fwVersion;
int ret;
/* Get the User Button initial state */
user_button_init_state = (uint32_t)(HAL_GPIO_ReadPin(USR_BTN_GPIO_Port, USR_BTN_Pin) == GPIO_PIN_RESET);
// Wait for others threads start
HAL_Delay(2000);
hci_init(user_notify, NULL);
/* get the BlueNRG HW and FW versions */
getBlueNRGVersion(&hwVersion, &fwVersion);
/*
* Reset BlueNRG again otherwise we won't
* be able to change its MAC address.
* aci_hal_write_config_data() must be the first
* command after reset otherwise it will fail.
*/
hci_reset();
HAL_Delay(100);
APP_LOG(TS_OFF, VLEVEL_M, "BLE HWver %d, FWver %d\r\n", hwVersion, fwVersion);
BLUENRG_memcpy(bdaddr, SERVER_BDADDR, sizeof(SERVER_BDADDR));
ret = aci_hal_write_config_data(CONFIG_DATA_PUBADDR_OFFSET,
CONFIG_DATA_PUBADDR_LEN,
bdaddr);
if (ret) {
APP_LOG(TS_OFF, VLEVEL_M, "Setting BD_ADDR failed 0x%02x.\r\n", ret);
}
ret = aci_gatt_init();
if (ret) {
APP_LOG(TS_OFF, VLEVEL_M, "GATT_Init failed.\r\n");
}
// GAP peripheral role setting
ret = aci_gap_init_IDB05A1(GAP_PERIPHERAL_ROLE_IDB05A1, 0, 0x07, &service_handle, &dev_name_char_handle, &appearance_char_handle);
if (ret != BLE_STATUS_SUCCESS) {
APP_LOG(TS_OFF, VLEVEL_M, "GAP_Init failed.\r\n");
}
ret = aci_gap_set_auth_requirement(MITM_PROTECTION_REQUIRED,
OOB_AUTH_DATA_ABSENT,
NULL,
7,
16,
USE_FIXED_PIN_FOR_PAIRING,
123456,
BONDING);
if (ret == BLE_STATUS_SUCCESS) {
APP_LOG(TS_OFF, VLEVEL_M, "BLE Stack Initialized.\r\n");
}
APP_LOG(TS_OFF, VLEVEL_M, "SERVER: BLE Stack Initialized\r\n");
ret = Add_Sample_Service();
if (ret == BLE_STATUS_SUCCESS)
{
APP_LOG(TS_OFF, VLEVEL_M, "Service added successfully.\r\n");
}
else
{
APP_LOG(TS_OFF, VLEVEL_M, "Error while adding service.\r\n");
}
/* Set output power level */
ret = aci_hal_set_tx_power_level(1,6);
/* USER CODE BEGIN BlueNRG_MS_Init_PostTreatment */
errorToDisplay = 0;
osStatus status = osTimerStart( ErrorDisplayTimerHandle, 2000 );
if( status != osOK )
APP_LOG(TS_OFF, VLEVEL_M, "Error starting error display timer\r\n");
/* USER CODE END BlueNRG_MS_Init_PostTreatment */
}
/*
* BlueNRG-MS background task
*/
void MX_BlueNRG_MS_Process(void)
{
/* USER CODE BEGIN BlueNRG_MS_Process_PreTreatment */
/* USER CODE END BlueNRG_MS_Process_PreTreatment */
User_Process();
hci_user_evt_proc();
/* USER CODE BEGIN BlueNRG_MS_Process_PostTreatment */
/* USER CODE END BlueNRG_MS_Process_PostTreatment */
}
/**
* @brief Configure the device as Client or Server and manage the communication
* between a client and a server.
*
* @param None
* @retval None
*/
static void User_Process(void)
{
if (set_connectable)
{
/* Establish connection with remote device */
Make_Connection();
set_connectable = FALSE;
user_button_init_state = (uint32_t)(HAL_GPIO_ReadPin(USR_BTN_GPIO_Port, USR_BTN_Pin) == GPIO_PIN_RESET);
}
if( connected && (last_finiteStateMachine.stm != finiteStateMachine.stm) )
{
updateFSM( finiteStateMachine );
if( last_finiteStateMachine.stm == APERIODIC && finiteStateMachine.stm == PERIODIC )
clearErrorList();
//if( last_finiteStateMachine == E_STOP && finiteStateMachine == APERIODIC )
if( finiteStateMachine.stm != ESTOP )
deleteErrorByNo( 0x112 );
last_finiteStateMachine = finiteStateMachine;
}
/* Check if the User Button has been pushed */
if (user_button_pressed)
{
/* Debouncing */
HAL_Delay(50);
/* Wait until the User Button is released */
while ((HAL_GPIO_ReadPin(USR_BTN_GPIO_Port, USR_BTN_Pin) == GPIO_PIN_RESET) == !user_button_init_state);
/* Debouncing */
HAL_Delay(50);
finiteStateMachine.stm = ESTOP;
addErrorToList( 0x112 );
/* Reset the User Button flag */
user_button_pressed = 0;
}
}
static void Ble_processFrame()
{
MX_BlueNRG_MS_Process();
osDelay( 5 );
}
static void Ble_processMsg(MSG_STRUCT *p_msg)
{
if( p_msg->opcode == CAN_ECHO || p_msg->opcode == OP_OUTPUT_ONCHANGE ) {
sendData( (uint8_t *)&(p_msg->data[2]), p_msg->lParam[0] );
}
else {
readATcommand( strlen(p_msg->data), (uint8_t *)p_msg->data );
}
}
void vBleTask( void *pvParameters )
{
/* Remove warning for unused parameter */
(void)pvParameters ;
osMessageQId myQueueId = getQueueId(BLE_COMM);
osEvent event;
MX_BlueNRG_MS_Init();
while(1)
{
event = osMessageGet( myQueueId, 100 );
if (event.status == osEventMessage)
{
MSG_STRUCT* p_recvMsg = event.value.p;
Ble_processMsg(p_recvMsg);
freeMemoryPoolMessage(p_recvMsg);
}
else if (event.status == osEventTimeout) {
Ble_processFrame();
}
}
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,888 @@
/**
******************************************************************************
* @file sample_service.c
* @author MCD Application Team
* @version V1.0.0
* @date 04-July-2014
* @brief Add a sample service using a vendor specific profile.
******************************************************************************
* @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 <automation.h>
#include "sample_service.h"
#include "bluenrg_gap_aci.h"
#include "bluenrg_gatt_aci.h"
#include "bluenrg_hal_aci.h"
#include "main.h"
#include "rtc_if.h"
#include <string.h>
#include <stdlib.h>
#include "signals.h"
#include "parcelize.h"
#include "crc32.h"
#define CHUNK_SIZE 17
/** @addtogroup Applications
* @{
*/
/** @addtogroup SampleApp
* @{
*/
/** @defgroup SAMPLE_SERVICE
* @{
*/
/** @defgroup SAMPLE_SERVICE_Private_Variables
* @{
*/
/* Private variables ---------------------------------------------------------*/
volatile int connected = FALSE;
volatile uint8_t set_connectable = 1;
volatile uint16_t connection_handle = 0;
volatile uint8_t notification_tx_enabled = FALSE, notification_fsm_enabled = FALSE,
notification_err_enabled = FALSE;
uint16_t tx_handle;
uint16_t rx_handle;
uint16_t date_handle;
uint16_t state_handle;
uint16_t err_handle;
uint16_t sampleServHandle, TXCharHandle, RXCharHandle, DateCharHandle, StateCharHandle, ErrCharHandle;
extern RTC_HandleTypeDef hrtc;
extern FiniteStateMachine finiteStateMachine;
bool uploadingInProgress = false;
int dataSize = 0;
int totalDataTransfer = 0;
long crcDataFromSender = 0;
char uploadBuffer[SETTINGS_BUFFER_SIZE];
uint16_t calib_buffer[6] = {0};
extern FLASH_STRUCT Flash;
extern uint16_t programDuration[];
extern WATERING_GENERAL default_settings;
extern volatile uint16_t outputs74HC955;
/**
* @}
*/
/** @defgroup SAMPLE_SERVICE_Private_Macros
* @{
*/
/* Private macros ------------------------------------------------------------*/
#define COPY_UUID_128(uuid_struct, uuid_15, uuid_14, uuid_13, uuid_12, uuid_11, uuid_10, uuid_9, uuid_8, uuid_7, uuid_6, uuid_5, uuid_4, uuid_3, uuid_2, uuid_1, uuid_0) \
do {\
uuid_struct.uuid128[0] = uuid_0; uuid_struct.uuid128[1] = uuid_1; uuid_struct.uuid128[2] = uuid_2; uuid_struct.uuid128[3] = uuid_3; \
uuid_struct.uuid128[4] = uuid_4; uuid_struct.uuid128[5] = uuid_5; uuid_struct.uuid128[6] = uuid_6; uuid_struct.uuid128[7] = uuid_7; \
uuid_struct.uuid128[8] = uuid_8; uuid_struct.uuid128[9] = uuid_9; uuid_struct.uuid128[10] = uuid_10; uuid_struct.uuid128[11] = uuid_11; \
uuid_struct.uuid128[12] = uuid_12; uuid_struct.uuid128[13] = uuid_13; uuid_struct.uuid128[14] = uuid_14; uuid_struct.uuid128[15] = uuid_15; \
}while(0)
/**
* @}
*/
/** @defgroup SAMPLE_SERVICE_Exported_Functions
* @{
*/
static void sendCommandToOutputs( uint16_t id, ActuatorStates changeState, uint8_t pumpRate );
static void sendCommandToAutomation( uint16_t id, ActuatorStates changeState );
static void sendCommandToSystem( CommandOpcode opcode, uint16_t param[6] );
/**
* @brief Add a sample service using a vendor specific profile
* @param None
* @retval Status
*/
tBleStatus Add_Sample_Service(void)
{
tBleStatus ret;
/*
UUIDs:
D973F2E0-B19E-11E2-9E96-0800200C9A66
D973F2E1-B19E-11E2-9E96-0800200C9A66
D973F2E2-B19E-11E2-9E96-0800200C9A66
D973F2E3-B19E-11E2-9E96-0800200C9A66
D973F2E4-B19E-11E2-9E96-0800200C9A66
D973F2E5-B19E-11E2-9E96-0800200C9A66
*/
const uint8_t service_uuid[16] = {0x66,0x9a,0x0c,0x20,0x00,0x08,0x96,0x9e,0xe2,0x11,0x9e,0xb1,0xe0,0xf2,0x73,0xd9};
const uint8_t charUuidTX[16] = {0x66,0x9a,0x0c,0x20,0x00,0x08,0x96,0x9e,0xe2,0x11,0x9e,0xb1,0xe1,0xf2,0x73,0xd9};
const uint8_t charUuidRX[16] = {0x66,0x9a,0x0c,0x20,0x00,0x08,0x96,0x9e,0xe2,0x11,0x9e,0xb1,0xe2,0xf2,0x73,0xd9};
const uint8_t charUuidDate[16] = {0x66,0x9a,0x0c,0x20,0x00,0x08,0x96,0x9e,0xe2,0x11,0x9e,0xb1,0xe3,0xf2,0x73,0xd9};
const uint8_t charUuidState[16] = {0x66,0x9a,0x0c,0x20,0x00,0x08,0x96,0x9e,0xe2,0x11,0x9e,0xb1,0xe4,0xf2,0x73,0xd9};
const uint8_t charUuidErr[16] = {0x66,0x9a,0x0c,0x20,0x00,0x08,0x96,0x9e,0xe2,0x11,0x9e,0xb1,0xe5,0xf2,0x73,0xd9};
ret = aci_gatt_add_serv(UUID_TYPE_128, service_uuid, PRIMARY_SERVICE, 16, &sampleServHandle); /* 1 for service + 3 for each characteristics */
if (ret != BLE_STATUS_SUCCESS) goto fail;
ret = aci_gatt_add_char(sampleServHandle, UUID_TYPE_128, charUuidTX, 20, CHAR_PROP_NOTIFY, ATTR_PERMISSION_NONE, 0,
16, 1, &TXCharHandle);
if (ret != BLE_STATUS_SUCCESS) goto fail;
ret = aci_gatt_add_char(sampleServHandle, UUID_TYPE_128, charUuidRX, 20, CHAR_PROP_WRITE|CHAR_PROP_WRITE_WITHOUT_RESP, ATTR_PERMISSION_NONE, GATT_NOTIFY_ATTRIBUTE_WRITE,
16, 1, &RXCharHandle);
if (ret != BLE_STATUS_SUCCESS) goto fail;
//ret = aci_gatt_add_char(sampleServHandle, UUID_TYPE_128, charUuidTemp, 10, CHAR_PROP_READ | CHAR_PROP_WRITE_WITHOUT_RESP, ATTR_PERMISSION_NONE, GATT_NOTIFY_ATTRIBUTE_WRITE | GATT_NOTIFY_READ_REQ_AND_WAIT_FOR_APPL_RESP,
// 16, 1, &TempCharHandle);
ret = aci_gatt_add_char(sampleServHandle, UUID_TYPE_128, charUuidDate, 13, CHAR_PROP_READ, ATTR_PERMISSION_NONE, GATT_NOTIFY_READ_REQ_AND_WAIT_FOR_APPL_RESP,
16, 1, &DateCharHandle);
if (ret != BLE_STATUS_SUCCESS) goto fail;
ret = aci_gatt_add_char(sampleServHandle, UUID_TYPE_128, charUuidState, 2, CHAR_PROP_NOTIFY | CHAR_PROP_WRITE_WITHOUT_RESP, ATTR_PERMISSION_NONE, GATT_NOTIFY_ATTRIBUTE_WRITE,
16, 1, &StateCharHandle);
if (ret != BLE_STATUS_SUCCESS) goto fail;
ret = aci_gatt_add_char(sampleServHandle, UUID_TYPE_128, charUuidErr, 2, CHAR_PROP_NOTIFY, ATTR_PERMISSION_NONE, 0,
16, 1, &ErrCharHandle);
if (ret != BLE_STATUS_SUCCESS) goto fail;
return BLE_STATUS_SUCCESS;
fail:
APP_LOG(TS_OFF, VLEVEL_M, "Error while adding I-Spritz Service.\r\n");
return BLE_STATUS_ERROR ;
}
/**
* @brief Make the device connectable
* @param None
* @retval None
*/
void Make_Connection(void)
{
tBleStatus ret;
const char local_name[] = {AD_TYPE_COMPLETE_LOCAL_NAME,'i','-','s','p','r','i','t','z'};
/* disable scan response */
hci_le_set_scan_resp_data(0,NULL);
APP_LOG(TS_OFF, VLEVEL_M, "General Discoverable Mode ");
/*
Advertising_Event_Type, Adv_Interval_Min, Adv_Interval_Max, Address_Type, Adv_Filter_Policy,
Local_Name_Length, Local_Name, Service_Uuid_Length, Service_Uuid_List, Slave_Conn_Interval_Min,
Slave_Conn_Interval_Max
*/
/*ret = aci_gap_set_discoverable(ADV_DATA_TYPE, ADV_INTERV_MIN, ADV_INTERV_MAX, PUBLIC_ADDR,
NO_WHITE_LIST_USE, 9, local_name, 0, NULL, 0, 0);*/
ret = aci_gap_set_discoverable(ADV_DATA_TYPE, 0, 0, PUBLIC_ADDR,
NO_WHITE_LIST_USE, 9, local_name, 0, NULL, 0, 0);
APP_LOG(TS_OFF, VLEVEL_M, "%d\r\n",ret);
}
/**
* @brief This function is used to receive data related to the sample service
* (received over the air from the remote board).
* @param data_buffer : pointer to store in received data
* @param Nb_bytes : number of bytes to be received
* @retval None
*/
void receiveData(uint8_t* data_buffer, uint8_t Nb_bytes)
{
char out[10];
time_t lastCurrentDayCycle[4];
if( uploadingInProgress )
{
strncat(&uploadBuffer[totalDataTransfer],(char*)data_buffer,Nb_bytes);
totalDataTransfer += Nb_bytes;
if( totalDataTransfer == dataSize )
{
memcpy(lastCurrentDayCycle,Flash.paramSys.currentDayCycle,sizeof(Flash.paramSys.currentDayCycle));
uint32_t crc = calcCRC32stm(uploadBuffer, dataSize, 0x04C11DB7, 0xffffffff, 1, 1, 1);
uploadingInProgress = false;
bool transferOK = (crc == crcDataFromSender);
sprintf(out,"#U=%d", transferOK ? 1 : 0);
sendData( (uint8_t*)out, strlen(out) );
APP_LOG(TS_OFF, VLEVEL_M, "\r\n%s\r\n", uploadBuffer);
if( transferOK )
{
//WATERING_GENERAL new_settings;
GeneralUnparcelize( uploadBuffer, &Flash.settings );
initCurrentDayCycle(&lastCurrentDayCycle);
saveSettings( &Flash );
}
}
}
else
{
for(int i = 0; i < Nb_bytes; i++) {
APP_LOG(TS_OFF, VLEVEL_M, "%c", data_buffer[i]);
}
fflush(stdout);
}
}
void setDefaultSettings()
{
Flash.settings = default_settings;
initCurrentDayCycle(NULL);
saveSettings( &Flash );
}
void downloadingSettings()
{
char out[50];
char* se_buff = (char*)pvPortMalloc(SETTINGS_BUFFER_SIZE);
if( !se_buff )
{
APP_LOG(TS_OFF, VLEVEL_M, "Not enough memory\r\n");
}
else
{
memset(se_buff,0,SETTINGS_BUFFER_SIZE);
int size = GeneralParcelize(se_buff);
uint32_t crc = calcCRC32stm(se_buff, size, 0x04C11DB7, 0xffffffff, 1, 1, 1);
sprintf(out,"#D=%04d,%08lX",size,crc);
sendData( (uint8_t*)out, strlen(out) );
// Calculate chunk number
uint16_t nChunk = size / CHUNK_SIZE;
uint16_t remain = size % CHUNK_SIZE;
if( remain > 0 )
nChunk += 1;
// Sending data
for( int c=0; c < nChunk; c++ )
{
out[1] = c+1;
if( c == nChunk - 1 )
{
out[0]=51;
size = remain;
if( !size )
size = CHUNK_SIZE;
}
else
{
out[0]=50;
size = CHUNK_SIZE;
}
strncpy(&out[2],&se_buff[c*CHUNK_SIZE],size);
out[size+2] = '\0';
//APP_LOG(TS_OFF, VLEVEL_M, out);
sendData( (uint8_t*)out, strlen(out) );
osDelay(50);
}
vPortFree(se_buff);
}
}
void uploadingSettings( char* data_buffer )
{
char out[10] = {0};
dataSize = toInt( data_buffer, 0, 4 );
substring(data_buffer,out,5,13);
crcDataFromSender = strtoul(out,0,16);
uploadingInProgress = true;
totalDataTransfer = 0;
memset(uploadBuffer,0,sizeof(uploadBuffer));
}
static void sendCommandToAutomation( uint16_t id, ActuatorStates changeState )
{
osMessageQId destQueue;
//BaseType_t xHigherPriorityTaskWoken;
destQueue = (osMessageQId)getQueueId(AUTOMATION);
//xHigherPriorityTaskWoken = pdFALSE;
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = OP_MAIN;
p_sendMsg->outputs = id;
p_sendMsg->changeState = changeState;
//xQueueSendFromISR(destQueue, &p_sendMsg, &xHigherPriorityTaskWoken);
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
void receiveDateTime(char* data_buffer)
{
struct tm* localTime;
//time_t utc = (time_t)atol(data_buffer);
time_t utc = (time_t)toLongLen( data_buffer, 10 );
Flash.settings.timeZoneOffset = (int8_t)toIntLen( &data_buffer[12], 3);
// utc += (Flash.settings.timeZoneOffset*3600); // Don't work
localTime = localtime(&utc);
set_time( localTime->tm_mday, localTime->tm_mon+1, localTime->tm_year-100, localTime->tm_hour, localTime->tm_min, localTime->tm_sec);
APP_LOG(TS_OFF, VLEVEL_M, "Setting date & time to %s\r\n",asctime(localTime));
sendCommandToAutomation( 0b11111111111, Z_UPDATE );
}
static void sendCommandToOutputs( uint16_t id, ActuatorStates changeState, uint8_t pumpRate )
{
osMessageQId destQueue;
destQueue = (osMessageQId)getQueueId(OUTPUTS);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = OP_OUTPUT_ONCHANGE;
p_sendMsg->outputs = id;
p_sendMsg->changeState = changeState;
p_sendMsg->pumpRate = pumpRate;
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
void driveManyValves(char* data_buffer)
{
uint8_t actuatorId = toIntLen( data_buffer, 3 );
uint8_t avgPumpRate = toIntLen( &data_buffer[4], 3);
//APP_LOG(TS_OFF, VLEVEL_M, "Bluetooth buffer: %s\r\n",data_buffer);
sendCommandToOutputs( actuatorId, Z_UPDATE, avgPumpRate );
}
void emergencyStop()
{
sendCommandToAutomation( ALL_OUTPUTS_OFF, E_STOP );
}
void safeStop()
{
sendCommandToAutomation( ALL_OUTPUTS_OFF, Z_ALL_OFF );
}
void getWateringStats()
{
uint8_t buff[1024] = {0}, out[30];
struct tm current_time;
time_t current_t;
strcpy((char*)buff,"Durées d'arrosage par programme:\n");
now(&current_time);
current_t = mktime(&current_time);
for( int i=0; i<4; i++ )
{
uint8_t diffD = dayCycleRemaining( current_t, i );
sprintf((char*)out,"%c: %d min.",'A'+i,programDuration[i]);
strcat((char*)buff,(char*)out);
if( diffD > 0 )
{
sprintf((char*)out,", dans %d jr\n",diffD);
strcat((char*)buff,(char*)out);
}
else
strcat((char*)buff,"\n");
}
strcat((char*)buff,"Séquences d'arrosage du jour:\n");
int index = strlen((char*)buff);
dailyWatering((char*)&buff[index]);
int size = strlen((char*)buff);
uint32_t crc = calcCRC32stm(buff, size, 0x04C11DB7, 0xffffffff, 1, 1, 1);
sprintf((char*)out,"#d=%04d,%08lX",size,crc);
sendData( (uint8_t*)out, strlen((char*)out) );
// Calculate chunk number
uint16_t nChunk = size / CHUNK_SIZE;
uint16_t remain = size % CHUNK_SIZE;
if( remain > 0 )
nChunk += 1;
else if( remain == 0)
remain = CHUNK_SIZE;
// Sending data
for( int c=0; c < nChunk; c++ )
{
out[1] = c+1;
if( c == nChunk - 1 )
{
out[0]=51;
size = remain;
}
else
{
out[0]=50;
size = CHUNK_SIZE;
}
strncpy((char*)&out[2],(char*)&buff[c*CHUNK_SIZE],size);
out[size+2] = '\0';
//APP_LOG(TS_OFF, VLEVEL_M, out);
sendData( (uint8_t*)out, strlen((char*)out) );
osDelay(50);
}
}
void spyCANbus( char* data_buffer )
{
osMessageQId destQueue;
destQueue = (osMessageQId)getQueueId(CAN_COMM);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
uint8_t state = toIntLen( data_buffer, 1 );
p_sendMsg->opcode = (state == 1 ? CAN_ECHO : CAN_NOECHO);
p_sendMsg->lParam[0] = 0;
if( data_buffer[1] == ',' ) // filter is active
{
uint16_t address = toIntLen( data_buffer, 3);
p_sendMsg->lParam[0] = address;
}
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
void requestStateMachine()
{
updateFSM( finiteStateMachine );
}
static void sendCommandToCAN( CommandOpcode opcode, uint16_t param[6] )
{
osMessageQId destQueue;
destQueue = (osMessageQId)getQueueId(CAN_COMM);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = opcode;
memcpy(p_sendMsg->lParam,param,12);
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
static void sendCommandToSystem( CommandOpcode opcode, uint16_t param[6] )
{
osMessageQId destQueue;
destQueue = (osMessageQId)getQueueId(AUTOMATION);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->changeState = UPDATE_SETTINGS;
p_sendMsg->opcode = opcode;
memcpy(p_sendMsg->lParam,param,12);
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
void setAuxOutputFeature(char* data_buffer)
{
uint16_t p[6] = {0};
p[0] = toIntLen( data_buffer, 1); // Output no
p[1] = toIntLen( &data_buffer[2], 1); // autorun disabled/enabled
p[2] = toIntLen( &data_buffer[4], 1); // ActuatorAutoRunning (0..4)
p[3] = toIntLen( &data_buffer[6], 3); // Low limit
p[4] = toIntLen( &data_buffer[10], 3); // High limit
sendCommandToSystem( OP_FEATURE, p );
}
void setModuleCalibration(char* data_buffer, int nParam )
{
calib_buffer[0] = toIntLen( data_buffer, 4);
calib_buffer[1] = toIntLen( &data_buffer[5], 1);
if( calib_buffer[1] > 3)
{
int len = strlen( data_buffer ) - 7;
int index = calib_buffer[1] - 4;
calib_buffer[2+index] = toIntLen( &data_buffer[7], len );
if( index < (nParam-1) )
return;
}
sendCommandToCAN( OP_CAN, calib_buffer );
memset(calib_buffer,0,12);
}
static void runCycle()
{
sendCommandToAutomation( ALL_OUTPUTS_OFF, Z_RESTART );
}
void systemReset()
{
sendCommandToAutomation( ALL_OUTPUTS_OFF, Z_ALL_OFF );
HAL_NVIC_DisableIRQ(EXTI0_IRQn);
osDelay(1500);
HAL_NVIC_EnableIRQ(EXTI0_IRQn);
osDelay(1500);
runCycle();
}
/**
* @brief This function is used to send data related to the sample service
* (to be sent over the air to the remote board).
* @param data_buffer : pointer to data to be sent
* @param Nb_bytes : number of bytes to send
* @retval None
*/
void sendData( uint8_t* data_buffer, uint8_t Nb_bytes )
{
aci_gatt_update_char_value(sampleServHandle, TXCharHandle, 0, Nb_bytes, data_buffer);
}
void sendBLEerror( uint16_t errno )
{
aci_gatt_update_char_value(sampleServHandle, ErrCharHandle, 0, 2, &errno);
}
void updateFSM()
{
aci_gatt_update_char_value(sampleServHandle, StateCharHandle, 0, 1, &finiteStateMachine);
}
void updateReg75HC955()
{
char buff[3] = {'#', 'O', 0 };
buff[2]= outputs74HC955 & 0x00FF;
aci_gatt_update_char_value(sampleServHandle, RXCharHandle, 0, 3, buff);
}
/**
* @brief This function is called when an attribute gets modified
* @param handle : handle of the attribute
* @param data_length : size of the modified attribute data
* @param att_data : pointer to the modified attribute data
* @retval None
*/
void Attribute_Modified_CB(uint16_t handle, uint8_t data_length, uint8_t *att_data)
{
if(handle == RXCharHandle + 1)
{
readATcommand(data_length, att_data );
}
else if (handle == TXCharHandle + 2)
{
if(att_data[0] == 0x01)
notification_tx_enabled = TRUE;
}
else if (handle == StateCharHandle + 1)
{
finiteStateMachine.stm = att_data[0];
}
else if (handle == ErrCharHandle + 2)
{
if(att_data[0] == 0x01)
notification_err_enabled = TRUE;
}
}
/**
* @brief This function is called when there is a LE Connection Complete event.
* @param addr : Address of peer device
* @param handle : Connection handle
* @retval None
*/
void GAP_ConnectionComplete_CB(uint8_t addr[6], uint16_t handle)
{
connected = TRUE;
connection_handle = handle;
APP_LOG(TS_OFF, VLEVEL_M, "Connected to device:");
for(int i = 5; i > 0; i--){
APP_LOG(TS_OFF, VLEVEL_M, "%02X-", addr[i]);
}
APP_LOG(TS_OFF, VLEVEL_M, "%02X\r\n", addr[0]);
}
/**
* @brief This function is called when the peer device get disconnected.
* @param None
* @retval None
*/
void GAP_DisconnectionComplete_CB(void)
{
connected = FALSE;
APP_LOG(TS_OFF, VLEVEL_M, "Disconnected\r\n");
if( finiteStateMachine.stm == APERIODIC )
safeStop();
/* Make the device connectable again. */
set_connectable = TRUE;
notification_tx_enabled = FALSE;
notification_fsm_enabled = FALSE;
notification_err_enabled = FALSE;
}
/**
* @brief This function is called when there is a notification from the server.
* @param attr_handle Handle of the attribute
* @param attr_len Length of attribute value in the notification
* @param attr_value Attribute value in the notification
* @retval None
*/
void GATT_Notification_CB(uint16_t attr_handle, uint8_t attr_len, uint8_t *attr_value)
{
if (attr_handle == tx_handle+1) {
receiveData(attr_value, attr_len);
}
}
/**
* @brief This function is called when a read request or read blob request is received.
* @param attr_handle Handle of the attribute
* @param attr_len Length of attribute value in the read
* @param attr_value Attribute value in the read
* @retval None
*/
void GATT_Read_Permit_Req_CB(uint16_t attr_handle, uint8_t attr_len, uint8_t *attr_value)
{
if (attr_handle == date_handle+1)
{
}
else if (attr_handle == state_handle+1)
{
finiteStateMachine.stm = attr_value[0];
}
else if (attr_handle == err_handle+1)
{
}
}
/**
* @brief This function is called whenever there is an ACI event to be processed.
* @note Inside this function each event must be identified and correctly
* parsed.
* @param pData Pointer to the ACI packet
* @retval None
*/
void user_notify(void * pData)
{
hci_uart_pckt *hci_pckt = pData;
uint8_t dummy;
/* obtain event packet */
hci_event_pckt *event_pckt = (hci_event_pckt*)hci_pckt->data;
if(hci_pckt->type != HCI_EVENT_PKT)
return;
switch(event_pckt->evt){
case EVT_DISCONN_COMPLETE:
{
GAP_DisconnectionComplete_CB();
}
break;
case EVT_LE_META_EVENT:
{
evt_le_meta_event *evt = (void *)event_pckt->data;
switch(evt->subevent){
case EVT_LE_CONN_COMPLETE:
{
evt_le_connection_complete *cc = (void *)evt->data;
GAP_ConnectionComplete_CB(cc->peer_bdaddr, cc->handle);
}
break;
case EVT_LE_CONN_UPDATE_COMPLETE:
{
//evt_le_connection_update_complete *cc = (void *)evt->data;
}
break;
}
}
break;
case EVT_VENDOR:
{
evt_blue_aci *blue_evt = (void*)event_pckt->data;
//APP_LOG(TS_ON, VLEVEL_M,"EVT_VENDOR %d\r\n", blue_evt->ecode);
switch(blue_evt->ecode){
case EVT_BLUE_GATT_ATTRIBUTE_MODIFIED:
{
//APP_LOG(TS_ON, VLEVEL_M,"EVT_BLUE_GATT_ATTRIBUTE_MODIFIED\r\n");
evt_gatt_attr_modified_IDB05A1 *evt = (evt_gatt_attr_modified_IDB05A1*)blue_evt->data;
Attribute_Modified_CB(evt->attr_handle, evt->data_length, evt->att_data);
}
break;
case EVT_BLUE_GATT_NOTIFICATION:
{
APP_LOG(TS_ON, VLEVEL_M,"EVT_BLUE_GATT_NOTIFICATION\r\n");
evt_gatt_attr_notification *evt = (evt_gatt_attr_notification*)blue_evt->data;
GATT_Notification_CB(evt->attr_handle, evt->event_data_length - 2, evt->attr_value);
}
break;
case EVT_BLUE_GATT_READ_PERMIT_REQ:
{
//APP_LOG(TS_ON, VLEVEL_M,"EVT_BLUE_GATT_READ_PERMIT_REQ\r\n");
evt_gatt_read_permit_req *evt = (evt_gatt_read_permit_req*)blue_evt->data;
//GATT_Read_Permit_Req_CB(evt->attr_handle, evt->event_data_length - 2, evt->attribute_value);
if(evt->attr_handle == DateCharHandle + 1)
{
uint8_t buff[13];
uint32_t epoch = get_EpochTime(); // UTC time
epoch -= (Flash.settings.timeZoneOffset*3600);
initDaylyWateringList();
uint8_t step = findSprinklingStep();
buff[11] = findDayDelay(step+1);
uint8_t ret = (uint8_t)findValvesStepState(step);
strcpy((char*)buff,"#?");
HOST_TO_LE_32(&buff[2],epoch);
buff[7] = step;
buff[8] = ret;
buff[6] = get_alarmA_time( &buff[9], &buff[10], &dummy );
buff[12] = getCaseTemperature();
aci_gatt_update_char_value(sampleServHandle, DateCharHandle,
0, /* charValOffset */
13, /* charValueLen */
buff);
updateReg75HC955();
(void)aci_gatt_allow_read(evt->conn_handle);
}
}
break;
case EVT_BLUE_GATT_INDICATION:
APP_LOG(TS_ON, VLEVEL_M,"EVT_BLUE_GATT_INDICATION\r\n");
break;
case EVT_BLUE_GATT_DISC_READ_CHAR_BY_UUID_RESP:
APP_LOG(TS_ON, VLEVEL_M,"EVT_BLUE_GATT_DISC_READ_CHAR_BY_UUID_RESP\r\n");
break;
case EVT_BLUE_GAP_PASS_KEY_REQUEST:
APP_LOG(TS_ON, VLEVEL_M,"EVT_BLUE_GAP_PASS_KEY_REQUEST\r\n");
break;
case EVT_BLUE_GAP_PAIRING_CMPLT:
{
//evt_gap_pairing_cmplt *evt = (evt_gap_pairing_cmplt*)blue_evt->data;
}
break;
case EVT_BLUE_GATT_PROCEDURE_COMPLETE:
APP_LOG(TS_ON, VLEVEL_M,"EVT_BLUE_GATT_PROCEDURE_COMPLETE\r\n");
break;
}
}
break;
}
}
/**
* @}
*/
void readATcommand( uint8_t data_length, uint8_t *att_data )
{
char command[30];
if( !strncmp((char*)att_data,"AT#",3) )
{
strncpy(command,(const char*)&att_data[3],data_length-3);
command[data_length-2] = '\0';
if( !strncmp( command, "UT=", 3) ) // Setting date and time, AT#UT=1644649142 (UnixTime format)
{
receiveDateTime(&command[3]);
}
else if( !strncmp( command, "DA=", 3) ) // Update actuator register, AT#DA=005,080 means switch on only valve 1 and 3 at 80 pump rate
{
driveManyValves(&command[3]);
}
else if( !strncmp( command, "ES", 2) ) // Emergency stop
{
emergencyStop();
}
else if( !strncmp( command, "RS", 2) ) // Reset
{
systemReset();
}
else if( !strncmp( command, "SM", 2) ) // Request State Machine to central
{
requestStateMachine();
}
else if( !strncmp( command, "RC", 2) ) // Run current cycle
{
runCycle();
}
else if( !strncmp( command, "WT", 2) ) // Get watering timing
{
getWateringStats();
}
else if( !strncmp( command, "CB=", 3) ) // Spy CAN-bus
{
spyCANbus(&command[3]); // can be followed by filter like, AT#CB=1,00784
}
else if( !strncmp( command, "AO=", 3) ) // Set/Unset auxilary output, AT#AO=3,1,1,012,080 means AUX output 3, autostart, when ref between
// range low and high, with low limit at 12 and high at 80
{
setAuxOutputFeature(&command[3]);
}
else if( !strncmp( command, "RQ=", 3) ) // request to a module, AT#RQ=0272,4,3400 means request calibration(3+) to module 0x110 with one param (3400)
{
setModuleCalibration(&command[3],2);
}
else if( !strncmp( command, "DS", 2) ) // Download settings to BLE client
{
downloadingSettings();
}
else if( !strncmp( command, "US=", 3) ) // Upload settings from BLE client
{
uploadingSettings(&command[3]);
}
else if( !strncmp( command, "RD", 2) ) // Set default settings
{
setDefaultSettings();
}
else
receiveData(att_data, data_length);
}
else
receiveData(att_data, data_length);
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,322 @@
/**
******************************************************************************
* @file : hci_tl_interface.c
* @brief : This file provides the implementation for all functions prototypes
* for the STM32 BlueNRG HCI Transport Layer interface
******************************************************************************
*
* COPYRIGHT 2021 STMicroelectronics
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "RTE_Components.h"
#include "hci_tl.h"
#include "cmsis_os.h"
#include "utilities_conf.h"
/* Defines -------------------------------------------------------------------*/
#define HEADER_SIZE 5U
#define MAX_BUFFER_SIZE 255U
#define TIMEOUT_DURATION 15U
/* Private variables ---------------------------------------------------------*/
extern osMutexId SPIMutexHandle;
/******************** IO Operation and BUS services ***************************/
/**
* @brief Initializes the peripherals communication with the BlueNRG
* Expansion Board (via SPI, I2C, USART, ...)
*
* @param void* Pointer to configuration struct
* @retval int32_t Status
*/
int32_t HCI_TL_SPI_Init(void* pConf)
{
#ifndef SPI3_HAL_CONFIG
GPIO_InitTypeDef GPIO_InitStruct;
__HAL_RCC_GPIOA_CLK_ENABLE();
/* Configure EXTI Line */
GPIO_InitStruct.Pin = HCI_TL_SPI_EXTI_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(HCI_TL_SPI_EXTI_PORT, &GPIO_InitStruct);
/* Configure RESET Line */
GPIO_InitStruct.Pin = HCI_TL_RST_PIN ;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(HCI_TL_RST_PORT, &GPIO_InitStruct);
/* Configure CS */
GPIO_InitStruct.Pin = HCI_TL_SPI_CS_PIN ;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(HCI_TL_SPI_CS_PORT, &GPIO_InitStruct);
return BSP_SPI3_Init();
#else
return BSP_ERROR_NONE;
#endif
}
/**
* @brief DeInitializes the peripherals communication with the BlueNRG
* Expansion Board (via SPI, I2C, USART, ...)
*
* @param None
* @retval int32_t 0
*/
int32_t HCI_TL_SPI_DeInit(void)
{
HAL_GPIO_DeInit(HCI_TL_SPI_EXTI_PORT, HCI_TL_SPI_EXTI_PIN);
HAL_GPIO_DeInit(HCI_TL_SPI_CS_PORT, HCI_TL_SPI_CS_PIN);
HAL_GPIO_DeInit(HCI_TL_RST_PORT, HCI_TL_RST_PIN);
return 0;
}
/**
* @brief Reset BlueNRG module.
*
* @param None
* @retval int32_t 0
*/
int32_t HCI_TL_SPI_Reset(void)
{
// Deselect CS PIN for BlueNRG to avoid spurious commands
HAL_GPIO_WritePin(HCI_TL_SPI_CS_PORT, HCI_TL_SPI_CS_PIN, GPIO_PIN_SET);
HAL_GPIO_WritePin(HCI_TL_RST_PORT, HCI_TL_RST_PIN, GPIO_PIN_RESET);
HAL_Delay(5);
HAL_GPIO_WritePin(HCI_TL_RST_PORT, HCI_TL_RST_PIN, GPIO_PIN_SET);
HAL_Delay(5);
return 0;
}
/**
* @brief Reads from BlueNRG SPI buffer and store data into local buffer.
*
* @param buffer : Buffer where data from SPI are stored
* @param size : Buffer size
* @retval int32_t: Number of read bytes
*/
int32_t HCI_TL_SPI_Receive(uint8_t* buffer, uint16_t size)
{
uint16_t byte_count;
uint8_t len = 0;
uint8_t char_ff = 0xff;
volatile uint8_t read_char;
uint8_t header_master[HEADER_SIZE] = {0x0b, 0x00, 0x00, 0x00, 0x00};
uint8_t header_slave[HEADER_SIZE];
osStatus status = osMutexWait(SPIMutexHandle, osWaitForever);
if( status == osOK )
{
/* CS reset */
HAL_GPIO_WritePin(HCI_TL_SPI_CS_PORT, HCI_TL_SPI_CS_PIN, GPIO_PIN_RESET);
/* Read the header */
BSP_SPI3_SendRecv(header_master, header_slave, HEADER_SIZE);
if(header_slave[0] == 0x02)
{
/* device is ready */
byte_count = (header_slave[4] << 8)| header_slave[3];
if(byte_count > 0)
{
/* avoid to read more data than the size of the buffer */
if (byte_count > size){
byte_count = size;
}
for(len = 0; len < byte_count; len++)
{
BSP_SPI3_SendRecv(&char_ff, (uint8_t*)&read_char, 1);
buffer[len] = read_char;
}
}
}
/* Release CS line */
HAL_GPIO_WritePin(HCI_TL_SPI_CS_PORT, HCI_TL_SPI_CS_PIN, GPIO_PIN_SET);
osMutexRelease(SPIMutexHandle);
//taskYIELD();
}
#if PRINT_CSV_FORMAT
if (len > 0) {
print_csv_time();
for (int i=0; i<len; i++) {
PRINT_CSV(" %02x", buffer[i]);
}
PRINT_CSV("\n");
}
#endif
return len;
}
/**
* @brief Writes data from local buffer to SPI.
*
* @param buffer : data buffer to be written
* @param size : size of first data buffer to be written
* @retval int32_t: Number of read bytes
*/
int32_t HCI_TL_SPI_Send(uint8_t* buffer, uint16_t size)
{
int32_t result;
uint8_t header_master[HEADER_SIZE] = {0x0a, 0x00, 0x00, 0x00, 0x00};
uint8_t header_slave[HEADER_SIZE];
static uint8_t read_char_buf[MAX_BUFFER_SIZE];
uint32_t tickstart = HAL_GetTick();
do
{
result = 0;
osStatus status = osMutexWait(SPIMutexHandle, 100 );
if( status == osOK )
{
/* CS reset */
HAL_GPIO_WritePin(HCI_TL_SPI_CS_PORT, HCI_TL_SPI_CS_PIN, GPIO_PIN_RESET);
/* Read header */
BSP_SPI3_SendRecv(header_master, header_slave, HEADER_SIZE);
if(header_slave[0] == 0x02)
{
/* SPI is ready */
if(header_slave[1] >= size)
{
BSP_SPI3_SendRecv(buffer, read_char_buf, size);
}
else
{
/* Buffer is too small */
result = -2;
}
} else {
/* SPI is not ready */
result = -1;
}
/* Release CS line */
HAL_GPIO_WritePin(HCI_TL_SPI_CS_PORT, HCI_TL_SPI_CS_PIN, GPIO_PIN_SET);
osMutexRelease(SPIMutexHandle);
taskYIELD();
if((HAL_GetTick() - tickstart) > TIMEOUT_DURATION)
{
result = -3;
break;
}
}
} while(result < 0);
return result;
}
/**
* @brief Reports if the BlueNRG has data for the host micro.
*
* @param None
* @retval int32_t: 1 if data are present, 0 otherwise
*/
static int32_t IsDataAvailable(void)
{
return (HAL_GPIO_ReadPin(HCI_TL_SPI_EXTI_PORT, HCI_TL_SPI_EXTI_PIN) == GPIO_PIN_SET);
}
/*void EXTI2_IRQHandler(void)
{
HAL_GPIO_EXTI_IRQHandler(HCI_TL_SPI_EXTI_PIN);
}*/
/***************************** hci_tl_interface main functions *****************************/
/**
* @brief Register hci_tl_interface IO bus services
*
* @param None
* @retval None
*/
void hci_tl_lowlevel_init(void)
{
/* USER CODE BEGIN hci_tl_lowlevel_init 1 */
/* USER CODE END hci_tl_lowlevel_init 1 */
tHciIO fops;
/* Register IO bus services */
fops.Init = HCI_TL_SPI_Init;
fops.DeInit = HCI_TL_SPI_DeInit;
fops.Send = HCI_TL_SPI_Send;
fops.Receive = HCI_TL_SPI_Receive;
fops.Reset = HCI_TL_SPI_Reset;
fops.GetTick = BSP_GetTick;
hci_register_io_bus (&fops);
/* USER CODE BEGIN hci_tl_lowlevel_init 2 */
/* USER CODE END hci_tl_lowlevel_init 2 */
/* Register event irq handler */
//HAL_EXTI_GetHandle(&hexti2, EXTI_LINE_2);
//HAL_EXTI_RegisterCallback(&hexti2, HAL_EXTI_COMMON_CB_ID, hci_tl_lowlevel_isr);
#ifndef SPI3_HAL_CONFIG
HAL_NVIC_SetPriority(EXTI2_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(EXTI2_IRQn);
#endif
/* USER CODE BEGIN hci_tl_lowlevel_init 3 */
/* USER CODE END hci_tl_lowlevel_init 3 */
}
/**
* @brief HCI Transport Layer Low Level Interrupt Service Routine
*
* @param None
* @retval None
*/
void hci_tl_lowlevel_isr(void)
{
/* Call hci_notify_asynch_evt() */
while( IsDataAvailable() )
{
if (hci_notify_asynch_evt(NULL))
{
break;
}
}
/* USER CODE BEGIN hci_tl_lowlevel_isr */
/* USER CODE END hci_tl_lowlevel_isr */
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,399 @@
/*!
* @file CayenneLpp.c
*
* @brief Implements the Cayenne Low Power Protocol
*
* \copyright Revised BSD License, see section \ref LICENSE.
*
* \code
* ______ _
* / _____) _ | |
* ( (____ _____ ____ _| |_ _____ ____| |__
* \____ \| ___ | (_ _) ___ |/ ___) _ \
* _____) ) ____| | | || |_| ____( (___| | | |
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
* (C)2013-2018 Semtech
*
* \endcode
*
* \author Miguel Luis ( Semtech )
*/
/* Includes ------------------------------------------------------------------*/
#include "stm32_mem.h"
#include "CayenneLpp.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* External variables ---------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
#define CAYENNE_LPP_MAXBUFFER_SIZE 242
#define LPP_DIGITAL_INPUT 0 /* 1 byte */
#define LPP_DIGITAL_OUTPUT 1 /* 1 byte */
#define LPP_ANALOG_INPUT 2 /* 2 bytes, 0.01 signed */
#define LPP_ANALOG_OUTPUT 3 /* 2 bytes, 0.01 signed */
#define LPP_LUMINOSITY 101 /* 2 bytes, 1 lux unsigned */
#define LPP_PRESENCE 102 /* 1 byte, 1 */
#define LPP_TEMPERATURE 103 /* 2 bytes, 0.1 Celsius degrees signed */
#define LPP_RELATIVE_HUMIDITY 104 /* 1 byte, 0.5% unsigned */
#define LPP_ACCELEROMETER 113 /* 2 bytes per axis, 0.001G */
#define LPP_BAROMETRIC_PRESSURE 115 /* 2 bytes 0.1 hPa Unsigned */
#define LPP_GYROMETER 134 /* 2 bytes per axis, 0.01 degrees/s */
#define LPP_GPS 136 /* 3 byte lon/lat 0.0001 degrees, 3 bytes alt 0.01m */
/* Data ID + Data Type + Data Size */
#define LPP_DIGITAL_INPUT_SIZE 3
#define LPP_DIGITAL_OUTPUT_SIZE 3
#define LPP_ANALOG_INPUT_SIZE 4
#define LPP_ANALOG_OUTPUT_SIZE 4
#define LPP_LUMINOSITY_SIZE 4
#define LPP_PRESENCE_SIZE 3
#define LPP_TEMPERATURE_SIZE 4
#define LPP_RELATIVE_HUMIDITY_SIZE 3
#define LPP_ACCELEROMETER_SIZE 8
#define LPP_BAROMETRIC_PRESSURE_SIZE 4
#define LPP_GYROMETER_SIZE 8
#define LPP_GPS_SIZE 11
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
static uint8_t CayenneLppBuffer[CAYENNE_LPP_MAXBUFFER_SIZE];
static uint8_t CayenneLppCursor = 0;
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Exported functions --------------------------------------------------------*/
void CayenneLppInit(void)
{
CayenneLppCursor = 0;
/* USER CODE BEGIN CayenneLppCursor */
/* USER CODE END CayenneLppCursor */
}
void CayenneLppReset(void)
{
CayenneLppCursor = 0;
/* USER CODE BEGIN CayenneLppReset */
/* USER CODE END CayenneLppReset */
}
uint8_t CayenneLppGetSize(void)
{
/* USER CODE BEGIN CayenneLppGetSize */
/* USER CODE END CayenneLppGetSize */
return CayenneLppCursor;
}
uint8_t *CayenneLppGetBuffer(void)
{
/* USER CODE BEGIN CayenneLppGetBuffer */
/* USER CODE END CayenneLppGetBuffer */
return CayenneLppBuffer;
}
uint8_t CayenneLppCopy(uint8_t *dst)
{
/* USER CODE BEGIN CayenneLppCopy_1 */
/* USER CODE END CayenneLppCopy_1 */
UTIL_MEM_cpy_8(dst, CayenneLppBuffer, CayenneLppCursor);
/* USER CODE BEGIN CayenneLppCopy_2 */
/* USER CODE END CayenneLppCopy_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddDigitalInput(uint8_t channel, uint8_t value)
{
/* USER CODE BEGIN CayenneLppAddDigitalInput_1 */
/* USER CODE END CayenneLppAddDigitalInput_1 */
if ((CayenneLppCursor + LPP_DIGITAL_INPUT_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_DIGITAL_INPUT;
CayenneLppBuffer[CayenneLppCursor++] = value;
/* USER CODE BEGIN CayenneLppAddDigitalInput_2 */
/* USER CODE END CayenneLppAddDigitalInput_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddDigitalOutput(uint8_t channel, uint8_t value)
{
/* USER CODE BEGIN CayenneLppAddDigitalOutput_1 */
/* USER CODE END CayenneLppAddDigitalOutput_1 */
if ((CayenneLppCursor + LPP_DIGITAL_OUTPUT_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_DIGITAL_OUTPUT;
CayenneLppBuffer[CayenneLppCursor++] = value;
/* USER CODE BEGIN CayenneLppAddDigitalOutput_2 */
/* USER CODE END CayenneLppAddDigitalOutput_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddAnalogInput(uint8_t channel, float value)
{
/* USER CODE BEGIN CayenneLppAddAnalogInput_1 */
/* USER CODE END CayenneLppAddAnalogInput_1 */
if ((CayenneLppCursor + LPP_ANALOG_INPUT_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
value *= 100;
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_ANALOG_INPUT;
CayenneLppBuffer[CayenneLppCursor++] = ((uint16_t)value) >> 8;
CayenneLppBuffer[CayenneLppCursor++] = (uint16_t)value;
/* USER CODE BEGIN CayenneLppAddAnalogInput_2 */
/* USER CODE END CayenneLppAddAnalogInput_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddAnalogOutput(uint8_t channel, uint16_t value)
{
/* USER CODE BEGIN CayenneLppAddAnalogOutput_1 */
/* USER CODE END CayenneLppAddAnalogOutput_1 */
if ((CayenneLppCursor + LPP_ANALOG_OUTPUT_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
value *= 100;
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_ANALOG_OUTPUT;
CayenneLppBuffer[CayenneLppCursor++] = value >> 8;
CayenneLppBuffer[CayenneLppCursor++] = value;
/* USER CODE BEGIN CayenneLppAddAnalogOutput_2 */
/* USER CODE END CayenneLppAddAnalogOutput_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddLuminosity(uint8_t channel, uint16_t lux)
{
/* USER CODE BEGIN CayenneLppAddLuminosity_1 */
/* USER CODE END CayenneLppAddLuminosity_1 */
if ((CayenneLppCursor + LPP_LUMINOSITY_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_LUMINOSITY;
CayenneLppBuffer[CayenneLppCursor++] = lux >> 8;
CayenneLppBuffer[CayenneLppCursor++] = lux;
/* USER CODE BEGIN CayenneLppAddLuminosity_2 */
/* USER CODE END CayenneLppAddLuminosity_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddPresence(uint8_t channel, uint8_t value)
{
/* USER CODE BEGIN CayenneLppAddPresence_1 */
/* USER CODE END CayenneLppAddPresence_1 */
if ((CayenneLppCursor + LPP_PRESENCE_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_PRESENCE;
CayenneLppBuffer[CayenneLppCursor++] = value;
/* USER CODE BEGIN CayenneLppAddPresence_2 */
/* USER CODE END CayenneLppAddPresence_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddTemperature(uint8_t channel, int16_t celsius)
{
/* USER CODE BEGIN CayenneLppAddTemperature_1 */
/* USER CODE END CayenneLppAddTemperature_1 */
if ((CayenneLppCursor + LPP_TEMPERATURE_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
int16_t val = celsius * 10;
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_TEMPERATURE;
CayenneLppBuffer[CayenneLppCursor++] = val >> 8;
CayenneLppBuffer[CayenneLppCursor++] = val;
/* USER CODE BEGIN CayenneLppAddTemperature_2 */
/* USER CODE END CayenneLppAddTemperature_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddRelativeHumidity(uint8_t channel, uint16_t rh)
{
/* USER CODE BEGIN CayenneLppAddRelativeHumidity_1 */
/* USER CODE END CayenneLppAddRelativeHumidity_1 */
if ((CayenneLppCursor + LPP_RELATIVE_HUMIDITY_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_RELATIVE_HUMIDITY;
CayenneLppBuffer[CayenneLppCursor++] = rh * 2;
/* USER CODE BEGIN CayenneLppAddRelativeHumidity_2 */
/* USER CODE END CayenneLppAddRelativeHumidity_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddAccelerometer(uint8_t channel, int16_t x, int16_t y, int16_t z)
{
/* USER CODE BEGIN CayenneLppAddAccelerometer_1 */
/* USER CODE END CayenneLppAddAccelerometer_1 */
if ((CayenneLppCursor + LPP_ACCELEROMETER_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
int16_t vx = x * 1000;
int16_t vy = y * 1000;
int16_t vz = z * 1000;
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_ACCELEROMETER;
CayenneLppBuffer[CayenneLppCursor++] = vx >> 8;
CayenneLppBuffer[CayenneLppCursor++] = vx;
CayenneLppBuffer[CayenneLppCursor++] = vy >> 8;
CayenneLppBuffer[CayenneLppCursor++] = vy;
CayenneLppBuffer[CayenneLppCursor++] = vz >> 8;
CayenneLppBuffer[CayenneLppCursor++] = vz;
/* USER CODE BEGIN CayenneLppAddAccelerometer_2 */
/* USER CODE END CayenneLppAddAccelerometer_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddBarometricPressure(uint8_t channel, uint16_t hpa)
{
/* USER CODE BEGIN CayenneLppAddBarometricPressure_1 */
/* USER CODE END CayenneLppAddBarometricPressure_1 */
if ((CayenneLppCursor + LPP_BAROMETRIC_PRESSURE_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
hpa *= 10;
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_BAROMETRIC_PRESSURE;
CayenneLppBuffer[CayenneLppCursor++] = hpa >> 8;
CayenneLppBuffer[CayenneLppCursor++] = hpa;
/* USER CODE BEGIN CayenneLppAddBarometricPressure_2 */
/* USER CODE END CayenneLppAddBarometricPressure_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddGyrometer(uint8_t channel, int16_t x, int16_t y, int16_t z)
{
/* USER CODE BEGIN CayenneLppAddGyrometer_1 */
/* USER CODE END CayenneLppAddGyrometer_1 */
if ((CayenneLppCursor + LPP_GYROMETER_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
int16_t vx = x * 100;
int16_t vy = y * 100;
int16_t vz = z * 100;
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_GYROMETER;
CayenneLppBuffer[CayenneLppCursor++] = vx >> 8;
CayenneLppBuffer[CayenneLppCursor++] = vx;
CayenneLppBuffer[CayenneLppCursor++] = vy >> 8;
CayenneLppBuffer[CayenneLppCursor++] = vy;
CayenneLppBuffer[CayenneLppCursor++] = vz >> 8;
CayenneLppBuffer[CayenneLppCursor++] = vz;
/* USER CODE BEGIN CayenneLppAddGyrometer_2 */
/* USER CODE END CayenneLppAddGyrometer_2 */
return CayenneLppCursor;
}
uint8_t CayenneLppAddGps(uint8_t channel, int32_t latitude, int32_t longitude, int32_t meters)
{
/* USER CODE BEGIN CayenneLppAddGps_1 */
/* USER CODE END CayenneLppAddGps_1 */
if ((CayenneLppCursor + LPP_GPS_SIZE) > CAYENNE_LPP_MAXBUFFER_SIZE)
{
return 0;
}
int32_t lat = latitude * 10000;
int32_t lon = longitude * 10000;
int32_t alt = meters * 100;
CayenneLppBuffer[CayenneLppCursor++] = channel;
CayenneLppBuffer[CayenneLppCursor++] = LPP_GPS;
CayenneLppBuffer[CayenneLppCursor++] = lat >> 16;
CayenneLppBuffer[CayenneLppCursor++] = lat >> 8;
CayenneLppBuffer[CayenneLppCursor++] = lat;
CayenneLppBuffer[CayenneLppCursor++] = lon >> 16;
CayenneLppBuffer[CayenneLppCursor++] = lon >> 8;
CayenneLppBuffer[CayenneLppCursor++] = lon;
CayenneLppBuffer[CayenneLppCursor++] = alt >> 16;
CayenneLppBuffer[CayenneLppCursor++] = alt >> 8;
CayenneLppBuffer[CayenneLppCursor++] = alt;
/* USER CODE BEGIN CayenneLppAddGps_2 */
/* USER CODE END CayenneLppAddGps_2 */
return CayenneLppCursor;
}
/* USER CODE BEGIN EF */
/* USER CODE END EF */
/* Private Functions Definition -----------------------------------------------*/
/* USER CODE BEGIN PrFD */
/* USER CODE END PrFD */

View File

@@ -0,0 +1,140 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file app_lorawan.c
* @author MCD Application Team
* @brief Application of the LRWAN Middleware
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "app_lorawan.h"
#include "lora_app.h"
#include "sys_app.h"
#include "stm32_seq.h"
#include "commonMsg.h"
#include "utilities_def.h"
/* USER CODE BEGIN Includes */
#include "stm32l4xx_hal.h"
#include "stm32_nucleo_errno.h"
#define TIMEOUT_DURATION 1000
/* USER CODE END Includes */
/* External variables ---------------------------------------------------------*/
/* USER CODE BEGIN EV */
extern SPI_HandleTypeDef hspi3;
/* USER CODE END EV */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* 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 */
/* Exported functions --------------------------------------------------------*/
void MX_LoRaWAN_Init(void)
{
/* USER CODE BEGIN MX_LoRaWAN_Init_1 */
/* USER CODE END MX_LoRaWAN_Init_1 */
/* USER CODE BEGIN MX_LoRaWAN_Init_2 */
/* USER CODE END MX_LoRaWAN_Init_2 */
LoRaWAN_Init();
/* USER CODE BEGIN MX_LoRaWAN_Init_3 */
/* USER CODE END MX_LoRaWAN_Init_3 */
}
void MX_LoRaWAN_Process(void)
{
/* USER CODE BEGIN MX_LoRaWAN_Process_1 */
/* USER CODE END MX_LoRaWAN_Process_1 */
UTIL_SEQ_Run(UTIL_SEQ_DEFAULT);
/* USER CODE BEGIN MX_LoRaWAN_Process_2 */
/* USER CODE END MX_LoRaWAN_Process_2 */
}
/* USER CODE BEGIN EF */
/* USER CODE END EF */
/* Private Functions Definition -----------------------------------------------*/
/* USER CODE BEGIN PrFD */
static void LoRa_processMsg(MSG_STRUCT *p_msg)
{
if( p_msg->opcode == OP_LORA_EVENT1 )
UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_LoRaSendOnTxSystemEvent), CFG_SEQ_Prio_0);
}
void vLoRaWANTask( void *pvParameters )
{
/* Remove warning for unused parameter */
(void)pvParameters ;
osMessageQId myQueueId;
osEvent event;
myQueueId = getQueueId(LORA_COMM);
//taskENTER_CRITICAL();
MX_LoRaWAN_Init();
//taskEXIT_CRITICAL();
while(1)
{
event = osMessageGet( myQueueId, 100 );
if (event.status == osEventMessage)
{
MSG_STRUCT* p_recvMsg = event.value.p;
LoRa_processMsg(p_recvMsg);
freeMemoryPoolMessage(p_recvMsg);
}
else if (event.status == osEventTimeout) {
MX_LoRaWAN_Process();
}
}
}
/* USER CODE END PrFD */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,646 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file lora_app.c
* @author MCD Application Team
* @brief Application of the LRWAN Middleware
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "platform.h"
#include "Region.h" /* Needed for LORAWAN_DEFAULT_DATA_RATE */
#include "sys_app.h"
#include "lora_app.h"
#include "stm32_seq.h"
//#include "stm32_timer.h"
#include "utilities_def.h"
#include "lora_app_version.h"
#include "lorawan_version.h"
#include "subghz_phy_version.h"
#include "lora_info.h"
#include "LmHandler.h"
//#include "stm32_lpm.h"
#include "sys_conf.h"
#include "CayenneLpp.h"
#include "signals.h"
//#include "STM32l4xx_Nucleo.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* External variables ---------------------------------------------------------*/
/* USER CODE BEGIN EV */
extern GPIO_TypeDef *BUTTON_PORT[];
extern const uint16_t BUTTON_PIN[];
extern const uint16_t BUTTON_IRQn[];
/* USER CODE END EV */
/* Private typedef -----------------------------------------------------------*/
/**
* @brief LoRa State Machine states
*/
typedef enum TxEventType_e
{
/**
* @brief Appdata Transmission issue based on timer every TxDutyCycleTime
*/
TX_ON_TIMER,
/**
* @brief Appdata Transmission external event plugged on OnSendEvent( )
*/
TX_ON_EVENT
/* USER CODE BEGIN TxEventType_t */
/* USER CODE END TxEventType_t */
} TxEventType_t;
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private function prototypes -----------------------------------------------*/
/**
* @brief LoRa End Node send request
*/
static void SendTxData(void);
static void SendTxSysData(void);
/**
* @brief TX timer callback function
* @param context ptr of timer context
*/
static void OnTxTimerEvent(void *context);
/**
* @brief join event callback function
* @param joinParams status of join
*/
static void OnJoinRequest(LmHandlerJoinParams_t *joinParams);
/**
* @brief tx event callback function
* @param params status of last Tx
*/
static void OnTxData(LmHandlerTxParams_t *params);
/**
* @brief callback when LoRa application has received a frame
* @param appData data received in the last Rx
* @param params status of last Rx
*/
static void OnRxData(LmHandlerAppData_t *appData, LmHandlerRxParams_t *params);
/*!
* Will be called each time a Radio IRQ is handled by the MAC layer
*
*/
static void OnMacProcessNotify(void);
/* USER CODE BEGIN PFP */
/**
* @brief LED Tx timer callback function
* @param context ptr of LED context
*/
static void OnTxTimerLedEvent(void *context);
/**
* @brief LED Rx timer callback function
* @param context ptr of LED context
*/
static void OnRxTimerLedEvent(void *context);
/**
* @brief LED Join timer callback function
* @param context ptr of LED context
*/
static void OnJoinTimerLedEvent(void *context);
/* USER CODE END PFP */
/* Private variables ---------------------------------------------------------*/
struct sysled_t {
uint16_t pin;
GPIO_TypeDef *port;
} Sys_Led[] = {
{ RADIO_LED0_Pin, RADIO_LED0_GPIO_Port },
{ RADIO_LED0_Pin, RADIO_LED0_GPIO_Port },
{ RADIO_LED1_Pin, RADIO_LED1_GPIO_Port }
};
static ActivationType_t ActivationType = LORAWAN_DEFAULT_ACTIVATION_TYPE;
/**
* @brief LoRaWAN handler Callbacks
*/
static LmHandlerCallbacks_t LmHandlerCallbacks =
{
.GetBatteryLevel = GetBatteryLevel,
.GetTemperature = GetTemperatureLevel,
.GetUniqueId = GetUniqueId,
.GetDevAddr = GetDevAddr,
.OnMacProcess = OnMacProcessNotify,
.OnJoinRequest = OnJoinRequest,
.OnTxData = OnTxData,
.OnRxData = OnRxData
};
/**
* @brief LoRaWAN handler parameters
*/
static LmHandlerParams_t LmHandlerParams =
{
.ActiveRegion = ACTIVE_REGION,
.DefaultClass = LORAWAN_DEFAULT_CLASS,
.AdrEnable = LORAWAN_ADR_STATE,
.TxDatarate = LORAWAN_DEFAULT_DATA_RATE,
.PingPeriodicity = LORAWAN_DEFAULT_PING_SLOT_PERIODICITY
};
/**
* @brief Type of Event to generate application Tx
*/
static TxEventType_t EventType = TX_ON_TIMER;
/**
* @brief Timer to handle the application Tx
*/
static UTIL_TIMER_Object_t TxTimer;
/* USER CODE BEGIN PV */
/**
* @brief User application buffer
*/
static uint8_t AppDataBuffer[LORAWAN_APP_DATA_BUFFER_MAX_SIZE];
/**
* @brief User application data structure
*/
static LmHandlerAppData_t AppData = { 0, 0, AppDataBuffer };
/**
* @brief Specifies the state of the application LED
*/
static uint8_t AppLedStateOn = RESET;
/**
* @brief Timer to handle the application Tx Led to toggle
*/
static UTIL_TIMER_Object_t TxLedTimer;
/**
* @brief Timer to handle the application Rx Led to toggle
*/
static UTIL_TIMER_Object_t RxLedTimer;
/**
* @brief Timer to handle the application Join Led to toggle
*/
static UTIL_TIMER_Object_t JoinLedTimer;
/* USER CODE END PV */
/* Exported functions ---------------------------------------------------------*/
/* USER CODE BEGIN EF */
/* USER CODE END EF */
void LoRaWAN_Init(void)
{
/* USER CODE BEGIN LoRaWAN_Init_1 */
LED_Init(LED_BLUE);
LED_Init(LED_RED1);
LED_Init(LED_RED2);
/* Get LoRa APP version*/
APP_LOG(TS_OFF, VLEVEL_M, "APP_VERSION: V%X.%X.%X\r\n",
(uint8_t)(__LORA_APP_VERSION >> __APP_VERSION_MAIN_SHIFT),
(uint8_t)(__LORA_APP_VERSION >> __APP_VERSION_SUB1_SHIFT),
(uint8_t)(__LORA_APP_VERSION >> __APP_VERSION_SUB2_SHIFT));
/* Get MW LoraWAN info */
APP_LOG(TS_OFF, VLEVEL_M, "MW_LORAWAN_VERSION: V%X.%X.%X\r\n",
(uint8_t)(__LORAWAN_VERSION >> __APP_VERSION_MAIN_SHIFT),
(uint8_t)(__LORAWAN_VERSION >> __APP_VERSION_SUB1_SHIFT),
(uint8_t)(__LORAWAN_VERSION >> __APP_VERSION_SUB2_SHIFT));
/* Get MW SubGhz_Phy info */
APP_LOG(TS_OFF, VLEVEL_M, "MW_RADIO_VERSION: V%X.%X.%X\r\n",
(uint8_t)(__SUBGHZ_PHY_VERSION >> __APP_VERSION_MAIN_SHIFT),
(uint8_t)(__SUBGHZ_PHY_VERSION >> __APP_VERSION_SUB1_SHIFT),
(uint8_t)(__SUBGHZ_PHY_VERSION >> __APP_VERSION_SUB2_SHIFT));
UTIL_TIMER_Create(&TxLedTimer, 0xFFFFFFFFU, UTIL_TIMER_ONESHOT, OnTxTimerLedEvent, NULL);
UTIL_TIMER_Create(&RxLedTimer, 0xFFFFFFFFU, UTIL_TIMER_ONESHOT, OnRxTimerLedEvent, NULL);
UTIL_TIMER_Create(&JoinLedTimer, 0xFFFFFFFFU, UTIL_TIMER_PERIODIC, OnJoinTimerLedEvent, NULL);
UTIL_TIMER_SetPeriod(&TxLedTimer, 500);
UTIL_TIMER_SetPeriod(&RxLedTimer, 500);
UTIL_TIMER_SetPeriod(&JoinLedTimer, 500);
/* USER CODE END LoRaWAN_Init_1 */
UTIL_SEQ_RegTask((1 << CFG_SEQ_Task_LmHandlerProcess), UTIL_SEQ_RFU, LmHandlerProcess);
UTIL_SEQ_RegTask((1 << CFG_SEQ_Task_LoRaSendOnTxTimerOrButtonEvent), UTIL_SEQ_RFU, SendTxData);
UTIL_SEQ_RegTask((1 << CFG_SEQ_Task_LoRaSendOnTxSystemEvent), UTIL_SEQ_RFU, SendTxSysData);
/* Init Info table used by LmHandler*/
LoraInfo_Init();
/* Init the Lora Stack*/
LmHandlerInit(&LmHandlerCallbacks);
LmHandlerConfigure(&LmHandlerParams);
/* USER CODE BEGIN LoRaWAN_Init_2 */
UTIL_TIMER_Start(&JoinLedTimer);
/* USER CODE END LoRaWAN_Init_2 */
LmHandlerJoin(ActivationType);
if (EventType == TX_ON_TIMER)
{
/* send every time timer elapses */
UTIL_TIMER_Create(&TxTimer, 0xFFFFFFFFU, UTIL_TIMER_ONESHOT, OnTxTimerEvent, NULL);
UTIL_TIMER_SetPeriod(&TxTimer, APP_TX_DUTYCYCLE);
UTIL_TIMER_Start(&TxTimer);
}
else
{
/* USER CODE BEGIN LoRaWAN_Init_3 */
/* send every time button is pushed */
//BSP_PB_Init(BUTTON_USER, BUTTON_MODE_EXTI);
/* USER CODE END LoRaWAN_Init_3 */
}
/* USER CODE BEGIN LoRaWAN_Init_Last */
/* USER CODE END LoRaWAN_Init_Last */
}
void LoRaWAN_Sleep(void)
{
LED_Off( 0 );
LED_Off( 1 );
LED_Off( 2 );
}
/* USER CODE END PB_Callbacks */
/* Private functions ---------------------------------------------------------*/
/* USER CODE BEGIN PrFD */
/* USER CODE END PrFD */
static void OnRxData(LmHandlerAppData_t *appData, LmHandlerRxParams_t *params)
{
/* USER CODE BEGIN OnRxData_1 */
if ((appData != NULL) || (params != NULL))
{
LED_On(LED_BLUE);
UTIL_TIMER_Start(&RxLedTimer);
static const char *slotStrings[] = { "1", "2", "C", "C Multicast", "B Ping-Slot", "B Multicast Ping-Slot" };
APP_LOG(TS_OFF, VLEVEL_M, "\r\n###### ========== MCPS-Indication ==========\r\n");
APP_LOG(TS_OFF, VLEVEL_H, "###### D/L FRAME:%04d | SLOT:%s | PORT:%d | DR:%d | RSSI:%d | SNR:%d\r\n",
params->DownlinkCounter, slotStrings[params->RxSlot], appData->Port, params->Datarate, params->Rssi, params->Snr);
switch (appData->Port)
{
case LORAWAN_SWITCH_CLASS_PORT:
/*this port switches the class*/
if (appData->BufferSize == 1)
{
switch (appData->Buffer[0])
{
case 0:
{
LmHandlerRequestClass(CLASS_A);
break;
}
case 1:
{
LmHandlerRequestClass(CLASS_B);
break;
}
case 2:
{
LmHandlerRequestClass(CLASS_C);
break;
}
default:
break;
}
}
break;
case LORAWAN_USER_APP_PORT:
if (appData->BufferSize == 1)
{
AppLedStateOn = appData->Buffer[0] & 0x01;
if (AppLedStateOn == RESET)
{
APP_LOG(TS_OFF, VLEVEL_H, "LED OFF\r\n");
LED_Off(LED_RED1);
}
else
{
APP_LOG(TS_OFF, VLEVEL_H, "LED ON\r\n");
LED_On(LED_RED1);
}
}
break;
default:
break;
}
}
/* USER CODE END OnRxData_1 */
}
static void SendTxData(void)
{
/* USER CODE BEGIN SendTxData_1 */
LoRaWAN_sensor_t sensor_data;
UTIL_TIMER_Time_t nextTxIn = 0;
#ifdef CAYENNE_LPP
uint8_t channel = 0;
#else
uint16_t humidity = 0;
uint32_t i = 0;
int32_t latitude = 0;
int32_t longitude = 0;
uint16_t altitudeGps = 0;
#endif /* CAYENNE_LPP */
EnvSensors_Read(&sensor_data);
AppData.Port = LORAWAN_USER_APP_PORT;
#ifdef CAYENNE_LPP
CayenneLppReset();
if ((LmHandlerParams.ActiveRegion != LORAMAC_REGION_US915) && (LmHandlerParams.ActiveRegion != LORAMAC_REGION_AU915)
&& (LmHandlerParams.ActiveRegion != LORAMAC_REGION_AS923))
{
CayenneLppAddDigitalInput(channel++, GetBatteryLevel()); // 0
CayenneLppAddDigitalOutput(channel++, AppLedStateOn);
}
CayenneLppAddTemperature(channel++, (int16_t)meas_case_temperature); // 2 -> 29 °C
CayenneLppAddTemperature(channel++, (int16_t)sensor_data.greenHouseAirTemperature); // 3 -> 35 °C
CayenneLppAddRelativeHumidity(channel++, (int16_t)sensor_data.greenHouseHumidity); // 4 -> 59 °C
CayenneLppAddBarometricPressure(channel++, (int16_t)sensor_data.atmosphericPressure); // 5 -> 974 mBar
CayenneLppAddDigitalOutput(channel++,sensor_data.waterLevel); // 6 -> 87 %
CayenneLppAddAnalogOutput(channel++,(uint16_t)sensor_data.solarIrradiance); // 7 -> 35 W/m²
CayenneLppAddTemperature(channel++, (int16_t)sensor_data.outsideAirTemperature); // 8 -> 20 °C
//CayenneLppAddDigitalOutput(channel++,sensor_data.maxBeaufort);
CayenneLppAddDigitalOutput(channel++,sensor_data.windDirection); // 9 -> 28° (sur 36° = Nord) Nord-Nord-Est
CayenneLppAddAnalogOutput(channel++,(uint16_t)(sensor_data.windSpeed*100)); // 10 -> 102 (m/s x100)
CayenneLppCopy(AppData.Buffer);
AppData.BufferSize = CayenneLppGetSize();
#else /* not CAYENNE_LPP */
humidity = (uint16_t)(sensor_data.humidity * 10); /* in %*10 */
AppData.Buffer[i++] = AppLedStateOn;
AppData.Buffer[i++] = (uint8_t)((pressure >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(pressure & 0xFF);
AppData.Buffer[i++] = (uint8_t)(temperature & 0xFF);
AppData.Buffer[i++] = (uint8_t)((humidity >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(humidity & 0xFF);
if ((LmHandlerParams.ActiveRegion == LORAMAC_REGION_US915) || (LmHandlerParams.ActiveRegion == LORAMAC_REGION_AU915)
|| (LmHandlerParams.ActiveRegion == LORAMAC_REGION_AS923))
{
AppData.Buffer[i++] = 0;
AppData.Buffer[i++] = 0;
AppData.Buffer[i++] = 0;
AppData.Buffer[i++] = 0;
}
else
{
latitude = sensor_data.latitude;
longitude = sensor_data.longitude;
AppData.Buffer[i++] = GetBatteryLevel(); /* 1 (very low) to 254 (fully charged) */
AppData.Buffer[i++] = (uint8_t)((latitude >> 16) & 0xFF);
AppData.Buffer[i++] = (uint8_t)((latitude >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(latitude & 0xFF);
AppData.Buffer[i++] = (uint8_t)((longitude >> 16) & 0xFF);
AppData.Buffer[i++] = (uint8_t)((longitude >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(longitude & 0xFF);
AppData.Buffer[i++] = (uint8_t)((altitudeGps >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(altitudeGps & 0xFF);
}
AppData.BufferSize = i;
#endif /* CAYENNE_LPP */
if (LORAMAC_HANDLER_SUCCESS == LmHandlerSend(&AppData, LORAWAN_DEFAULT_CONFIRMED_MSG_STATE, &nextTxIn, false))
{
APP_LOG(TS_ON, VLEVEL_L, "LoRaWAN SEND REQUEST\r\n");
}
else if (nextTxIn > 0)
{
APP_LOG(TS_ON, VLEVEL_L, "LoRaWAN next Tx in : ~%d second(s)\r\n", (nextTxIn / 1000));
}
/* USER CODE END SendTxData_1 */
}
static void SendTxSysData(void)
{
/* USER CODE BEGIN SendTxData_1 */
LoRaWAN_event_sensor_t sensor_data;
#ifdef CAYENNE_LPP
uint8_t channel = 0;
#else
uint16_t vibes_frequency = 0;
#endif /* CAYENNE_LPP */
EventSensors_Read(&sensor_data);
AppData.Port = LORAWAN_USER_APP_PORT + 1;
#ifdef CAYENNE_LPP
CayenneLppReset();
if ((LmHandlerParams.ActiveRegion != LORAMAC_REGION_US915) && (LmHandlerParams.ActiveRegion != LORAMAC_REGION_AU915)
&& (LmHandlerParams.ActiveRegion != LORAMAC_REGION_AS923))
{
CayenneLppAddDigitalInput(channel++, GetBatteryLevel()); // _0
CayenneLppAddDigitalOutput(channel++, AppLedStateOn); // _1
}
CayenneLppAddDigitalInput(channel++,sensor_data.subsonic_AI_similarity); // _2 -> From 0 to 100
CayenneLppCopy(AppData.Buffer);
AppData.BufferSize = CayenneLppGetSize();
#else /* not CAYENNE_LPP */
AppData.Buffer[i++] = AppLedStateOn;
if ((LmHandlerParams.ActiveRegion == LORAMAC_REGION_US915) || (LmHandlerParams.ActiveRegion == LORAMAC_REGION_AU915)
|| (LmHandlerParams.ActiveRegion == LORAMAC_REGION_AS923))
{
AppData.Buffer[i++] = 0;
AppData.Buffer[i++] = 0;
AppData.Buffer[i++] = 0;
AppData.Buffer[i++] = 0;
}
else
{
AppData.Buffer[i++] = GetBatteryLevel(); /* 1 (very low) to 254 (fully charged) */
AppData.Buffer[i++] = (uint8_t)((latitude >> 16) & 0xFF);
AppData.Buffer[i++] = (uint8_t)((latitude >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(latitude & 0xFF);
AppData.Buffer[i++] = (uint8_t)((longitude >> 16) & 0xFF);
AppData.Buffer[i++] = (uint8_t)((longitude >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(longitude & 0xFF);
AppData.Buffer[i++] = (uint8_t)((altitudeGps >> 8) & 0xFF);
AppData.Buffer[i++] = (uint8_t)(altitudeGps & 0xFF);
}
AppData.BufferSize = i;
#endif /* CAYENNE_LPP */
if (LORAMAC_HANDLER_SUCCESS == LmHandlerSend(&AppData, LORAWAN_DEFAULT_CONFIRMED_MSG_STATE, NULL, false))
{
APP_LOG(TS_ON, VLEVEL_L, "LoRaWAN SEND REQUEST\r\n");
}
/* USER CODE END SendTxData_1 */
}
static void OnTxTimerEvent(void *context)
{
/* USER CODE BEGIN OnTxTimerEvent_1 */
/* USER CODE END OnTxTimerEvent_1 */
UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_LoRaSendOnTxTimerOrButtonEvent), CFG_SEQ_Prio_0);
/*Wait for next tx slot*/
UTIL_TIMER_Start(&TxTimer);
/* USER CODE BEGIN OnTxTimerEvent_2 */
/* USER CODE END OnTxTimerEvent_2 */
}
/* USER CODE BEGIN PrFD_LedEvents */
static void OnTxTimerLedEvent(void *context)
{
LED_Off(LED_RED2);
}
static void OnRxTimerLedEvent(void *context)
{
LED_Off(LED_BLUE) ;
}
static void OnJoinTimerLedEvent(void *context)
{
LED_Toggle(LED_RED1) ;
}
/* USER CODE END PrFD_LedEvents */
static void OnTxData(LmHandlerTxParams_t *params)
{
/* USER CODE BEGIN OnTxData_1 */
if ((params != NULL))
{
/* Process Tx event only if its a mcps response to prevent some internal events (mlme) */
if (params->IsMcpsConfirm != 0)
{
LED_On(LED_RED2) ;
UTIL_TIMER_Start(&TxLedTimer);
APP_LOG(TS_OFF, VLEVEL_M, "\r\n###### ========== MCPS-Confirm =============\r\n");
APP_LOG(TS_OFF, VLEVEL_H, "###### U/L FRAME:%04d | PORT:%d | DR:%d | PWR:%d", params->UplinkCounter,
params->AppData.Port, params->Datarate, params->TxPower);
APP_LOG(TS_OFF, VLEVEL_H, " | MSG TYPE:");
if (params->MsgType == LORAMAC_HANDLER_CONFIRMED_MSG)
{
APP_LOG(TS_OFF, VLEVEL_H, "CONFIRMED [%s]\r\n", (params->AckReceived != 0) ? "ACK" : "NACK");
}
else
{
APP_LOG(TS_OFF, VLEVEL_H, "UNCONFIRMED\r\n");
}
}
}
/* USER CODE END OnTxData_1 */
}
static void OnJoinRequest(LmHandlerJoinParams_t *joinParams)
{
/* USER CODE BEGIN OnJoinRequest_1 */
if (joinParams != NULL)
{
if (joinParams->Status == LORAMAC_HANDLER_SUCCESS)
{
UTIL_TIMER_Stop(&JoinLedTimer);
LED_Off(LED_RED1) ;
APP_LOG(TS_OFF, VLEVEL_M, "\r\n###### = JOINED = ");
if (joinParams->Mode == ACTIVATION_TYPE_ABP)
{
APP_LOG(TS_OFF, VLEVEL_M, "ABP ======================\r\n");
}
else
{
APP_LOG(TS_OFF, VLEVEL_M, "OTAA =====================\r\n");
}
}
else
{
APP_LOG(TS_OFF, VLEVEL_M, "\r\n###### = JOIN FAILED\r\n");
}
}
/* USER CODE END OnJoinRequest_1 */
}
static void OnMacProcessNotify(void)
{
/* USER CODE BEGIN OnMacProcessNotify_1 */
/* USER CODE END OnMacProcessNotify_1 */
UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_LmHandlerProcess), CFG_SEQ_Prio_0);
/* USER CODE BEGIN OnMacProcessNotify_2 */
/* USER CODE END OnMacProcessNotify_2 */
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,156 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file lora_info.c
* @author MCD Application Team
* @brief To give info to the application about LoRaWAN configuration
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "LoRaMac.h"
#include "lora_info.h"
#include "sys_app.h" /* APP_PRINTF */
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
static LoraInfo_t loraInfo = {0, 0};
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Exported variables --------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Exported functions --------------------------------------------------------*/
void LoraInfo_Init(void)
{
loraInfo.ActivationMode = 0;
loraInfo.Region = 0;
loraInfo.ClassB = 0;
loraInfo.Kms = 0;
/* USER CODE BEGIN LoraInfo_Init_1 */
/* USER CODE END LoraInfo_Init_1 */
#ifdef REGION_AS923
loraInfo.Region |= (1 << LORAMAC_REGION_AS923) ;
#endif /* REGION_AS923 */
#ifdef REGION_AU915
loraInfo.Region |= (1 << LORAMAC_REGION_AU915) ;
#endif /* REGION_AU915 */
#ifdef REGION_CN470
loraInfo.Region |= (1 << LORAMAC_REGION_CN470) ;
#endif /* REGION_CN470 */
#ifdef REGION_CN779
loraInfo.Region |= (1 << LORAMAC_REGION_CN779) ;
#endif /* REGION_CN779 */
#ifdef REGION_EU433
loraInfo.Region |= (1 << LORAMAC_REGION_EU433) ;
#endif /* REGION_EU433 */
#ifdef REGION_EU868
loraInfo.Region |= (1 << LORAMAC_REGION_EU868) ;
#endif /* REGION_EU868 */
#ifdef REGION_KR920
loraInfo.Region |= (1 << LORAMAC_REGION_KR920) ;
#endif /* REGION_KR920 */
#ifdef REGION_IN865
loraInfo.Region |= (1 << LORAMAC_REGION_IN865) ;
#endif /* REGION_IN865 */
#ifdef REGION_US915
loraInfo.Region |= (1 << LORAMAC_REGION_US915) ;
#endif /* REGION_US915 */
#ifdef REGION_RU864
loraInfo.Region |= (1 << LORAMAC_REGION_RU864) ;
#endif /* REGION_RU864 */
if (loraInfo.Region == 0)
{
APP_PRINTF("error: At least one region shall be defined in the MW: check lorawan_conf.h \r\n");
while (1 != UTIL_ADV_TRACE_IsBufferEmpty())
{
/* Wait that all printfs are completed*/
}
while (1) {} /* At least one region shall be defined */
}
#if ( LORAMAC_CLASSB_ENABLED == 1 )
loraInfo.ClassB = 1;
#elif !defined (LORAMAC_CLASSB_ENABLED)
#error LORAMAC_CLASSB_ENABLED not defined ( shall be <0 or 1> )
#endif /* LORAMAC_CLASSB_ENABLED */
#if (!defined (LORAWAN_KMS) || (LORAWAN_KMS == 0))
loraInfo.Kms = 0;
loraInfo.ActivationMode = 3;
#else /* LORAWAN_KMS == 1 */
loraInfo.Kms = 1;
loraInfo.ActivationMode = ACTIVATION_BY_PERSONALIZATION + (OVER_THE_AIR_ACTIVATION << 1);
#endif /* LORAWAN_KMS */
/* USER CODE BEGIN LoraInfo_Init_2 */
/* USER CODE END LoraInfo_Init_2 */
}
LoraInfo_t *LoraInfo_GetPtr(void)
{
/* USER CODE BEGIN LoraInfo_GetPtr */
/* USER CODE END LoraInfo_GetPtr */
return &loraInfo;
}
/* USER CODE BEGIN EF */
/* USER CODE END EF */
/* Private functions --------------------------------------------------------*/
/* USER CODE BEGIN PF */
/* USER CODE END PF */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,127 @@
#include <automation.h>
#include "actuator_mgr.h"
extern FLASH_STRUCT Flash;
extern bool actuatorRunning[];
// Start actuator when low limit is reached and stop it when low limit - hysteresis is reached
void actuator_AAR_OVER( uint16_t id, uint16_t reference, uint16_t hysteresis )
{
WATERING_ACTUATOR* wa = &Flash.settings.actuators[id];
bool* stateFlag = &actuatorRunning[id];
if( wa->autoRunFeature != 0 ) //AAR_DISABLE
{
if( wa->autoRunEnabled )
{
// Start actuator
if( reference > wa->setpoints[0] && !*stateFlag )
{
*stateFlag = true;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_START, UNDEF_FLOWRATE );
}
// Stop actuator
if( (reference <= (wa->setpoints[0] - hysteresis) ) && *stateFlag )
{
*stateFlag = false;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_STOP, UNDEF_FLOWRATE );
}
}
else
{
// Stop actuator
if( *stateFlag )
{
*stateFlag = false;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_STOP, UNDEF_FLOWRATE );
}
}
}
}
// Start actuator when low limit is reached and stop it when high limit is reached
void actuator_AAR_OUTOFRANGE( uint16_t id, uint16_t reference, uint16_t hysteresis )
{
WATERING_ACTUATOR* wa = &Flash.settings.actuators[id];
bool* stateFlag = &actuatorRunning[id];
if( wa->autoRunFeature != 0 ) // AAR_DISABLE
{
if( wa->autoRunEnabled )
{
// Start actuator
if( (reference < wa->setpoints[0]) && !*stateFlag )
{
*stateFlag = true;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_START, UNDEF_FLOWRATE );
}
// Stop actuator
if( (reference > wa->setpoints[1]) && *stateFlag )
{
*stateFlag = false;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_STOP, UNDEF_FLOWRATE );
}
}
else
{
// Stop actuator
if( *stateFlag )
{
*stateFlag = false;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_STOP, UNDEF_FLOWRATE );
}
}
}
}
// Stop actuator when reference is reached and start it when reference + hysteresis is reached
void actuator_AAR_ABOVE( uint16_t id, uint16_t reference, uint16_t hysteresis )
{
WATERING_ACTUATOR* wa = &Flash.settings.actuators[id];
bool* stateFlag = &actuatorRunning[id];
if( wa->autoRunFeature != 0 ) //AAR_DISABLE
{
if( wa->autoRunEnabled )
{
// Start actuator
if( ( reference <= wa->setpoints[0] ) && !*stateFlag )
{
*stateFlag = true;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_START, UNDEF_FLOWRATE );
}
// Stop actuator
if( ( reference > (wa->setpoints[0] + hysteresis) ) && *stateFlag )
{
*stateFlag = false;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_STOP, UNDEF_FLOWRATE );
}
}
else
{
// Stop actuator
if( *stateFlag )
{
*stateFlag = false;
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_STOP, UNDEF_FLOWRATE );
}
}
}
}
// Start actuator
void actuator_AAR_ON( uint16_t id )
{
WATERING_ACTUATOR* wa = &Flash.settings.actuators[id];
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_START, UNDEF_FLOWRATE );
}
// Stop actuator
void actuator_AAR_OFF( uint16_t id )
{
WATERING_ACTUATOR* wa = &Flash.settings.actuators[id];
Automation_sendCommandToActuators( BITSHIFT_OUTPUT(wa->outputNum), Z_STOP, UNDEF_FLOWRATE );
}

View File

@@ -0,0 +1,793 @@
#include "main.h"
#include <string.h>
#include <stdlib.h>
#include "cmsis_os.h"
#include <stdbool.h>
/* Demo includes. */
#include "automation.h"
#include "parcelize.h"
#include "signals.h"
#include "sample_service.h"
#include "actuator_mgr.h"
#include "flash_page.h"
#include "utils.h"
#include "rtc_if.h"
#include <time.h>
#include <math.h>
#include "lora_app.h"
#define NUMBER_OF_VALVES 8
#define TEMP_HYSTERESIS 2
#define MAX_WATERING_SEQ 100
//volatile uint8_t low_power_on = 0;
bool actuatorRunning[4] = { false };
uint8_t receivedInitialValue = 0;
uint16_t programDuration[4] = {0};
FiniteStateMachine finiteStateMachine;
extern ADC_HandleTypeDef hadc1;
//
static WATERING_OF_THE_DAY_STRUCT wateringList_of_the_day[MAX_WATERING_SEQ] = {0};
WATERING_GENERAL default_settings = {
DATA_VERSION,
3,
2,
12,
0, 0,
1,
{
{ 8, false, { 35, 0 }, 1, 0.0 },
{ 9, false, { 3, 0 }, 2, 0.0 },
{ 10, true, { 15, 80 }, 4, 0.0 },
{ 11, true, { 0, 0 }, 0, 0.0 },
{ 12, true, { 0, 0 }, 0, 0.0 }
},
{
{ 0, true, false, false, { {0, 0, 0, { 10, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 },
{ 1, true, false, false, { {0, 0, 0, { 20, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 },
{ 2, true, false, false, { {0, 0, 0, { 20, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 },
{ 3, true, false, false, { {0, 0, 0, { 5, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 },
{ 4, true, false, false, { {0, 5, 15, { 0, 20, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 },
{ 5, true, false, false, { {0, 0, 0, { 0, 20, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 },
{ 6, true, false, false, { {0, 0, 0, { 0, 0, 5, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 },
{ 7, true, false, false, { {0, 0, 0, { 0, 0, 0, 30 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }}, {0, 0, 0, { 0, 0, 0, 0 }} }, 90 }
},
{
{ 0, 0x2A, 0, 0, 1, { 480, 0, 0, 0 }, 80, false, 60},
{ 1, 0x7F, 5, 0, 1, { 585, 0, 0, 0 }, 100, true, 0},
{ 2, 0x5F, 1, 0, 3, { 420, 540, 660, 0 }, 100, true, 0},
{ 3, 0x5F, 3, 0, 1, { 360, 0, 0, 0 }, 100, true, 0}
},
{ 55, 60, 70, 75, 85, 90, 100, 100, 90, 85, 75, 65 }
};
PARAM_SYS_STRUCT default_paramSys = {
{ 0, 0, 0, 0 }
};
FLASH_STRUCT Flash;
extern osMutexId flashMutexHandle;
extern osThreadId outputsTaskHandle;
extern RTC_HandleTypeDef hrtc;
extern RTC_AlarmTypeDef sAlarm;
extern IWDG_HandleTypeDef hiwdg;
int8_t getCaseTemperature()
{
float Avg_Slope = 2.5;
float V25 = 0.76;
HAL_ADC_Start(&hadc1); // start the adc
HAL_ADC_PollForConversion(&hadc1, 100); // poll for conversion
uint32_t raw = HAL_ADC_GetValue(&hadc1); // get the adc value
float Vsense = raw * 3.3 / 4095;
HAL_ADC_Stop(&hadc1); // stop adc
meas_case_temperature = (((V25 - Vsense) / Avg_Slope) + 25);
return (int8_t)meas_case_temperature;
}
/*-----------------------------------------------------------*/
uint16_t findValvesStepState( uint8_t step )
{
uint8_t valves = wateringList_of_the_day[step].valves;
return valves;
}
uint8_t findAverageFlowRate( uint16_t valvesState )
{
uint16_t avgPumpRate = 0;
uint16_t valvesNbr = 0;
for( int v = 0; v < 8; v++ )
{
if( valvesState & (1<<v) )
{
valvesNbr++;
avgPumpRate += Flash.settings.valves[v].pumpAdjust;
}
}
if( !valvesNbr )
avgPumpRate = 100;
else
avgPumpRate /= valvesNbr;
return avgPumpRate;
}
void wateringStats( uint16_t month_id )
{
memset(programDuration,0,sizeof(programDuration));
for( int p=0; p < 4; p++ )
{
// Search for valve running time
for( int v=0; v < 8; v++ )
{
float rt = Flash.settings.valves[v].sequence[0].runTime[p];
if( (rt>0) && Flash.settings.programs[p].monthlySeasonalAdjust )
{
rt = rt * Flash.settings.programs[p].seasonalAdjust / 100;
rt = rt * Flash.settings.seasonalMonthlyParam[month_id] / 100;
}
rt *= Flash.settings.programs[p].nStartTimes;
programDuration[p] += rt;
}
}
}
int findDayDelay( uint8_t st )
{
return difftime(wateringList_of_the_day[st].jTime,wateringList_of_the_day[0].jTime) / (3600*24);
}
int dailyStepWatering( uint8_t step, char* buffer )
{
char buff[80];
struct tm* top_t;
time_t jtime = wateringList_of_the_day[step].jTime;
top_t = localtime( &jtime );
sprintf(buff,"%d: %02d:%02d:%02d",step,top_t->tm_hour,top_t->tm_min,top_t->tm_sec);
strcat(buffer,(char*)buff);
int diff_day = findDayDelay(step);
if( diff_day <= 0 )
strcpy(buff," ");
else
sprintf(buff,"(J+%d) ",diff_day);
strcat(buffer,(char*)buff);
strcpy((char*)buff," v");
for( int v=0; v<8; v++ )
{
if( wateringList_of_the_day[step].valves & (1<<v) )
buff[v+2] = '1' + v;
else
buff[v+2] = '-';
}
buff[10] = '\0';
strcat(buffer,(char*)buff);
return diff_day;
}
void dailyWatering( char* buffer )
{
int a = 1;
while( wateringList_of_the_day[a].jTime != 0 )
{
dailyStepWatering( a++, buffer );
strcat(buffer,"\n");
}
}
int getCycleFromPeriod( SelectDays per )
{
int cycle = 0;
if( per > OVER_2_DAYS )
cycle = per - 2;
return cycle;
}
int dayCycleRemaining( time_t current_t, int pId )
{
int cycle = 0;
int diffDay = 0;
cycle = getCycleFromPeriod(Flash.settings.programs[pId].period);
if( cycle > 0 )
diffDay = cycle - ((int)(difftime(current_t,Flash.paramSys.currentDayCycle[pId]) / 86400) % (cycle+1));
return diffDay;
}
/* Routines for programs */
bool isWateringDay( WATERING_PROGRAM* o, struct tm* t )
{
bool ret = false;
time_t current_t;
uint8_t wday = t->tm_wday; // Get day of the week
if( (o->wateringWeekDay & (1<<wday)) > 0 )
{
switch(o->period) {
case PER_EVEN:
if( t->tm_mday % 2 == 0 )
ret = true;
break;
case PER_ODD:
if( t->tm_mday % 2 > 0 )
ret = true;
break;
case PER_ODD31:
if( t->tm_mday % 2 > 0 && t->tm_mday <= 29 )
ret = true;
break;
case OVER_2_DAYS:
case OVER_3_DAYS:
case OVER_4_DAYS:
case OVER_5_DAYS:
current_t = mktime(t);
if( dayCycleRemaining(current_t, o->id) == 0 )
ret = true;
break;
default: // PER_SELECT
ret = true;
break;
}
}
return ret;
}
int compareWateringList(const void *s1, const void *s2)
{
WATERING_OF_THE_DAY_STRUCT* e1 = (WATERING_OF_THE_DAY_STRUCT *)s1;
WATERING_OF_THE_DAY_STRUCT* e2 = (WATERING_OF_THE_DAY_STRUCT *)s2;
return e1->jTime - e2->jTime;
}
void registeringValves( WATERING_OF_THE_DAY_STRUCT list[] )
{
int i = 1;
while( list[i].jTime != 0 )
{
if( list[i].tempState )
list[i].valves = list[i-1].valves | list[i].valves;
else
list[i].valves = list[i-1].valves & ~(list[i].valves);
i++;
}
}
bool isStepsRunTime( WATERING_SEQUENCE seq[] )
{
if( seq[0].startYearDay != 0 ) {
for( int i = 1; i < 4; i++ ) {
if( seq[i].startYearDay <= seq[i-1].startYearDay ) {
return false;
}
}
return true;
}
return false;
}
uint16_t wateringList( struct tm* current_time, WATERING_OF_THE_DAY_STRUCT list[] )
{
struct tm top_time, start_of_the_day;
time_t top_t, start_of_the_day_t;
uint16_t ti=0;
bool delayedStart;
// Create sprinkling list of the day
memset(list, 0, sizeof(wateringList_of_the_day));
// Get day of the year used with growth steps
uint8_t yday = current_time->tm_yday;
// Initialize 1st position of the list with the start of the day
start_of_the_day = *current_time;
start_of_the_day.tm_hour = 0;
start_of_the_day.tm_min = 0;
start_of_the_day.tm_sec = 0;
start_of_the_day_t = mktime(&start_of_the_day); // Find the end of the current day
list[ti++].jTime = start_of_the_day_t;
top_time = start_of_the_day;
for( int p=0; p < 4; p++ )
{
WATERING_PROGRAM* wp = &Flash.settings.programs[p];
if( isWateringDay( wp,current_time) ) // Checking if it is or not a watering day
{
for( int t=0; (t < wp->nStartTimes) && (ti < (MAX_WATERING_SEQ-2)); t++ )
{
delayedStart = false;
uint16_t stime = wp->startTimes[t];
top_time.tm_hour = stime / 60;
top_time.tm_min = stime % 60;
top_time.tm_sec = 0;
top_t = mktime(&top_time); // Watering start time at the current day
// Search for valve running time
for( int v=0; (v < 8) && (ti < (MAX_WATERING_SEQ-2)); v++ )
{
WATERING_VALVE* wv = &Flash.settings.valves[v];
int sId = 0;
if( isStepsRunTime(wv->sequence) ) // Using sequence according to the 4 growth steps (init, development, middle, late)
{
sId = 3;
while( sId >= 0 && wv->sequence[sId--].startYearDay >= yday );
if( sId < 0 ) // No active valve in this program!
continue;
}
// Calculation of watering runtime
float rt = wv->sequence[sId].runTime[p];
if( rt > 0 )
{
if( wp->monthlySeasonalAdjust ) // Applying monthly correction
{
rt = rt * wp->seasonalAdjust / 100;
rt = rt * Flash.settings.seasonalMonthlyParam[current_time->tm_mon] / 100;
}
if( wp->valveDelay > 0 )
{
if( delayedStart )
{
top_t = list[ti-1].jTime;
top_t += wp->valveDelay;
}
else
delayedStart = true;
}
uint16_t cycleTime = wv->sequence[sId].cycleTime;
if( cycleTime == 0 ) // Just one watering at specific time
{
// Calculate watering start time
list[ti].jTime = top_t;
list[ti].progId = 'A' + p;
list[ti].tempState = true;
list[ti].pumpRate = wv->pumpAdjust;
list[ti].valves = (1<<v);
ti++;
// and end time
top_t += (uint16_t)(rt * 60);
list[ti].jTime = top_t;
list[ti].progId = 'A' + p;
list[ti].tempState = false;
list[ti].pumpRate = 90;
list[ti].valves = (1<<v);
ti++;
}
else // Day cycle
{
uint16_t nPeriod = rt / cycleTime;
cycleTime *= 60;
uint16_t soakTime = wv->sequence[sId].soakTime * 60 + cycleTime;
for( int pe=0; pe < nPeriod; pe++ )
{
// Calculate watering start time
time_t start_t = top_t + (pe*soakTime);
list[ti].jTime = start_t;
list[ti].progId = 'A' + p;
list[ti].tempState = true;
list[ti].pumpRate = wv->pumpAdjust;
list[ti].valves = (1<<v);
ti++;
// and end time
list[ti].jTime = start_t + cycleTime;
list[ti].progId = 'A' + p;
list[ti].tempState = false;
list[ti].pumpRate = 90;
list[ti].valves = (1<<v);
ti++;
}
}
}
}
}
}
}
// Sorting
qsort(list, ti, sizeof(WATERING_OF_THE_DAY_STRUCT), compareWateringList);
// registering valves in bitfied
registeringValves( list );
return ti;
}
WATERING_OF_THE_DAY_STRUCT findFirstStartAtNextWatering( time_t t_day )
{
WATERING_OF_THE_DAY_STRUCT list[MAX_WATERING_SEQ], midnight = {0};
uint16_t size, nLoop = 31;
struct tm* currTime;
midnight.jTime = t_day + (24*3600);
do
{
t_day += (24*3600);
currTime = localtime ( &t_day );
size = wateringList( currTime, list );
nLoop--;
} while( size < 2 && nLoop > 0 );
return ( nLoop > 0 ? list[1] : midnight );
}
uint16_t optimizeWatering( WATERING_OF_THE_DAY_STRUCT list[] )
{
int i = 1;
while( list[i].jTime != 0 )
{
if( (list[i-1].jTime == list[i].jTime) )
{
int cv = list[i-1].valves;
int ccv = list[i].valves;
int j = i;
while( list[j-1].jTime != 0 )
{
list[j-1] = list[j];
j++;
}
if( ccv > cv )
list[i-1].valves |= ccv;
else
list[i-1].valves = ccv;
}
else
i++;
}
return i;
}
uint16_t initDaylyWateringList()
{
struct tm current_time;
WATERING_OF_THE_DAY_STRUCT nextWatering;
uint16_t ti=0;
now( &current_time ); // Current date time
// Create sprinkling list of the day - Return the size of the list
ti = wateringList( &current_time, wateringList_of_the_day );
nextWatering = findFirstStartAtNextWatering( wateringList_of_the_day[0].jTime ); // Find first watering start from the given time
ti = optimizeWatering( wateringList_of_the_day );
// End the list with the first start of the next watering
wateringList_of_the_day[ti] = nextWatering;
// Stats
wateringStats(current_time.tm_mon);
return difftime(nextWatering.jTime,wateringList_of_the_day[0].jTime) / (3600*24);
}
void initCurrentDayCycle( void* ptr )
{
time_t *ldc = (time_t*)(ptr);
int cycle = 0;
for( int p=0; p<4; p++ )
{
cycle = getCycleFromPeriod(Flash.settings.programs[p].period);
if( cycle > 0 )
{
if( ptr == NULL || ldc[p] != Flash.paramSys.currentDayCycle[p] )
Flash.paramSys.currentDayCycle[p] = wateringList_of_the_day[0].jTime;
}
else
Flash.paramSys.currentDayCycle[p] = 0;
}
}
uint8_t findSprinklingStep()
{
struct tm current_time, *new_time;
time_t current_t;
uint8_t s;
now( &current_time ); // Current date time
// Find the right sequence in this list
s = 0;
current_t = mktime(&current_time);
while( current_t >= wateringList_of_the_day[s].jTime )
s++;
new_time = localtime(&wateringList_of_the_day[s].jTime);
int diffTime = findDayDelay(s);
s--;
if( wateringList_of_the_day[s].valves == 0 )
{
APP_LOG(TS_OFF, VLEVEL_M, "No watering until %02d:%02d:%02d", new_time->tm_hour, new_time->tm_min, new_time->tm_sec);
}
else
{
APP_LOG(TS_OFF, VLEVEL_M, "Watering: v"BYTE_TO_BINARY_PATTERN" until %02d:%02d:%02d",BYTE_TO_BINARY(wateringList_of_the_day[s].valves),
new_time->tm_hour, new_time->tm_min, new_time->tm_sec);
}
if( diffTime > 0 )
APP_LOG(TS_OFF, VLEVEL_M, " (D+%d)",diffTime);
APP_LOG(TS_OFF, VLEVEL_M, "\r\n");
// Set next alarm
set_alarmA( new_time );
return s;
}
void Automation_sendCommandToActuators( uint16_t id, ActuatorStates state, uint8_t flowRate )
{
osMessageQId destQueue;
destQueue = getQueueId(OUTPUTS);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = OP_OUTPUT_ONCHANGE;
p_sendMsg->outputs = id;
p_sendMsg->changeState = state;
p_sendMsg->pumpRate = flowRate;
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
void mainStatement(ActuatorStates state)
{
switch( state ) {
case Z_ALL_OFF:
finiteStateMachine.stm = APERIODIC;
APP_LOG(TS_OFF, VLEVEL_M, "Received instruction to stop...\r\n");
Automation_sendCommandToActuators( ALL_OUTPUTS_OFF, Z_ALL_OFF, 100 );
stop_alarmA();
actuator_reset_state();
break;
case Z_RESTART:
updateAUXtimer(AUX_230VAC_PORT);
case Z_UPDATE:
finiteStateMachine.stm = PERIODIC;
APP_LOG(TS_OFF, VLEVEL_M, "Received instruction to update zones\r\n");
initDaylyWateringList();
uint8_t step = findSprinklingStep();
uint16_t vss = findValvesStepState(step);
uint8_t flow = findAverageFlowRate(vss);
Automation_sendCommandToActuators( vss, Z_UPDATE, flow );
APP_LOG(TS_OFF, VLEVEL_M, "Case temperature: %.1f C\r\n", meas_case_temperature);
actuator_reset_state();
break;
case E_STOP:
finiteStateMachine.stm = ESTOP;
APP_LOG(TS_OFF, VLEVEL_M, "Received E-Stop...\r\n");
addErrorToList( 0x112 );
Automation_sendCommandToActuators( ALL_OUTPUTS_OFF, Z_ALL_OFF, 100 );
stop_alarmA();
break;
case UPDATE_SETTINGS:
case Z_START:
default:
break;
}
}
bool saveSettings( FLASH_STRUCT* data )
{
uint32_t ret = 0;
osStatus status = osMutexWait(flashMutexHandle, 5000);
if (status == osOK)
{
APP_LOG(TS_OFF, VLEVEL_M, "Saving settings...\r\n");
int numofbytes = sizeof( FLASH_STRUCT );
uint32_t ret = Flash_Write_Data(FLASH_USER_START_ADDR, (__IO uint64_t *)data, numofbytes );
if( ret != 0 )
APP_LOG(TS_OFF, VLEVEL_M, "Flash write error %d\r\n",ret);
osMutexRelease(flashMutexHandle);
}
osDelay(50);
return ret == 0;
}
static void Automation_processMsg(MSG_STRUCT *p_msg)
{
uint8_t zoneTimeUpdate = 0;
osMessageQId destQueue;
MSG_STRUCT *p_sendMsg;
uint8_t num;
CommandOpcode opcode = p_msg->opcode;
switch( opcode ) {
case OP_RTC:
if( finiteStateMachine.stm != PERIODIC )
break;
case OP_MAIN:
mainStatement(p_msg->changeState);
break;
case OP_FEATURE:
num = p_msg->lParam[0];
if( num > 0 && num < 4 )
{
WATERING_ACTUATOR* wa = &(Flash.settings.actuators[num-1]);
//wa->outputNum = num + 8;
wa->autoRunEnabled = p_msg->lParam[1];
wa->autoRunFeature = p_msg->lParam[2];
switch( wa->autoRunFeature ) {
case AAR_DISABLE :
wa->setpoints[0] = wa->setpoints[1] = 0;
break;
case AAR_OVER :
case AAR_ABOVE:
wa->setpoints[0] = p_msg->lParam[3];
wa->setpoints[1] = 0;
break;
case AAR_INRANGE:
case AAR_OUTOFRANGE:
wa->setpoints[0] = p_msg->lParam[3];
wa->setpoints[1] = p_msg->lParam[4];
break;
}
zoneTimeUpdate = 1;
}
break;
case OP_CAN: destQueue = (osMessageQId)getQueueId(BLE_COMM);
p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = OP_CAN;
memcpy(p_sendMsg,p_msg,sizeof(MSG_STRUCT));
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
break;
default:
break;
};
if( zoneTimeUpdate )
{
saveSettings( &Flash );
}
osDelay( 20 );
}
void updateAUXtimer( uint16_t actuatorId )
{
struct tm current_time;
time_t current_t;
uint16_t local_current_minutes_from_midnight;
if( Flash.settings.auxStartTime == Flash.settings.auxEndTime ) {
stop_alarmB();
if( Flash.settings.auxStartTime != 0 ) { // Enabled AUX output forever
actuator_AAR_ON( actuatorId );
APP_LOG(TS_ON, VLEVEL_M, "AUX220V enabled\r\n");
}
else {
actuator_AAR_OFF( actuatorId ); // else disable AUX output
APP_LOG(TS_ON, VLEVEL_M, "AUX220V disabled\r\n");
}
}
else {
now( &current_time ); // Current UTC date time
current_time.tm_sec = 0;
// Afficher l'heure locale après modification
current_t = mktime(&current_time);
// Calculate minutes past midnight
local_current_minutes_from_midnight = current_time.tm_hour * 60 + current_time.tm_min;
actuator_AAR_OFF( actuatorId );
uint16_t nextAlarmInMinutes = 0;
if (Flash.settings.auxEndTime < Flash.settings.auxStartTime) {
// Interval is on two days
if (local_current_minutes_from_midnight >= Flash.settings.auxStartTime ||
local_current_minutes_from_midnight < Flash.settings.auxEndTime) {
actuator_AAR_ON( actuatorId );
nextAlarmInMinutes = Flash.settings.auxEndTime - local_current_minutes_from_midnight;
}
else
nextAlarmInMinutes = Flash.settings.auxStartTime - local_current_minutes_from_midnight;
} else {
// Interval is on the same day
if (local_current_minutes_from_midnight >= Flash.settings.auxStartTime &&
local_current_minutes_from_midnight < Flash.settings.auxEndTime) {
actuator_AAR_ON( actuatorId );
nextAlarmInMinutes = Flash.settings.auxEndTime - local_current_minutes_from_midnight;
}
else {
if( Flash.settings.auxStartTime < local_current_minutes_from_midnight )
nextAlarmInMinutes = (24*60) - local_current_minutes_from_midnight + Flash.settings.auxStartTime;
else
nextAlarmInMinutes = Flash.settings.auxStartTime - local_current_minutes_from_midnight;
}
}
// Set alarm B from current time
current_t += (nextAlarmInMinutes*60);
struct tm *alarmB = gmtime(&current_t);
if (alarmB != NULL) {
APP_LOG(TS_ON, VLEVEL_M, "Alarm B is setting at (GMT%+03d) %s\r",Flash.settings.timeZoneOffset,
asctime(alarmB));
set_alarmB( alarmB );
}
}
}
void actuator_reset_state()
{
for( int id = 0; id < 4; id++ )
actuatorRunning[id] = false;
}
static void Automation_processFrame()
{
// Fill up Tank 1 with Tank 2 if low level in Tank 1. Automatic stop of transfer when low level in Tank 2
actuator_AAR_OUTOFRANGE( PORT2_16A, gh_waterTankLevel[0], 0 );
// Run greenhouse fan if inside temperature over setpoint
actuator_AAR_OVER( PORT0_8A, gh_insideTemperature[0], TEMP_HYSTERESIS );
osDelay( 10 );
}
void vAutomationTask( void *pvParameters )
{
FLASH_STRUCT saved_data;
/* Remove warning for unused parameter */
(void)pvParameters ;
osMessageQId myQueueId = getQueueId(AUTOMATION);
finiteStateMachine.stm = IDLE;
//check for saved date in EEPROM
APP_LOG(TS_OFF, VLEVEL_M, "Checking EEPROM for stored data\r\n");
int numofwords = (sizeof( FLASH_STRUCT )/4)+((sizeof( FLASH_STRUCT )%4)!=0);
Flash_Read_Data(FLASH_USER_START_ADDR, (__IO uint32_t *)&saved_data, numofwords );
osDelay(50);
if( saved_data.settings.versionID != DATA_VERSION ) // Bad version
{
saved_data.settings = default_settings;
initCurrentDayCycle( NULL );
saveSettings( &saved_data );
}
Flash = saved_data;
// Unlock Outputs and LoRaWAN tasks
xTaskNotifyGive( outputsTaskHandle );
// Update AUX timer
updateAUXtimer(AUX_230VAC_PORT);
// Update valve status when first powered on
initDaylyWateringList();
uint8_t step = findSprinklingStep();
uint16_t vss = findValvesStepState(step);
uint8_t flow = findAverageFlowRate(vss);
Automation_sendCommandToActuators( vss, Z_UPDATE, flow );
finiteStateMachine.stm = PERIODIC;
//sendWarnError(0x999);
while(1) {
osEvent event;
event = osMessageGet(myQueueId, 100);
#ifdef AUTO_RESTART
HAL_IWDG_Refresh(&hiwdg);
#endif
if( finiteStateMachine.stm != IDLE )
HAL_GPIO_TogglePin(LD2_GPIO_Port, LD2_Pin);
if (event.status == osEventMessage) {
MSG_STRUCT* p_recvMsg = event.value.p;
Automation_processMsg(p_recvMsg);
freeMemoryPoolMessage(p_recvMsg);
}
else if (event.status == osEventTimeout) {
Automation_processFrame();
}
}
}

View File

@@ -0,0 +1,335 @@
#include <stdio.h>
#include "main.h"
#include <string.h>
#include "cmsis_os.h"
#include "commonMsg.h"
/* Demo includes. */
#include "can_bus.h"
#include "signals.h"
#include "sample_service.h"
#include "utils.h"
#include "pcanpro_can.h"
/*-----------------------------------------------------------*/
extern CAN_HandleTypeDef hcan1;
GREEN_HOUSE_SENSORS_STRUCT greenHouseSensors = {
5,
{
{ 0x320, METEO, 4, {0}, 5},
{ 0x321, LEVEL, 1, {0}, 12 },
{ 0x340, SOIL, 2, {0}, 10 },
{ 0x341, SOIL, 2, {0}, 3 },
{ 0x342, SOIL, 2, {0}, 10 },
}
};
uint16_t sensorTicks[5] = { 0 };
uint8_t can_echo_flag = 0;
uint16_t filterStationID = 0;
extern osTimerId CanTimeoutHandle;
volatile bool isInitialized = false;
uint16_t discoveredStations[25] = {0}, i_discoveredStations = 0;
uint16_t discoveredStations_bitfield = 0, r_discoveredStations_bitfield = 0;
volatile bool errorDiscoveringStation = false;
/* USER CODE BEGIN PFP */
int findIndexDiscoveringStationsByID( uint16_t id )
{
int index = -1;
for( int i=0; i < i_discoveredStations; i++ )
{
if( discoveredStations[i] == id )
{
index = i;
break;
}
}
return index;
}
void newCANbusStation( uint16_t id )
{
if( id == MCU_S_SUBSONICGAUGE )
return;
discoveredStations[i_discoveredStations] = id;
discoveredStations_bitfield |= (1<<i_discoveredStations);
i_discoveredStations++;
}
void discoveringStation( uint16_t id )
{
int index = findIndexDiscoveringStationsByID( id );
if( index >= 0 )
r_discoveredStations_bitfield |= (1<<index);
else
{
newCANbusStation( id );
}
}
// Used to check if CAN-bus sensor is always running
void CanTimeoutCallback( void const * arg )
{
if( !isInitialized )
{
// record sensors automatically
//osTimerStart( CanTimeoutHandle, 800 );
isInitialized = true;
}
else
{
// check if sensors are running
errorDiscoveringStation = (r_discoveredStations_bitfield != discoveredStations_bitfield);
r_discoveredStations_bitfield = 0;
}
}
void LoraNotification()
{
osMessageQId destQueue;
destQueue = getQueueId(LORA_COMM);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = OP_LORA_EVENT1;
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
int findSensorIdByAddress( uint16_t addr )
{
uint16_t addr16 = 0x300;
addr16 += addr;
for( int i=0; i<greenHouseSensors.nbSensors; i++ )
{
if( greenHouseSensors.sensors[i].address == addr16 )
return i;
}
return -1;
}
void echoCanMessage( uint16_t addr, uint8_t* data, uint16_t sz)
{
osMessageQId destQueue;
uint8_t buff[15];
destQueue = (osMessageQId)getQueueId(BLE_COMM);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = CAN_ECHO;
p_sendMsg->lParam[0] = sz+4;
memcpy(buff,"#C",2);
HOST_TO_LE_16(&buff[2],addr);
memcpy(&buff[4],data,sz);
memcpy(&(p_sendMsg->data[2]),buff,sz+4);
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
int CAN_filterConfig(void)
{
int ret = 0;
//pcan_can_set_filter_mask( CAN_BUS_1, 0, 0, 0, 0 );
CAN_FilterTypeDef sFilterConfig;
sFilterConfig.FilterBank = 0;
sFilterConfig.FilterMode = CAN_FILTERMODE_IDMASK;
sFilterConfig.FilterScale = CAN_FILTERSCALE_32BIT;
sFilterConfig.FilterIdHigh = 0x000 << 5; // CAN address
sFilterConfig.FilterIdLow = 0;
sFilterConfig.FilterMaskIdHigh = 0x000 << 5; // CAN address mask
sFilterConfig.FilterMaskIdLow = 0;
sFilterConfig.FilterFIFOAssignment = CAN_RX_FIFO0;
sFilterConfig.FilterActivation = ENABLE;
sFilterConfig.SlaveStartFilterBank = 14;
HAL_CAN_ConfigFilter(&hcan1, &sFilterConfig);
if( HAL_CAN_ActivateNotification( &hcan1, INTERNAL_CAN_IT_FLAGS ) != HAL_OK )
ret = -1;
if( HAL_CAN_Start( &hcan1 ) != HAL_OK )
ret = -1;
return ret;
}
int pcan_rx_frame( uint8_t channel, struct t_can_msg *pmsg )
{
HAL_GPIO_TogglePin(CAN_LED_GPIO_Port,CAN_LED_Pin);
if( can_echo_flag )
{
echoCanMessage( pmsg->id, pmsg->data, pmsg->size);
}
if( !isInitialized )
{
int index = findIndexDiscoveringStationsByID( pmsg->id );
if( index < 0 )
newCANbusStation( pmsg->id );
}
else
{
// Set discovered stations register bitfield
discoveringStation(pmsg->id);
if ( pmsg->id == MCU_S_ANEMOMETER )
{
dev_anemometer device;
memcpy(device.data,pmsg->data,pmsg->size);
// Read temperature
gh_outsideTemperature[0] = getOutsideTemperature(device);
gh_atmPressure[0] = getAtmPressure(device);
gh_windMaxBeaufort[0] = getWindBeaufort(device);
gh_windDirection[0] = getWindDirection(device);
gh_windSpeed[0] = getWindSpeed(device);
//APP_LOG(TS_OFF, VLEVEL_M, "Greenhouse data: External Temp. %.1f°C, Atm. Pressure %dhPa\r\n",gh_outsideTemperature1, gh_atmPressure1 );
}
else if ( pmsg->id == MCU_S_WATERTANK )
{
dev_watertank device;
memcpy(device.data,pmsg->data,pmsg->size);
// Read tank level
gh_waterTankLevel[0] = getWaterTankLevel(device);
//APP_LOG(TS_OFF, VLEVEL_M, "Greenhouse data: Water tank level %d%%, Rain(%s)\r\n", gh_rain[0] == 1 ? "YES" : "NO" );
}
else if ( pmsg->id == MCU_S_PYRANOMETER )
{
dev_pyranometer device;
memcpy(device.data,pmsg->data,pmsg->size);
// Read solar irradiance inside the greenhouse
gh_solarIrradiance[0] = getSolarIrradiance(device);
}
else if ( pmsg->id == MCU_S_THERMOMETER )
{
dev_thermometer device;
memcpy(device.data,pmsg->data,pmsg->size);
// Read current temperature inside the greenhouse
gh_insideTemperature[0] = getInsideTemperature(device);
// Read current relative humidity inside the greenhouse
gh_insideHumidity[0] = getInsideRelativeHumidity(device);
}
else if ( pmsg->id == MCU_S_SUBSONICGAUGE ) // experimental function!!
{
dev_subsonic_gauge device;
memcpy(device.data,pmsg->data,pmsg->size);
// Read subsonic AI similarity
gh_soilVibesAiSimilarity[0] = getSubsonicAiSimilarity(device);
// Event system required lorawan messaging
LoraNotification();
}
else if ( pmsg->id == MCU_S_DISDROMETER )
{
dev_disdrometer device;
memcpy(device.data,pmsg->data,pmsg->size);
// Read rain rate in mm/h
gh_averageRainDropRate[0] = getAvgRainDropRate(device);
}
/*else if ( pmsg->id == MCU_S_RAINGAUGE )
{
dev_rain_gauge device;
memcpy(device.data,pmsg->data,pmsg->size);
// Read rain condition
gh_rainingCondition[0] = getRainingCondition(device);
}*/
}
return 0;
}
static void Can_Bus_processMsg(MSG_STRUCT *p_msg)
{
struct t_can_msg msg;
if( p_msg->opcode == CAN_ECHO )
{
can_echo_flag = 1;
filterStationID = p_msg->lParam[0];
}
else if( p_msg->opcode == CAN_NOECHO )
{
can_echo_flag = 0;
filterStationID = 0;
}
else if( p_msg->opcode == OP_CAN )
{
dev_command_request request;
request.RQ_Device = p_msg->lParam[0];
request.RQ_OpCode = p_msg->lParam[1];
request.setpoints[0] = p_msg->lParam[2];
request.setpoints[1] = p_msg->lParam[3];
msg.id = MCU_R_COMMAND;
msg.size = 6;
msg.flags = MSG_FLAG_STD;
memcpy(msg.data,&request,msg.size);
pcan_can_write( CAN_BUS_1, &msg );
}
osDelay( 10 );
}
static void Can_Bus_processFrame()
{
pcan_can_poll();
if( errorDiscoveringStation )
addErrorToList( 0x207 );
osDelay( 10 );
}
void vCanBusTask( void *pvParameters )
{
/* Remove warning for unused parameter */
(void)pvParameters ;
osMessageQId myQueueId = getQueueId(CAN_COMM);
pcan_can_install_rx_callback( CAN_BUS_1, pcan_rx_frame );
CAN_filterConfig();
APP_LOG(TS_OFF, VLEVEL_M, "CAN-bus started\r\n");
HAL_GPIO_WritePin(CAN_LED_GPIO_Port,CAN_LED_Pin,GPIO_PIN_RESET);
osStatus status = osTimerStart( CanTimeoutHandle, 5000 );
if( status != osOK )
APP_LOG(TS_OFF, VLEVEL_M, "Error discovering CAN-bus sensors\r\n");
while(1) {
osEvent event;
event = osMessageGet(myQueueId, 100);
if (event.status == osEventMessage) {
MSG_STRUCT* p_recvMsg = event.value.p;
Can_Bus_processMsg(p_recvMsg);
freeMemoryPoolMessage(p_recvMsg);
}
else if (event.status == osEventTimeout) {
Can_Bus_processFrame();
}
}
}

View File

@@ -0,0 +1,140 @@
/*
* crc32.c
*
* Created on: 13 août 2022
* Author: xavie
*/
#include "crc32.h"
#ifdef SYS_CRC
uint32_t TM_CRC_Calculate32(uint32_t* arr, uint32_t count, uint8_t reset) {
/* Reset CRC data register if necessary */
if (reset) {
/* Reset generator */
CRC->CR = CRC_CR_RESET;
}
/* Calculate CRC */
while (count--) {
/* Set new value */
CRC->DR = *arr++;
}
/* Return data */
return CRC->DR;
}
#endif
uint8_t reflect8(uint8_t val)
{
uint8_t resVal = 0;
for(int i = 0; i < 8; i++)
{
if ((val & (1 << i)) != 0)
{
resVal |= (uint8_t )(1 << (7 - i));
}
}
return resVal;
}
uint32_t reflect32(uint32_t val)
{
uint32_t resVal = 0;
for(int i = 0; i < 32; i++)
{
if ((val & (1 << i)) != 0)
{
resVal |= (uint32_t )(1 << (31 - i));
}
}
return resVal;
}
uint32_t calcCRC32stm(void *data, uint32_t len,
uint32_t poly, uint32_t seed, uint32_t initCRC, uint32_t inR, uint32_t outR)
{
const unsigned char *buffer = (const unsigned char*) data;
unsigned int crc = seed;
unsigned char byte;
while( len-- )
{
byte = *buffer++;
if(inR) {
#ifdef SYS_CRC
byte = __RBIT((uint32_t)byte) >> 24;
#else
byte = reflect8(byte);
#endif
}
crc = crc ^ (byte << 24);
for( int bit = 0; bit < 8; bit++ )
{
if( crc & (1L << 31)) crc = (crc << 1) ^ poly;
else crc = (crc << 1);
}
}
if(outR) {
#ifdef SYS_CRC
crc = __RBIT(crc);
#else
crc = reflect32(crc);
#endif
}
if(initCRC == 1) crc = ~crc;
return crc;
}
/* uint32_t calcCRC32std(void *data, uint32_t len,
uint32_t poly, uint32_t seed, uint32_t initCRC, uint32_t inR, uint32_t outR)
{
uint32_t crc;
unsigned char* current = (unsigned char*) data;
uint8_t byte;
crc = seed;
while (len--) {
byte = *current++;
if(inR) {
byte = reflect8(byte);
}
crc ^= byte;
for (unsigned int j = 0; j < 8; j++) {
if (crc & 1)
crc = (crc >> 1) ^ poly;
else
crc = crc >> 1;
}
}
if(outR) {
crc = reflect32(crc);
}
if(initCRC == 1) crc = ~crc;
return crc;
}*/
#ifdef SYS_CRC
uint32_t crc32_check (CRC_HandleTypeDef *hcrc, uint8_t* buf, uint16_t len) {
uint32_t* pBuffer = (uint32_t*)buf;
uint32_t BufferLength = (len/4); //(Length of buf uint8 to Length of buf uint32 is 1 by 4)
uint32_t index = 0;
__HAL_CRC_DR_RESET(hcrc);
for(index = 0; index < BufferLength; index++) {
hcrc->Instance->DR = __RBIT(pBuffer[index]);
}
return __RBIT(hcrc->Instance->DR) ^ 0xFFFFFFFF;
}
#endif

View File

@@ -0,0 +1,258 @@
#include <stdio.h>
#include "main.h"
#include <string.h>
#include "cmsis_os.h"
#include "commonMsg.h"
/* Demo includes. */
#include "currentMeas.h"
#include "automation.h"
#include "utils.h"
#include "signals.h"
#include <math.h>
#include <limits.h>
#define ACS724
#define MVOLT_PER_AMP_05AB 400 // ACS724LLCTR-05AB-T +/- 5A
#define MVOLT_PER_AMP_20AB 100 // ACS724LLCTR-20AB-T +/- 20A
#define ADC1_DMABufferSize 1 // counts for measuring system voltage reference
#define ADC1_CHANNELS 3
#define ADC2_DMABufferSize 30 // counts for measuring TRMS current
#define ADC2_CHANNELS 2
extern TIM_HandleTypeDef htim6;
extern ADC_HandleTypeDef hadc1, hadc2;
extern osSemaphoreId ADC1SemHandle;
extern osSemaphoreId ADC2SemHandle;
extern osMutexId measMutexHandle;
uint16_t adc1_buffer[ADC1_DMABufferSize][ADC1_CHANNELS] = {0};
uint16_t raw1_buffer[ADC1_DMABufferSize][ADC1_CHANNELS] = {0};
uint16_t adc2_buffer[ADC2_DMABufferSize][ADC2_CHANNELS] = {0};
uint16_t raw2_buffer[ADC2_DMABufferSize][ADC2_CHANNELS] = {0};
CURRENT_THRESHOLD_STRUCT current_thresholds[] = {
{ CURRENT_VALVE_REF, CURRENT_VALVE_UPPER_LIMIT, CURRENT_VALVE_LOWER_LIMIT }, // Valve
{ CURRENT_ACTUATOR_REF, CURRENT_ACTUATOR_UPPER_LIMIT, CURRENT_ACTUATOR_LOWER_LIMIT } // Actuator
};
/*-----------------------------------------------------------*/
bool isShortedPosition( uint16_t instant_current, uint16_t current_reference )
{
return instant_current > current_reference;
}
bool isNotConnectedPosition( uint16_t instant_current_ma )
{
return instant_current_ma <= CURRENT_AT_REST_THRESHOLD_MA;
}
bool isMalfunctionPosition( uint16_t instant_current_ma, uint16_t current_reference_ma )
{
return ( instant_current_ma < current_reference_ma ) &&
!isNotConnectedPosition( instant_current_ma );
}
void current_consumption_checking(uint16_t current_ma,
CURRENT_DEVICE_TYPE device_type, uint16_t current_output_state )
{
uint16_t v = 0, v_count=0;
float current_mA = (float) current_ma / 1000.0f; // Convert to mA
if( device_type == VALVE_DEVICE ) {
current_output_state &= ALL_VALVES_MASK; // Mask to valve outputs only
}
else {
current_output_state &= ACTUATORS_MASK; // Mask to actuator outputs only
}
for (v = 0; v < (sizeof(uint16_t) * CHAR_BIT); v++)
{
if ((current_output_state >> v) & 1) {
v_count++;
}
}
// --- Logic for monitoring idle power ---
if (current_output_state == 0) { // If outputs are assumed to be at low state
if (current_mA > CURRENT_AT_REST_THRESHOLD_MA) {
// ALERT: Abnormal consumption
APP_LOG(TS_OFF, VLEVEL_M,"ALERT: abnormal current consumption: %.2f mA (Threshold: %.2f mA)\r\n",
current_mA, CURRENT_AT_REST_THRESHOLD_MA);
addErrorToList( 0x220 );
} else {
APP_LOG(TS_OFF, VLEVEL_M,"Outputs are low, current consumption: %.2f mA (OK)\r\n", current_mA);
}
} else { // If outputs are enabled (HIGH), check consumption
if( v_count == 1 ) { // mean one valve or one actuator is enabled
// read value from adc measurement task
APP_LOG(TS_ON, VLEVEL_M, "Device current: %.2f mA\r\n",current_mA);
if( isShortedPosition( current_mA, current_thresholds[device_type].currentUpperLimit ) ) {
APP_LOG(TS_ON, VLEVEL_M, "Warning: short circuit detected on position %d\r\n",v);
addErrorToList( 0x208 + v );
}
else if( isMalfunctionPosition( current_mA, current_thresholds[device_type].currentUpperLimit ) ) {
APP_LOG(TS_ON, VLEVEL_M, "Warning: current out-of-range on position %d\r\n",v);
addErrorToList( 0x208 + v );
}
else if( isNotConnectedPosition( current_mA ) ) {
APP_LOG(TS_ON, VLEVEL_M, "Warning: no device on position %d\r\n",v);
addErrorToList( 0x202 );
}
} else {
// Multiple outputs are enabled, we cannot determine the current for each output
APP_LOG(TS_ON, VLEVEL_M, "Warning: multiple outputs enabled (%d), current cannot be determined\r\n", v_count);
}
}
}
// --- Fonction pour calculer la valeur RMS ---
float calculate_current_rms( CURRENT_DEVICE_TYPE device_type, int acs_sensivity )
{
float sum_of_squares = 0.0f;
float voltage_measured;
float current_instantaneous;
// --- step 1 : Calculate DC offset of the signal (samples average) ---
long sum_adc_raw = 0;
for (uint16_t i = 0; i < ADC2_DMABufferSize; i++)
{
sum_adc_raw += raw2_buffer[i][device_type];
}
float average_adc_raw = (float)sum_adc_raw / ADC2_DMABufferSize;
float dc_offset_voltage = (average_adc_raw / 4095.0) * VREF;
// --- step 2 : for each sample ---
for (uint16_t i = 0; i < ADC2_DMABufferSize; i++)
{
// Convert raw ADC value to a voltage (0 à VREF)
voltage_measured = ((float)raw2_buffer[i][device_type] / 4095.0) * VREF;
// Minus DC offset for getting the AC signal
float ac_voltage = voltage_measured - dc_offset_voltage;
// Convert AC voltage in instant current
current_instantaneous = ac_voltage / acs_sensivity;
// Add the square of the instantaneous current to the sum
sum_of_squares += (current_instantaneous * current_instantaneous);
}
// --- setp 3 : Calculate the mean square
float mean_square = sum_of_squares / ADC2_DMABufferSize;
// --- step 4 : Calculate the square root (RMS) ---
float rms_current = sqrtf(mean_square);
return rms_current;
}
void external_temp_calculation( float* meas )
{
float mVoltage = raw1_buffer[0][1] * VREF / 4095;
// On-board MCP9701 device
*meas = (mVoltage - 400) / 19.5;
}
bool VREF_calculation()
{
bool ret = false;
if( raw1_buffer[0][1] > 0 ) {
VREF = __HAL_ADC_CALC_VREFANALOG_VOLTAGE(raw1_buffer[0][0], ADC_RESOLUTION_12B);
ret = true;
}
return ret;
}
void battery_voltage_calculation( float* meas )
{
float mVoltage = raw1_buffer[0][2] * VREF / 4095;
// On-board MCP9701 device
*meas = (mVoltage * 3);
}
void Reference_Meas_processFrame()
{
if( VREF_calculation() ) {
external_temp_calculation(&meas_case_temperature);
battery_voltage_calculation(&meas_battery_voltage);
}
}
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc)
{
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
if(hadc->Instance == ADC1)
{
memcpy(raw1_buffer,adc1_buffer,sizeof(adc1_buffer));
xSemaphoreGiveFromISR(ADC1SemHandle, &xHigherPriorityTaskWoken);
}
else if(hadc->Instance == ADC2)
{
//HAL_GPIO_WritePin(DBG1_GPIO_Port,DBG1_Pin,GPIO_PIN_SET);
//HAL_GPIO_TogglePin(DBG1_GPIO_Port,DBG1_Pin);
memcpy(raw2_buffer,adc2_buffer,sizeof(adc2_buffer));
xSemaphoreGiveFromISR(ADC2SemHandle, &xHigherPriorityTaskWoken);
}
portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
//HAL_GPIO_WritePin(DBG1_GPIO_Port,DBG1_Pin,GPIO_PIN_RESET);
}
void vCurrentMeasTask( void *pvParameters )
{
/* Remove warning for unused parameter */
(void)pvParameters ;
TickType_t xLastWakeTime;
const TickType_t xFrequency = pdMS_TO_TICKS(100); // Mesurer toutes les 100 ms (10 Hz)
uint16_t current_output_state = 0; // Outputs initial state
osMessageQId myQueueId = getQueueId(ADC_MEAS);
// Start ADC Calibration
while(HAL_ADCEx_Calibration_Start(&hadc1,ADC_SINGLE_ENDED) != HAL_OK )
;
while(HAL_ADCEx_Calibration_Start(&hadc2,ADC_SINGLE_ENDED) != HAL_OK )
;
// ADC1 Clk = 64MMz / 2 (synchronous prescaler) = 32MHz
// ADC VREF sampling time: 4*µs
// Minimum sampling time calculation: 4µ / (1 / 32M) = 128 cycles mini. select: 247.5
HAL_ADC_Start_DMA(&hadc1, (uint32_t*)&adc1_buffer, ((uint32_t)(ADC1_DMABufferSize*ADC1_CHANNELS)));
HAL_ADC_Start_DMA(&hadc2, (uint32_t*)&adc2_buffer, ((uint32_t)(ADC2_DMABufferSize*ADC2_CHANNELS)));
HAL_TIM_Base_Start(&htim6);
osDelay(1000); // Wait for stabilization
xLastWakeTime = xTaskGetTickCount();
while(1) {
// Convert ADC1 values
xSemaphoreTake(ADC1SemHandle, portMAX_DELAY);
// Attempt to receive the output state of the output task in a non-blocking manner.
// If a new state is available, it is updated. Otherwise, the last known state is retained.
xQueueReceive(myQueueId, &current_output_state, 0);
// Convert ADC2 values
xSemaphoreTake(ADC2SemHandle, portMAX_DELAY);
//buggy lines commented out
//meas_valves_current = calculate_current_rms( VALVE_DEVICE, MVOLT_PER_AMP_05AB );
//current_consumption_checking(meas_valves_current*1000, VALVE_DEVICE, current_output_state );
//meas_drives_current = calculate_current_rms( ACTUATOR_DEVICE, MVOLT_PER_AMP_20AB );
//current_consumption_checking(meas_drives_current*1000, ACTUATOR_DEVICE, current_output_state );
Reference_Meas_processFrame();
// Wait for the next measurement period
vTaskDelayUntil(&xLastWakeTime, xFrequency);
}
}

View File

@@ -0,0 +1,15 @@
/*
* env_sensors.c
*
* Created on: 13 mai 2023
* Author: xavie
*/
#include "env_sensors.h"
float AvgRainProbability;
float PeakRainProbability;
float AvgRainDropSize;
float PeakRainDropSize;
FLASH_ENV_SENSORS env_sensors_tab;

View File

@@ -0,0 +1,91 @@
/*
* flash_page.c
*
* Created on: May 13, 2021
* Author: xavie
*/
#include "flash_page.h"
#include "string.h"
#include "stdio.h"
#include "main.h"
static uint32_t GetPage(uint32_t Address)
{
for (int indx=0; indx < 512; indx++)
{
if((Address < (0x08000000 + (FLASH_PAGE_SIZE *(indx+1))) ) && (Address >= (0x08000000 + FLASH_PAGE_SIZE*indx)))
{
return ( Address < 0x08080000 ? indx : indx - 256 );
}
}
return -1;
}
uint32_t Flash_Write_Data (uint32_t StartPageAddress, __IO uint64_t * DATA_64, uint16_t bsize)
{
uint32_t ret = 0;
static FLASH_EraseInitTypeDef EraseInitStruct;
uint32_t PAGEError;
int sofar=0;
/* Unlock the Flash to enable the flash control register access *************/
HAL_FLASH_Unlock();
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |
FLASH_FLAG_PGAERR | FLASH_FLAG_PGSERR);
/* Erase the user Flash area*/
uint32_t StartPage = GetPage(StartPageAddress);
uint32_t EndPageAdress = StartPageAddress + bsize;
uint32_t EndPage = GetPage(EndPageAdress);
/* Fill EraseInit structure*/
EraseInitStruct.TypeErase = FLASH_TYPEERASE_PAGES;
EraseInitStruct.Banks = (StartPageAddress < 0x08080000 ? FLASH_BANK_1 : FLASH_BANK_2);
EraseInitStruct.Page = StartPage;
EraseInitStruct.NbPages = (EndPage - StartPage) +1;
if (HAL_FLASHEx_Erase(&EraseInitStruct, &PAGEError) != HAL_OK)
{
/*Error occurred while page erase.*/
ret = HAL_FLASH_GetError ();
}
/* Program the user Flash area word by word*/
bsize = ( bsize / sizeof( uint64_t ))+(( bsize % sizeof( uint64_t ))!=0);
while ( sofar < bsize && ret == HAL_OK )
{
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD, StartPageAddress, DATA_64[sofar]) == HAL_OK)
{
StartPageAddress += 8; // use StartPageAddress += 2 for half word and 8 for double word
sofar++;
}
else
{
/* Error occurred while writing data in Flash memory*/
ret = HAL_FLASH_GetError ();
}
}
/* Lock the Flash to disable the flash control register access (recommended
to protect the FLASH memory against possible unwanted operation) *********/
HAL_FLASH_Lock();
return ret;
}
void Flash_Read_Data (uint32_t StartPageAddress, __IO uint32_t * DATA_32, uint16_t wsize)
{
while (1)
{
*DATA_32 = *(__IO uint32_t *)StartPageAddress;
StartPageAddress += 4;
DATA_32++;
if (!(wsize--)) break;
}
}

View File

@@ -0,0 +1,59 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* File Name : freertos.c
* Description : Code for freertos applications
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "FreeRTOS.h"
#include "task.h"
#include "main.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* 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 Variables */
/* USER CODE END Variables */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN FunctionPrototypes */
/* USER CODE END FunctionPrototypes */
/* Private application code --------------------------------------------------*/
/* USER CODE BEGIN Application */
/* USER CODE END Application */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,360 @@
#include <automation.h>
#include "main.h"
#include <string.h>
#include <math.h>
#include <stdbool.h>
#include "cmsis_os.h"
#include "commonMsg.h"
/* Demo includes. */
#include "outputs.h"
#include "utils.h"
#include "signals.h"
#define LSBFIRST 0
#define MSBFIRST 1
#define lowByte(w) ((uint8_t) ((w) & 0xff))
#define highByte(w) ((uint8_t) ((w) >> 8))
#define FLUSHING_VALVE 15//8
#define HOLD_PRESSURE ON
/*-----------------------------------------------------------*/
extern FLASH_STRUCT Flash;
extern osMutexId flashMutexHandle;
extern TIM_HandleTypeDef htim8;
extern osThreadId automationTaskHandle;
volatile uint16_t outputs74HC955 = 0; // Current register state of the two 74HC955
uint8_t countOpenedValves( uint8_t outputs )
{
uint8_t count = 0;
for(int b=0; b<8; b++)
{
if( outputs & (1<<b) )
{
count++;
}
}
return count;
}
void shiftOut( uint8_t bitOrder, uint8_t val )
{
uint8_t i;
for (i = 0; i < 8; i++)
{
HAL_GPIO_WritePin(CLK_OUT_GPIO_Port, CLK_OUT_Pin, GPIO_PIN_RESET);
if (bitOrder == LSBFIRST)
HAL_GPIO_WritePin(DATA_OUT_GPIO_Port, DATA_OUT_Pin, !!(val & (1 << i)));
else
HAL_GPIO_WritePin(DATA_OUT_GPIO_Port, DATA_OUT_Pin, !!(val & (1 << (7 - i))));
osDelay(1);
HAL_GPIO_WritePin(CLK_OUT_GPIO_Port, CLK_OUT_Pin, GPIO_PIN_SET);
}
}
void writeOut( uint16_t data )
{
HAL_GPIO_WritePin(LATCH_OUT_GPIO_Port, LATCH_OUT_Pin, GPIO_PIN_RESET);
shiftOut(MSBFIRST, highByte(data));
shiftOut(MSBFIRST, lowByte(data));
osDelay(1);
HAL_GPIO_WritePin(LATCH_OUT_GPIO_Port, LATCH_OUT_Pin, GPIO_PIN_SET);
}
bool updateSpeedRef( uint8_t cy )
{
if( cy != UNDEF_FLOWRATE ) {
uint32_t tDelay = 100 - cy;
if( tDelay < 3 )
tDelay = 3;
else if( tDelay > 97)
tDelay = 97;
htim8.Instance->CCR2 = tDelay;
return true;
}
return false;
}
void runACmotor( uint8_t cycle )
{
if( updateSpeedRef( cycle ) ) {
HAL_TIM_OC_Start(&htim8,TIM_CHANNEL_2); // Start Timer for drive converter
}
}
void stopACmotor()
{
HAL_TIM_OC_Stop(&htim8,TIM_CHANNEL_2); // Stop Timer for drive converter
}
static uint16_t _updateOutputs( uint16_t outputs )
{
uint16_t cs_outputs;
char binaryHi[9] = {0};
char binaryLo[9] = {0};
cs_outputs = CONVERT_STATE( outputs );
itoa(highByte(cs_outputs),binaryHi,2);
itoa(lowByte(cs_outputs),binaryLo,2);
APP_LOG(TS_ON, VLEVEL_M, "Set outputs(direct) %05s %08s\r\n",binaryHi,binaryLo);
writeOut( cs_outputs );
return cs_outputs ^ ALL_VALVES_MASK; // Used by Measurements task to detect changes
}
// parameter outputs can be on 8bits or 16bits
// Pump needs to run to keep hydraulic circuit under pressure (valves need pressure to be fully closed)
static uint16_t updateOutputs( uint16_t outputs, int8_t pumpRate )
{
uint16_t temp_outputs, cs_outputs;
bool pumpRunning = false;
int16_t pumpDelay;
char binaryHi[9] = {0};
char binaryLo[9] = {0};
// If pump is running or not, the flushing valve is always closed - mounted on actuators board
outputs &= ~(BITSHIFT_OUTPUT(FLUSHING_VALVE));
// Get pump state - so at least one valve is opened
pumpRunning = outputs74HC955 & BITSHIFT_OUTPUT(Flash.settings.actuators[3].outputNum);
// Get pump delay according to valves opening
if( outputs & VALVES_MASK )
{
pumpDelay = Flash.settings.PumpStartDelay * 1000;
}
else
{
pumpDelay = Flash.settings.PumpStopDelay * 1000;
}
if( outputs != outputs74HC955 )
{
uint8_t nbActiveValves = countOpenedValves( outputs );
// Start/stop pump with delay
if( pumpDelay < 0 )
{
pumpDelay = (-pumpDelay);
if( !pumpRunning && nbActiveValves )
{
temp_outputs = outputs74HC955 | BITSHIFT_OUTPUT(Flash.settings.actuators[3].outputNum);
runACmotor(pumpRate);
}
else if( pumpRunning && !nbActiveValves )
{
temp_outputs = outputs74HC955 & ~(BITSHIFT_OUTPUT(Flash.settings.actuators[3].outputNum));
stopACmotor();
}
else
{
temp_outputs = outputs;
}
cs_outputs = CONVERT_STATE(temp_outputs);
writeOut( cs_outputs );
itoa(highByte(cs_outputs),binaryHi,2);
itoa(lowByte(cs_outputs),binaryLo,2);
APP_LOG(TS_ON, VLEVEL_M, "Set outputs(a) %05s %08s - Motor speed ref %d\r\n",binaryHi,binaryLo,pumpRate);
osDelay(pumpDelay);
if( temp_outputs == outputs )
return outputs;
outputs = (temp_outputs & ACTUATORS_MASK) | (outputs & VALVES_MASK);
cs_outputs = CONVERT_STATE(outputs);
writeOut( cs_outputs );
itoa(highByte(cs_outputs),binaryHi,2);
itoa(lowByte(cs_outputs),binaryLo,2);
APP_LOG(TS_ON, VLEVEL_M, "Set outputs(b) %05s %08s - Motor speed ref %d\r\n",binaryHi,binaryLo,pumpRate);
}
else
{
temp_outputs = outputs;
cs_outputs = CONVERT_STATE(temp_outputs);
writeOut( cs_outputs );
itoa(highByte(cs_outputs),binaryHi,2);
itoa(lowByte(cs_outputs),binaryLo,2);
APP_LOG(TS_ON, VLEVEL_M, "Set outputs(c) %05s %08s - Motor speed ref %d\r\n",binaryHi,binaryLo,pumpRate);
osDelay(pumpDelay);
if( !pumpRunning && nbActiveValves )
{
outputs = temp_outputs | BITSHIFT_OUTPUT(Flash.settings.actuators[3].outputNum);
runACmotor(pumpRate);
}
else if( pumpRunning && !nbActiveValves )
{
outputs = temp_outputs & ~(BITSHIFT_OUTPUT(Flash.settings.actuators[3].outputNum));
stopACmotor();
}
else
{
return outputs;
}
cs_outputs = CONVERT_STATE(outputs);
writeOut( cs_outputs );
itoa(highByte(cs_outputs),binaryHi,2);
itoa(lowByte(cs_outputs),binaryLo,2);
APP_LOG(TS_ON, VLEVEL_M, "Set outputs(d) %05s %08s - Motor speed ref %d\r\n",binaryHi,binaryLo,pumpRate);
}
}
else
{
updateSpeedRef( pumpRate );
itoa(highByte(CONVERT_STATE(outputs)),binaryHi,2);
itoa(lowByte(CONVERT_STATE(outputs)),binaryLo,2);
APP_LOG(TS_ON, VLEVEL_M, "Outputs unchanged %05s %08s - Motor speed ref %d\r\n",binaryHi,binaryLo,pumpRate);
}
return outputs;
}
static void Outputs_processFrame()
{
osDelay(5);
}
void reg74HC955BleMessage()
{
osMessageQId destQueue;
uint8_t buff[3] = { '#', 'O', 0 };
destQueue = (osMessageQId)getQueueId(BLE_COMM);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = OP_OUTPUT_ONCHANGE;
p_sendMsg->lParam[0] = 3;
buff[2] = lowByte(outputs74HC955);
memcpy(&(p_sendMsg->data[2]),buff,3);
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
static void Outputs_processMsg(MSG_STRUCT *p_msg)
{
uint16_t new74HC955;
if( p_msg->opcode == OP_OUTPUT_ONCHANGE )
{
ActuatorStates state = p_msg->changeState;
switch( state ) {
case Z_ALL_OFF:
new74HC955 = ALL_OUTPUTS_OFF;
break;
case Z_START:
new74HC955 = outputs74HC955 | p_msg->outputs;
break;
case Z_STOP:
new74HC955 = outputs74HC955 & (~p_msg->outputs);
break;
case Z_UPDATE:
new74HC955 = (outputs74HC955 & ACTUATORS_MASK) | (p_msg->outputs & VALVES_MASK);
break;
default:
return;
}
outputs74HC955 = updateOutputs(new74HC955,p_msg->pumpRate);
reg74HC955BleMessage();
}
osDelay( 5 );
}
uint8_t isCurrentRefSaved()
{
float totalCurrent = 0;
for( int a=0; a < 4; a++ )
{
totalCurrent += Flash.settings.actuators[a].avgCurrentConsumption;
}
return ( totalCurrent > 0 );
}
static void Outputs_ProcessChecking()
{
osMessageQId destQueue;
uint16_t output_state = 0x0000;
destQueue = (osMessageQId)getQueueId(ADC_MEAS);
for( int v = 1; v < 9; v++ )
{
output_state = _updateOutputs( BITSHIFT_OUTPUT(v) );
osDelay(100);
// Send output state to the measurement task
// Buggy line commented out
//xQueueSend(destQueue, &output_state, 0);
osDelay(100);
}
for( int a = 9; a < 13; a++ )
{
// Keep all valves closed to put them under pressure - Required for better performance
output_state = _updateOutputs( BITSHIFT_OUTPUT(a) );
osDelay(100);
// Send output state to the measurement task
xQueueSend(destQueue, &output_state, 0);
osDelay(100);
}
// Put hydraulic circuit under pressure to be sure that valves will not leak
osDelay(1200);
_updateOutputs(ALL_OUTPUTS_OFF);
}
void vOutputsTask( void *pvParameters )
{
/* Remove warning for unused parameter */
(void)pvParameters ;
osMessageQId myQueueId = getQueueId(OUTPUTS);
// Enable all outputs
HAL_GPIO_WritePin(OE_GPIO_Port, OE_Pin, GPIO_PIN_RESET);
taskENTER_CRITICAL();
_updateOutputs(ALL_OUTPUTS_OFF);
taskEXIT_CRITICAL();
APP_LOG(TS_ON, VLEVEL_M, "Switching all Valves off...\r\n");
// Waiting for reading parameters
ulTaskNotifyTake( pdFALSE, portMAX_DELAY );
osStatus status = osMutexWait(flashMutexHandle, 0);
if( status == osOK )
{
//osDelay(2000);
APP_LOG(TS_ON, VLEVEL_M, "Starting outputs auto-test\r\n");
Outputs_ProcessChecking();
osMutexRelease(flashMutexHandle);
APP_LOG(TS_ON, VLEVEL_M, "Outputs auto-test done\r\n");
// Unlock automation task
xTaskNotifyGive( automationTaskHandle );
}
while(1)
{
osEvent event;
event = osMessageGet( myQueueId, 100 );
if (event.status == osEventMessage)
{
MSG_STRUCT* p_recvMsg = event.value.p;
Outputs_processMsg(p_recvMsg);
freeMemoryPoolMessage(p_recvMsg);
}
else if (event.status == osEventTimeout) {
Outputs_processFrame();
}
}
}

View File

@@ -0,0 +1,257 @@
#include <automation.h>
#include "parcelize.h"
extern FLASH_STRUCT Flash;
void ActuatorParcelize( char* out, int id )
{
char buf[256] = {0};
WATERING_ACTUATOR* wa;
wa = &Flash.settings.actuators[id];
sprintf(buf,"(%02d%1d[%03d%03d]%1d%04.1f)",
wa->outputNum,
wa->autoRunEnabled ? 1 : 0,
wa->setpoints[0], wa->setpoints[1],
wa->autoRunFeature,
wa->avgCurrentConsumption);
strcat(out,buf);
}
void ActuatorUnparcelize( char* in, WATERING_ACTUATOR* o )
{
o->outputNum = toInt(in,0,2);
o->autoRunEnabled = toBool(in,2);
o->setpoints[0] = toInt(in,4,7);
o->setpoints[1] = toInt(in,7,10);
o->autoRunFeature = toInt(in,11,12);
o->avgCurrentConsumption = toFloat(in,12,16);
}
void SequenceParcelize( char* out, int id )
{
char buf[50] = {0};
WATERING_VALVE* wa;
wa = &Flash.settings.valves[id];
for( int s = 0; s < 4; s++ )
{
WATERING_SEQUENCE* ws = &wa->sequence[s];
sprintf(buf,"(%03d%03d%03d[%03d%03d%03d%03d])",
ws->startYearDay,
ws->cycleTime,
ws->soakTime,
ws->runTime[0],ws->runTime[1],ws->runTime[2],ws->runTime[3]);
strcat(out,buf);
}
}
void SequenceUnparcelize( char* in, WATERING_SEQUENCE* o )
{
o->startYearDay = toInt(in,0,3);
o->cycleTime = toInt(in,3,6);
o->soakTime = toInt(in,6,9);
o->runTime[0] = toInt(in,10,13);
o->runTime[1] = toInt(in,13,16);
o->runTime[2] = toInt(in,16,19);
o->runTime[3] = toInt(in,19,22);
}
void ValveParcelize( char* buff, int id )
{
char buf[1024] = { 0 };
WATERING_VALVE* wv;
wv = &Flash.settings.valves[id];
sprintf((char*)buf,"(%1d%1d%1d%1d",
wv->id,
wv->MV_Pump ? 1 : 0,
wv->sensorsOverride ? 1 : 0,
wv->dummy ? 1 : 0);
strcat(buff,(char*)buf);
strcat(buff,"S[");
SequenceParcelize(buff, id );
sprintf((char*)buf,"]%03d)",wv->pumpAdjust);
strcat(buff,(char*)buf);
}
void ValveUnparcelize( char* in, WATERING_VALVE* o )
{
o->id = toInt(in,0,1);
o->MV_Pump = toBool(in,1);
o->sensorsOverride = toBool(in,2);
o->dummy = toBool(in,3);
int index = 7;
for( int s=0; s < 4; s++ )
{
SequenceUnparcelize( &in[index+(s*25)], &o->sequence[s] );
}
index += 100;
o->pumpAdjust = toInt(in,index,index+3);
}
void ProgramParcelize( char* buff, int id )
{
char buf[1024];
WATERING_PROGRAM* wp;
wp = &Flash.settings.programs[id];
sprintf(buf,"(%1d%03d%1d000%1d",
wp->id,
wp->wateringWeekDay,
wp->period,
wp->nStartTimes);
strcat(buff,buf);
strcat(buff,"T[");
for( int d=0; d < wp->nStartTimes; d++ )
{
sprintf(buf,"%04d",wp->startTimes[d]);
strcat(buff,buf);
}
strcat(buff,"]");
sprintf(buf,"%03d%1d%03d)",
wp->seasonalAdjust,
wp->monthlySeasonalAdjust ? 1 : 0,
wp->valveDelay);
strcat(buff,buf);
}
void ProgramUnparcelize( char* in, WATERING_PROGRAM* o )
{
o->id = toInt(in,0,1);
o->wateringWeekDay = toInt(in,1,4);
o->period = toInt(in,4,5);
//int dummy = toInt(in,5,8);
o->nStartTimes = toInt(in,8,9);
for( int t=0; t < o->nStartTimes; t++ )
{
o->startTimes[t] = toInt(in,11+(t*4),15+(t*4));
}
int index = 12 + (o->nStartTimes*4);
o->seasonalAdjust = toInt(in,index,index+3);
o->monthlySeasonalAdjust = toBool(in,index+3);
o->valveDelay = toInt(in,index+4,index+7);
}
int GeneralParcelize( char* buff )
{
char buf[SETTINGS_BUFFER_SIZE];
WATERING_GENERAL* wg;
wg = &Flash.settings;
sprintf(buf,"%08X%03d%03d%03d%04d%04d%03d",
DATA_VERSION,
wg->PumpStartDelay,
wg->PumpStopDelay,
wg->FlushingTime,
wg->auxStartTime,
wg->auxEndTime,
wg->timeZoneOffset);
strcat(buff,buf);
strcat(buff,"A[");
for( int a=0; a<5; a++ )
ActuatorParcelize( buff, a );
strcat(buff,"]P[");
for( int p=0; p<4; p++ )
ProgramParcelize( buff, p );
strcat(buff,"]V[");
for( int v=0; v<8; v++ )
ValveParcelize( buff, v );
strcat(buff,"]M[");
for( int m=0; m<12; m++ )
{
sprintf(buf,"%03d",wg->seasonalMonthlyParam[m]);
strcat(buff,buf);
}
strcat(buff,"]");
return strlen(buff);
}
bool GeneralUnparcelize( char* in, WATERING_GENERAL* o )
{
char out[128];
substring(in,out,0,8);
long version = DATA_VERSION;
if( !memcmp((void*)out,(void*)&version,4) )
return false;
o->versionID = DATA_VERSION;
o->PumpStartDelay = toInt(in,8,11);
o->PumpStopDelay = toInt(in,11,14);
o->FlushingTime = toInt(in,14,17);
o->auxStartTime = toInt(in,17,21);
o->auxEndTime = toInt(in,21,25);
o->timeZoneOffset = toInt(in,25,28);
int endIndex = 0;
for( int a = 0; a < 5; a++ )
{
endIndex = 47 + ( a * 18 );
substring(in,out,31+(a*18),endIndex);
ActuatorUnparcelize( out, &(o->actuators[a]) );
}
endIndex += 5;
for( int p = 0; p < 4; p++ )
{
char *pos = strchr (&in[endIndex], ')');
int endIndexPgm = pos ? pos - in : -1;
substring(in,out,endIndex,endIndexPgm);
ProgramUnparcelize( out, &(o->programs[p]) );
endIndex = endIndexPgm + 2;
}
endIndex += 3;
for( int v = 0; v < 8; v++ )
{
substring(in,out,endIndex,endIndex+110);
ValveUnparcelize( out, &(o->valves[v]) );
endIndex += 112;
}
endIndex += 2;
for( int m = 0; m < 12; m++ )
{
substring(in,out,endIndex,endIndex+3);
Flash.settings.seasonalMonthlyParam[m] = atoi(out);
endIndex += 3;
}
return true;
}
void EnvSensorsParcelize( char* buff )
{
char buf[25];
sprintf(buf,"%02d",env_sensors_tab.nbr);
for( int i = 0; i < ENV_SENSORS_NBR; i++ )
{
env_sensors_t* es = &env_sensors_tab.env_sensors[i];
sprintf(buf,"%04d%02d",es->can_address,es->param_id);
strcat(buff,buf);
}
}
void EnvSensorsUnparcelize( char* in, FLASH_ENV_SENSORS* o )
{
memset(o,0,sizeof(FLASH_ENV_SENSORS));
o->nbr = toInt(in,0,2);
for( int ev = 0; ev < o->nbr; ev++ )
{
int offset = 7 * ev;
env_sensors_t* es = &o->env_sensors[ev];
es->can_address = toInt(in,2+offset,6+offset);
es->param_id = toInt(in,6+offset,9+offset);
}
}

View File

@@ -0,0 +1,446 @@
#include <assert.h>
#include "main.h"
#include "pcanpro_can.h"
extern CAN_HandleTypeDef hcan1;
#define CAN_TX_FIFO_SIZE (256)
static struct t_can_dev
{
void *dev;
uint32_t tx_msgs;
uint32_t tx_errs;
uint32_t tx_ovfs;
uint32_t rx_msgs;
uint32_t rx_errs;
uint32_t rx_ovfs;
struct t_can_msg tx_fifo[CAN_TX_FIFO_SIZE];
uint32_t tx_head;
uint32_t tx_tail;
uint32_t esr_reg;
int (*rx_isr)( uint8_t, struct t_can_msg* );
int (*tx_isr)( uint8_t, struct t_can_msg* );
void (*err_handler)( int bus, uint32_t esr );
}
can_dev_array[CAN_BUS_TOTAL] =
{
[CAN_BUS_1] = { .dev = &hcan1 },
// [CAN_BUS_2] = { .dev = &hcan[CAN_BUS_2] },
};
uint32_t pcan_can_msg_time( const struct t_can_msg *pmsg, uint32_t nt, uint32_t dt )
{
const uint32_t data_bits = pmsg->size<<3;
const uint32_t control_bits = ( pmsg->flags & MSG_FLAG_EXT ) ? 67:47;
if( pmsg->flags & MSG_FLAG_BRS )
return (control_bits*nt) + (data_bits*dt);
else
return (control_bits+data_bits)*nt;
}
int pcan_can_set_filter_mask( int bus, int num, int format, uint32_t id, uint32_t mask )
{
CAN_FilterTypeDef filter = { 0 };
CAN_HandleTypeDef *p_can = can_dev_array[bus].dev;
if( num >= CAN_INT_FILTER_MAX )
return -1;
/* CAN1 & CAN2 filter shared 28 filters, we use 14 for each one */
/*if( p_can->Instance == CAN2 )
{
num += CAN2_FILTER_START;
}*/
filter.FilterMode = CAN_FILTERMODE_IDMASK;
filter.FilterScale = CAN_FILTERSCALE_32BIT;
if( format == MSG_FLAG_EXT )
{
id &= 0x1FFFFFFF;
/* EXTID[28:13] */
filter.FilterIdHigh = id >> 13;
/* EXTID[12:0] + IDE */
filter.FilterIdLow = ((id << 3)&0xFFFF) | CAN_ID_EXT;
filter.FilterMaskIdHigh = mask >> 13;
filter.FilterMaskIdLow = ((mask << 3)&0xFFFF) | CAN_ID_EXT;
}
else
{
id &= 0x7FF;
filter.FilterIdHigh = id << 5;
filter.FilterIdLow = 0x0;
filter.FilterMaskIdHigh = mask << 5;
filter.FilterMaskIdLow = 0x0;
}
filter.FilterFIFOAssignment = CAN_FILTER_FIFO0;
filter.FilterActivation = ENABLE;
filter.FilterBank = num;
filter.SlaveStartFilterBank = CAN2_FILTER_START;
if( HAL_CAN_ConfigFilter( p_can, &filter ) != HAL_OK )
return -1;
return 0;
}
int pcan_can_filter_init_stdid_list( int bus, const uint16_t *id_list, int id_len )
{
CAN_FilterTypeDef filter = { 0 };
CAN_HandleTypeDef *p_can = can_dev_array[bus].dev;
int i, offset = 0;
//offset = ( p_can->Instance == CAN2 ) ? CAN2_FILTER_START: 0;
/* STDID[10:3] | STDID[2:0] RTR IDE EXID[17:15] */
/* IDE = 0, RTR = 0, EXID[17:15] = { 0 } */
filter.FilterMode = CAN_FILTERMODE_IDLIST;
filter.FilterScale = CAN_FILTERSCALE_16BIT;
i = 0;
while( i < id_len )
{
filter.FilterBank = ((i)>>2)+offset;
filter.SlaveStartFilterBank = CAN2_FILTER_START;
filter.FilterMaskIdLow = 0;
filter.FilterMaskIdHigh = 0;
filter.FilterIdLow = 0;
filter.FilterIdHigh = 0;
switch( (id_len-i) )
{
/* fallthrough */
default:
filter.FilterMaskIdLow = id_list[i++]<<5;
case 3:
filter.FilterMaskIdHigh = id_list[i++]<<5;
case 2:
filter.FilterIdLow = id_list[i++]<<5;
case 1:
filter.FilterIdHigh = id_list[i++]<<5;
}
filter.FilterFIFOAssignment = CAN_FILTER_FIFO0;
filter.FilterActivation = ENABLE;
if( HAL_CAN_ConfigFilter( p_can, &filter ) != HAL_OK )
return -1;
}
return id_len;
}
static int _can_send( CAN_HandleTypeDef *p_can, struct t_can_msg *p_msg )
{
CAN_TxHeaderTypeDef msg = { .TransmitGlobalTime = DISABLE };
uint32_t txMailbox = 0;
if( HAL_CAN_IsTxMessagePending( p_can, CAN_TX_MAILBOX0 ) )
return -1;
if( p_msg->flags & MSG_FLAG_EXT )
{
msg.ExtId = p_msg->id & 0x1FFFFFFF;
msg.IDE = CAN_ID_EXT;
}
else
{
msg.StdId = p_msg->id & 0x7FF;
msg.IDE = CAN_ID_STD;
}
msg.DLC = p_msg->size;
msg.RTR = (p_msg->flags & MSG_FLAG_RTR)?CAN_RTR_REMOTE:CAN_RTR_DATA;
if( HAL_CAN_AddTxMessage( p_can, &msg, (void*)p_msg->data, &txMailbox ) != HAL_OK )
return -1;
return txMailbox;
}
static void pcan_can_flush_tx( int bus )
{
struct t_can_dev *p_dev = &can_dev_array[bus];
struct t_can_msg *p_msg;
/* empty fifo */
if( p_dev->tx_head == p_dev->tx_tail )
return;
p_msg = &p_dev->tx_fifo[p_dev->tx_tail];
if( _can_send( p_dev->dev, p_msg ) < 0 )
return;
if( p_dev->tx_isr )
{
(void)p_dev->tx_isr( bus, p_msg );
}
/* update fifo index */
p_dev->tx_tail = (p_dev->tx_tail+1)&(CAN_TX_FIFO_SIZE-1);
}
int pcan_can_write( int bus, struct t_can_msg *p_msg )
{
struct t_can_dev *p_dev = &can_dev_array[bus];
if( !p_msg )
return 0;
uint32_t tx_head_next = (p_dev->tx_head+1)&(CAN_TX_FIFO_SIZE-1);
/* overflow ? just skip it */
if( tx_head_next == p_dev->tx_tail )
{
++p_dev->tx_ovfs;
return -1;
}
p_dev->tx_fifo[p_dev->tx_head] = *p_msg;
p_dev->tx_head = tx_head_next;
return 0;
}
void pcan_can_install_rx_callback( int bus, int (*cb)( uint8_t, struct t_can_msg* ) )
{
struct t_can_dev *p_dev = &can_dev_array[bus];
p_dev->rx_isr = cb;
}
void pcan_can_install_tx_callback( int bus, int (*cb)( uint8_t, struct t_can_msg* ) )
{
struct t_can_dev *p_dev = &can_dev_array[bus];
p_dev->tx_isr = cb;
}
void pcan_can_install_err_callback( int bus, void (*cb)( int , uint32_t ) )
{
struct t_can_dev *p_dev = &can_dev_array[bus];
p_dev->err_handler = cb;
}
void pcan_can_set_silent( int bus, uint8_t silent_mode )
{
CAN_HandleTypeDef *p_can = can_dev_array[bus].dev;
p_can->Init.Mode = silent_mode ? CAN_MODE_SILENT: CAN_MODE_NORMAL;
if( HAL_CAN_Init( p_can ) != HAL_OK )
{
assert( 0 );
}
}
/* bxCAN does not support FDCAN ISO mode switch */
void pcan_can_set_iso_mode( int bus, uint8_t iso_mode )
{
(void)bus;
(void)iso_mode;
}
void pcan_can_set_loopback( int bus, uint8_t loopback )
{
CAN_HandleTypeDef *p_can = can_dev_array[bus].dev;
p_can->Init.Mode = loopback ? CAN_MODE_LOOPBACK: CAN_MODE_NORMAL;
if( HAL_CAN_Init( p_can ) != HAL_OK )
{
assert( 0 );
}
}
void pcan_can_set_bus_active( int bus, uint16_t mode )
{
CAN_HandleTypeDef *p_can = can_dev_array[bus].dev;
if( mode )
{
HAL_CAN_Start( p_can );
HAL_CAN_AbortTxRequest( p_can, CAN_TX_MAILBOX0 | CAN_TX_MAILBOX1 | CAN_TX_MAILBOX2 );
}
else
{
HAL_CAN_AbortTxRequest( p_can, CAN_TX_MAILBOX0 | CAN_TX_MAILBOX1 | CAN_TX_MAILBOX2 );
HAL_CAN_Stop( p_can );
}
}
static void pcan_can_tx_complete( int bus, int mail_box )
{
++can_dev_array[bus].tx_msgs;
}
static void pcan_can_tx_err( int bus, int mail_box )
{
++can_dev_array[bus].tx_errs;
}
int pcan_can_stats( int bus, struct t_can_stats *p_stats )
{
struct t_can_dev *p_dev = &can_dev_array[bus];
p_stats->tx_msgs = p_dev->tx_msgs;
p_stats->tx_errs = p_dev->tx_errs;
p_stats->rx_msgs = p_dev->rx_msgs;
p_stats->rx_errs = p_dev->rx_errs;
p_stats->rx_ovfs = p_dev->rx_ovfs;
return sizeof( struct t_can_stats );
}
void pcan_can_poll( void )
{
static uint32_t err_last_check = 0;
uint32_t ts_ms;
//ts_ms = HAL_GetTick();
ts_ms = xTaskGetTickCount() * (1000 / configTICK_RATE_HZ);
#if ( CAN_WITHOUT_ISR == 1 )
HAL_CAN_IRQHandler( &hcan[CAN_BUS_1] );
// HAL_CAN_IRQHandler( &hcan[CAN_BUS_2] );
#endif
pcan_can_flush_tx( CAN_BUS_1 );
// pcan_can_flush_tx( CAN_BUS_2 );
if( (uint32_t)( err_last_check - ts_ms ) > 250 )
{
err_last_check = ts_ms;
for( int i = 0; i < CAN_BUS_TOTAL; i++ )
{
if( !can_dev_array[i].err_handler )
continue;
CAN_HandleTypeDef *pcan = can_dev_array[i].dev;
if( can_dev_array[i].esr_reg != pcan->Instance->ESR )
{
can_dev_array[i].esr_reg = pcan->Instance->ESR;
can_dev_array[i].err_handler( i, can_dev_array[i].esr_reg );
}
}
}
}
/* --------------- HAL PART ------------- */
static int _bus_from_int_dev( CAN_TypeDef *can )
{
// if( can == CAN1 )
// return CAN_BUS_1;
// else if( can == CAN2 )
// return CAN_BUS_2;
/* abnormal! */
return CAN_BUS_1;
}
static void pcan_can_isr_frame( CAN_HandleTypeDef *hcan, uint32_t fifo )
{
CAN_RxHeaderTypeDef hdr;
const int bus = _bus_from_int_dev( hcan->Instance );
struct t_can_dev * const p_dev = &can_dev_array[bus];
struct t_can_msg msg = { 0 };
if( HAL_CAN_GetRxMessage( hcan, fifo, &hdr, msg.data ) != HAL_OK )
return;
/* oversize frame ? */
if( hdr.DLC > CAN_PAYLOAD_MAX_SIZE )
return;
if( hdr.IDE == CAN_ID_STD )
{
msg.id = hdr.StdId;
}
else
{
msg.id = hdr.ExtId;
msg.flags |= MSG_FLAG_EXT;
}
if( hdr.RTR != CAN_RTR_DATA )
{
msg.flags |= MSG_FLAG_RTR;
}
msg.size = hdr.DLC;
//msg.timestamp = pcan_timestamp_us();
if( p_dev->rx_isr )
{
if( p_dev->rx_isr( bus, &msg ) < 0 )
{
++p_dev->rx_ovfs;
return;
}
}
++p_dev->rx_msgs;
}
/* CAN HAL subsystem callbacks */
void HAL_CAN_TxMailbox0CompleteCallback( CAN_HandleTypeDef *hcan )
{
pcan_can_tx_complete( _bus_from_int_dev( hcan->Instance ), 0 );
}
void HAL_CAN_TxMailbox1CompleteCallback( CAN_HandleTypeDef *hcan )
{
pcan_can_tx_complete( _bus_from_int_dev( hcan->Instance ), 1 );
}
void HAL_CAN_TxMailbox2CompleteCallback( CAN_HandleTypeDef *hcan )
{
pcan_can_tx_complete( _bus_from_int_dev( hcan->Instance ), 2 );
}
void HAL_CAN_TxMailbox0AbortCallback( CAN_HandleTypeDef *hcan ){}
void HAL_CAN_TxMailbox1AbortCallback( CAN_HandleTypeDef *hcan ){}
void HAL_CAN_TxMailbox2AbortCallback( CAN_HandleTypeDef *hcan ){}
void HAL_CAN_RxFifo0MsgPendingCallback( CAN_HandleTypeDef *hcan )
{
pcan_can_isr_frame( hcan, CAN_RX_FIFO0 );
}
void HAL_CAN_RxFifo1MsgPendingCallback( CAN_HandleTypeDef *hcan )
{
pcan_can_isr_frame( hcan, CAN_RX_FIFO1 );
}
void HAL_CAN_RxFifo0FullCallback( CAN_HandleTypeDef *hcan )
{
}
void HAL_CAN_RxFifo1FullCallback( CAN_HandleTypeDef *hcan )
{
}
void HAL_CAN_SleepCallback( CAN_HandleTypeDef *hcan ){}
void HAL_CAN_WakeUpFromRxMsgCallback( CAN_HandleTypeDef *hcan ){}
void HAL_CAN_ErrorCallback( CAN_HandleTypeDef *hcan )
{
/* handle errors */
uint32_t err = HAL_CAN_GetError( hcan );
int bus = _bus_from_int_dev( hcan->Instance );
if ( err & HAL_CAN_ERROR_TX_TERR0 )
{
pcan_can_tx_err( bus, 0 );
}
if ( err & HAL_CAN_ERROR_TX_TERR1 )
{
pcan_can_tx_err( bus, 1 );
}
if ( err & HAL_CAN_ERROR_TX_TERR2 )
{
pcan_can_tx_err( bus, 2 );
}
HAL_CAN_ResetError( hcan );
}

View File

@@ -0,0 +1,588 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file rtc_if.c
* @author MCD Application Team
* @brief Configure RTC Alarm, Tick and Calendar manager
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include <automation.h>
#include <math.h>
#include "main.h" /*for Mx generated RTC_N_PREDIV_S and RTC_N_PREDIV_A*/
#include <stdbool.h>
#include "rtc_if.h"
#include "utils.h"
/* USER CODE BEGIN Includes */
#include <string.h>
#include "commonMsg.h"
#include "actuator_mgr.h"
/* USER CODE END Includes */
/* External variables ---------------------------------------------------------*/
extern RTC_HandleTypeDef hrtc;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Private typedef -----------------------------------------------------------*/
typedef struct
{
uint32_t Rtc_Time; /* Reference time */
RTC_TimeTypeDef RTC_Calndr_Time; /* Reference time in calendar format */
RTC_DateTypeDef RTC_Calndr_Date; /* Reference date in calendar format */
} RtcTimerContext_t;
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
#define MAX_TS_SIZE (int) 16
#define MIN_ALARM_DELAY 3 /* in ticks */
/* RTC Ticks/ms conversion */
#define RTC_BKP_SECONDS RTC_BKP_DR0
#define RTC_BKP_SUBSECONDS RTC_BKP_DR1
#define RTC_BKP_MSBTICKS RTC_BKP_DR2
/* Sub-second mask definition */
#define RTC_ALARMSUBSECONDMASK RTC_N_PREDIV_S<<RTC_ALRMASSR_MASKSS_Pos
/* RTC Time base in us */
#define USEC_NUMBER 1000000
#define MSEC_NUMBER (USEC_NUMBER/1000)
#define COMMON_FACTOR 3
#define CONV_NUMER (MSEC_NUMBER>>COMMON_FACTOR)
#define CONV_DENOM (1<<(RTC_N_PREDIV_S-COMMON_FACTOR))
#define DAYS_IN_LEAP_YEAR (uint32_t) 366
#define DAYS_IN_YEAR (uint32_t) 365
#define SECONDS_IN_1DAY (uint32_t) 86400
#define SECONDS_IN_1HOUR (uint32_t) 3600
#define SECONDS_IN_1MINUTE (uint32_t) 60
#define MINUTES_IN_1HOUR (uint32_t) 60
#define HOURS_IN_1DAY (uint32_t) 24
#define DAYS_IN_MONTH_CORRECTION_NORM ((uint32_t) 0x99AAA0 )
#define DAYS_IN_MONTH_CORRECTION_LEAP ((uint32_t) 0x445550 )
/* Calculates ceiling(X/N) */
#define DIVC(X,N) ( ( (X) + (N) -1 ) / (N) )
//#define RTIF_DEBUG
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
#ifdef RTIF_DEBUG
#include "sys_app.h" /*for app_log*/
#define RTC_IF_DBG_PRINTF(...) do{ {UTIL_ADV_TRACE_COND_FSend(VLEVEL_ALWAYS, T_REG_OFF, TS_OFF, __VA_ARGS__);} }while(0);
#else
#define RTC_IF_DBG_PRINTF(...)
#endif /* RTIF_DEBUG */
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
RTC_AlarmTypeDef sAlarm;
char cur_time[80], cur_date[80];
/*!
* \brief Indicates if the RTC is already Initialized or not
*/
static bool RTC_Initalized = false;
/*!
* Keep the value of the RTC timer when the RTC alarm is set
* Set with the RTC_SetTimerContext function
* Value is kept as a Reference to calculate alarm
*/
static RtcTimerContext_t RtcTimerContext;
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/*!
* @brief get current time from calendar in ticks
* @param pointer to RTC_DateStruct
* @param pointer to RTC_TimeStruct
* @retval time in ticks
*/
static uint32_t RTC_GetCalendarValue(RTC_DateTypeDef *RTC_DateStruct, RTC_TimeTypeDef *RTC_TimeStruct);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Exported variables ---------------------------------------------------------*/
/*Timer driver*/
const UTIL_TIMER_Driver_s UTIL_TimerDriver =
{
RTC_IF_Init,
RTC_IF_SetTimerContext,
RTC_IF_GetTimerContext,
RTC_IF_GetTimerElapsedTime,
RTC_IF_GetTimerValue,
RTC_IF_GetMinimumTimeout,
RTC_IF_Convert_ms2Tick,
RTC_IF_Convert_Tick2ms,
};
/*System Time driver*/
const UTIL_SYSTIM_Driver_s UTIL_SYSTIMDriver =
{
RTC_IF_BkUp_Write_Seconds,
RTC_IF_BkUp_Read_Seconds,
RTC_IF_BkUp_Write_SubSeconds,
RTC_IF_BkUp_Read_SubSeconds,
RTC_IF_GetTime,
};
/* USER CODE BEGIN Exported_Variables */
/* USER CODE END Exported_Variables */
/* Exported functions ---------------------------------------------------------*/
/* USER CODE BEGIN Exported_Functions */
/* USER CODE END Exported_Functions */
void RTC_IF_Init(void)
{
if (RTC_Initalized == false)
{
RTC_IF_DBG_PRINTF("RTC_init\n\r");
MX_RTC_Init();
/** Configure the Alarm A */
HAL_RTC_DeactivateAlarm(&hrtc, RTC_ALARM_A);
/** Configure the Alarm B */
HAL_RTC_DeactivateAlarm(&hrtc, RTC_ALARM_B);
/*Enable Direct Read of the calendar registers (not through Shadow) */
HAL_RTCEx_EnableBypassShadow(&hrtc);
RTC_IF_SetTimerContext();
RTC_Initalized = true;
}
}
uint32_t RTC_IF_SetTimerContext(void)
{
/*store time context*/
RtcTimerContext.Rtc_Time = RTC_GetCalendarValue(&RtcTimerContext.RTC_Calndr_Date, &RtcTimerContext.RTC_Calndr_Time);
RTC_IF_DBG_PRINTF("RTC_IF_SetTimerContext=%d\n\r", RtcTimerContext.Rtc_Time);
/*return time context*/
return (uint32_t) RtcTimerContext.Rtc_Time;
}
uint32_t RTC_IF_GetTimerContext(void)
{
RTC_IF_DBG_PRINTF("RTC_IF_GetTimerContext=%d\n\r", RtcTimerContext.Rtc_Time);
/*return time context*/
return (uint32_t) RtcTimerContext.Rtc_Time;
}
uint32_t RTC_IF_GetTimerElapsedTime(void)
{
RTC_TimeTypeDef RTC_TimeStruct;
RTC_DateTypeDef RTC_DateStruct;
uint32_t CalendarValue = RTC_GetCalendarValue(&RTC_DateStruct, &RTC_TimeStruct);
return ((uint32_t)(CalendarValue - RtcTimerContext.Rtc_Time));
}
uint32_t RTC_IF_GetTimerValue(void)
{
uint32_t CalendarValue = 0;
RTC_TimeTypeDef RTC_TimeStruct;
RTC_DateTypeDef RTC_DateStruct;
if (RTC_Initalized == true)
{
CalendarValue = (uint32_t) RTC_GetCalendarValue(&RTC_DateStruct, &RTC_TimeStruct);
}
return CalendarValue;
}
uint32_t RTC_IF_GetMinimumTimeout(void)
{
return (MIN_ALARM_DELAY);
}
uint32_t RTC_IF_Convert_ms2Tick(uint32_t timeMilliSec)
{
return (uint32_t)((((uint64_t)timeMilliSec) * CONV_DENOM) / CONV_NUMER);
}
uint32_t RTC_IF_Convert_Tick2ms(uint32_t tick)
{
return (((uint64_t)(tick) * CONV_NUMER) / CONV_DENOM);
}
uint32_t RTC_IF_GetTime(uint16_t *mSeconds)
{
RTC_TimeTypeDef RTC_TimeStruct ;
RTC_DateTypeDef RTC_DateStruct;
uint32_t ticks;
uint64_t calendarValue = RTC_GetCalendarValue(&RTC_DateStruct, &RTC_TimeStruct);
uint32_t seconds = (uint32_t)(calendarValue >> RTC_N_PREDIV_S);
ticks = (uint32_t) calendarValue & RTC_PREDIV_S;
*mSeconds = RTC_IF_Convert_Tick2ms(ticks);
return seconds;
}
void RTC_IF_BkUp_Write_Seconds(uint32_t Seconds)
{
HAL_RTCEx_BKUPWrite(&hrtc, RTC_BKP_SECONDS, Seconds);
}
void RTC_IF_BkUp_Write_SubSeconds(uint32_t SubSeconds)
{
HAL_RTCEx_BKUPWrite(&hrtc, RTC_BKP_SUBSECONDS, SubSeconds);
}
uint32_t RTC_IF_BkUp_Read_Seconds(void)
{
return HAL_RTCEx_BKUPRead(&hrtc, RTC_BKP_SECONDS);
}
uint32_t RTC_IF_BkUp_Read_SubSeconds(void)
{
return HAL_RTCEx_BKUPRead(&hrtc, RTC_BKP_SUBSECONDS);
}
/* USER CODE BEGIN EF */
/* USER CODE END EF */
/* Private functions ---------------------------------------------------------*/
__STATIC_INLINE uint32_t _GetSubSecond(RTC_TypeDef *RTCx)
{
return (uint32_t)(READ_BIT(RTCx->SSR, RTC_SSR_SS));
}
/*!
* @brief get current time from calendar in ticks
* @param pointer to RTC_DateStruct
* @param pointer to RTC_TimeStruct
* @retval time in ticks
*/
static uint32_t RTC_GetCalendarValue(RTC_DateTypeDef *RTC_DateStruct, RTC_TimeTypeDef *RTC_TimeStruct)
{
uint32_t calendarValue = 0;
uint32_t first_read;
uint32_t correction;
/* Get Time and Date*/
HAL_RTC_GetTime(&hrtc, RTC_TimeStruct, RTC_FORMAT_BIN);
/* make sure it is correct due to asynchronus nature of RTC*/
do
{
first_read = _GetSubSecond(RTC);
HAL_RTC_GetDate(&hrtc, RTC_DateStruct, RTC_FORMAT_BIN);
HAL_RTC_GetTime(&hrtc, RTC_TimeStruct, RTC_FORMAT_BIN);
} while (first_read != _GetSubSecond(RTC));
/* calculte amount of elapsed days since 01/01/2000 */
calendarValue = DIVC((DAYS_IN_YEAR * 3 + DAYS_IN_LEAP_YEAR) * RTC_DateStruct->Year, 4);
correction = ((RTC_DateStruct->Year % 4) == 0) ? DAYS_IN_MONTH_CORRECTION_LEAP : DAYS_IN_MONTH_CORRECTION_NORM ;
calendarValue += (DIVC((RTC_DateStruct->Month - 1) * (30 + 31),
2) - (((correction >> ((RTC_DateStruct->Month - 1) * 2)) & 0x3)));
calendarValue += (RTC_DateStruct->Date - 1);
/* convert from days to seconds */
calendarValue *= SECONDS_IN_1DAY;
calendarValue += ((uint32_t)RTC_TimeStruct->Seconds +
((uint32_t)RTC_TimeStruct->Minutes * SECONDS_IN_1MINUTE) +
((uint32_t)RTC_TimeStruct->Hours * SECONDS_IN_1HOUR)) ;
calendarValue = (calendarValue << RTC_N_PREDIV_S) + (RTC_PREDIV_S - RTC_TimeStruct->SubSeconds);
return (calendarValue);
}
void TimestampNow(uint8_t *buff, uint16_t *size)
{
/* USER CODE BEGIN TimestampNow_1 */
/* USER CODE END TimestampNow_1 */
uint32_t ms = HAL_GetTick();
snprintf((char *)buff, MAX_TS_SIZE, "%02ld:%02ld:%02ld.%03ld: ", ms/(60*60*1000)%24, ms/(60*1000)%60, (ms/1000)%60, ms%1000);
*size = strlen((char *)buff);
/* USER CODE BEGIN TimestampNow_2 */
/* USER CODE END TimestampNow_2 */
}
void RTC_calibration( int16_t cal )
{
int16_t cal_p, cal_m;
HAL_RTCEx_SetCalibrationOutPut(&hrtc, RTC_CALIBOUTPUT_512HZ);
if (cal > 0)
{
cal_p = RTC_SMOOTHCALIB_PLUSPULSES_SET;
cal_m = 512 - cal;
}
else
{
cal_p = RTC_SMOOTHCALIB_PLUSPULSES_RESET;
cal_m = -cal;
}
HAL_RTCEx_SetSmoothCalib(&hrtc, RTC_SMOOTHCALIB_PERIOD_32SEC, cal_p, cal_m);
HAL_RTCEx_DeactivateCalibrationOutPut(&hrtc);
}
int16_t RTC_get_calibration()
{
int16_t cal;
if (hrtc.Instance->CALR & 0x8000)
{
cal = 512 - (hrtc.Instance->CALR & 0x1ff);
}
else
{
cal = -(hrtc.Instance->CALR & 0x1ff);
}
return cal;
}
// Michael Keith and Tom Craver published an expression to minimise the number of keystrokes
// needed to enter a self-contained function for converting a Gregorian date into a numerical day of the week
uint8_t get_weekday( RTC_DateTypeDef sDate )
{
int d = sDate.Date;
int m = sDate.Month;
int y = sDate.Year + 2000;
uint8_t weekday = (d += m < 3 ? y-- : y - 2, 23*m/9 + d + 4 + y/4- y/100 + y/400)%7;
return weekday;
}
uint8_t now( struct tm* tm )
{
RTC_DateTypeDef gDate;
RTC_TimeTypeDef gTime;
/* Get the RTC current Time */
HAL_RTC_GetTime(&hrtc, &gTime, RTC_FORMAT_BIN);
/* Get the RTC current Date */
HAL_RTC_GetDate(&hrtc, &gDate, RTC_FORMAT_BIN);
uint8_t weekday = get_weekday( gDate ); // Find the day of the week : 0:Sunday -> 6 Saturday
tm->tm_wday = weekday;
tm->tm_year = gDate.Year + 100;
tm->tm_mday = gDate.Date;
tm->tm_mon = gDate.Month - 1;
tm->tm_hour = gTime.Hours;
tm->tm_min = gTime.Minutes;
tm->tm_sec = gTime.Seconds;
tm->tm_isdst = -1;
tm->tm_yday = 275 * gDate.Month / 9 - 30 + gDate.Date - 2 % gDate.Month;
return weekday;
}
// yy: just the decade 2021 means 21
void set_time( uint8_t dd, uint8_t mm, uint8_t yy, uint8_t hh, uint8_t min, uint8_t sec)
{
RTC_TimeTypeDef sTime;
RTC_DateTypeDef sDate;
sTime.Hours = hh; // set hours
sTime.Minutes = min; // set minutes
sTime.Seconds = sec; // set seconds
sTime.DayLightSaving = RTC_DAYLIGHTSAVING_NONE;
sTime.StoreOperation = RTC_STOREOPERATION_RESET;
if (HAL_RTC_SetTime(&hrtc, &sTime, RTC_FORMAT_BIN) != HAL_OK)
{
Error_Handler();
}
sDate.Month = mm; // month
sDate.Date = dd; // date
sDate.Year = yy; // year
sDate.WeekDay = get_weekday(sDate); // week day
if (HAL_RTC_SetDate(&hrtc, &sDate, RTC_FORMAT_BIN) != HAL_OK)
{
Error_Handler();
}
HAL_RTCEx_BKUPWrite(&hrtc, RTC_BKP_DR1, 0x32F2); // backup register
}
uint32_t get_EpochTime()
{
struct tm datetime;
now(&datetime);
return mktime(&datetime);
}
uint8_t get_alarmA_time( uint8_t *hr, uint8_t *min, uint8_t *sec )
{
RTC_DateTypeDef gDate;
/* Get the RTC current Date */
HAL_RTC_GetDate(&hrtc, &gDate, RTC_FORMAT_BIN);
HAL_RTC_GetAlarm(&hrtc, &sAlarm, RTC_ALARM_A, RTC_FORMAT_BIN);
*hr = sAlarm.AlarmTime.Hours;
*min = sAlarm.AlarmTime.Minutes;
*sec = sAlarm.AlarmTime.Seconds;
return sAlarm.AlarmDateWeekDay;
}
void stop_alarmA()
{
HAL_RTC_DeactivateAlarm(&hrtc, RTC_ALARM_A);
}
void stop_alarmB()
{
HAL_RTC_DeactivateAlarm(&hrtc, RTC_ALARM_B);
}
int get_time(void)
{
RTC_DateTypeDef gDate;
RTC_TimeTypeDef gTime;
uint32_t first_read;
/* Get the RTC current Time */
HAL_RTC_GetTime(&hrtc, &gTime, RTC_FORMAT_BIN);
/* make sure it is correct due to asynchronous nature of RTC*/
do
{
first_read = _GetSubSecond(RTC);
HAL_RTC_GetDate(&hrtc, &gDate, RTC_FORMAT_BIN);
HAL_RTC_GetTime(&hrtc, &gTime, RTC_FORMAT_BIN);
} while (first_read != _GetSubSecond(RTC));
/* Display time Format: hh:mm:ss */
snprintf((char*)cur_time,sizeof(cur_time),"%02d:%02d:%02d",gTime.Hours, gTime.Minutes, gTime.Seconds);
/* Display date Format: dd-mm-yy */
snprintf((char*)cur_date,sizeof(cur_date),"%02d/%02d/%4d",gDate.Date, gDate.Month, 2000 + gDate.Year);
return gTime.Hours * 60 + gTime.Minutes;
}
void set_alarmA( struct tm* alarm_tm )
{
sAlarm.AlarmTime.Hours = alarm_tm->tm_hour; // hours
sAlarm.AlarmTime.Minutes = alarm_tm->tm_min; // min
sAlarm.AlarmTime.Seconds = alarm_tm->tm_sec; //seconds
sAlarm.AlarmTime.SubSeconds = 0x0;
sAlarm.AlarmTime.DayLightSaving = RTC_DAYLIGHTSAVING_NONE;
sAlarm.AlarmTime.StoreOperation = RTC_STOREOPERATION_RESET;
sAlarm.AlarmMask = RTC_ALARMMASK_NONE;
sAlarm.AlarmSubSecondMask = RTC_ALARMSUBSECONDMASK_ALL;
sAlarm.AlarmDateWeekDaySel = RTC_ALARMDATEWEEKDAYSEL_DATE;
sAlarm.AlarmDateWeekDay = alarm_tm->tm_mday; // DATE
sAlarm.Alarm = RTC_ALARM_A;
if (HAL_RTC_SetAlarm_IT(&hrtc, &sAlarm, RTC_FORMAT_BIN) != HAL_OK)
{
Error_Handler();
}
}
void set_alarmB( struct tm* alarm_tm )
{
sAlarm.AlarmTime.Hours = alarm_tm->tm_hour; // hours
sAlarm.AlarmTime.Minutes = alarm_tm->tm_min; // min
sAlarm.AlarmTime.Seconds = 0x0;
sAlarm.AlarmTime.SubSeconds = 0x0;
sAlarm.AlarmTime.DayLightSaving = RTC_DAYLIGHTSAVING_NONE;
sAlarm.AlarmTime.StoreOperation = RTC_STOREOPERATION_RESET;
sAlarm.AlarmMask = RTC_ALARMMASK_NONE;
sAlarm.AlarmSubSecondMask = RTC_ALARMSUBSECONDMASK_ALL;
sAlarm.AlarmDateWeekDaySel = RTC_ALARMDATEWEEKDAYSEL_DATE;
sAlarm.AlarmDateWeekDay = alarm_tm->tm_mday; // DATE
sAlarm.Alarm = RTC_ALARM_B;
if (HAL_RTC_SetAlarm_IT(&hrtc, &sAlarm, RTC_FORMAT_BIN) != HAL_OK)
{
Error_Handler();
}
}
void updateAutomation()
{
osMessageQId destQueue = getQueueId(AUTOMATION);
MSG_STRUCT *p_sendMsg = allocMemoryPoolMessage(); // receiver must free
p_sendMsg->opcode = OP_RTC;
p_sendMsg->outputs = ALL_OUTPUTS_OFF;
p_sendMsg->changeState = Z_UPDATE;
osMessagePut(destQueue, (uint32_t)p_sendMsg, osWaitForever);
}
void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc)
{
updateAutomation();
}
void HAL_RTCEx_AlarmBEventCallback(RTC_HandleTypeDef *hrtc)
{
updateAUXtimer( AUX_230VAC_PORT );
}
/* USER CODE BEGIN PrFD */
/* USER CODE END PrFD */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,188 @@
/*
* signals.c
*
* Created on: Jan 28, 2022
* Author: xavie
*/
#include "signals.h"
#define STSOP_LATTITUDE ((float) 49.229393 ) /*!< default latitude position */
#define STSOP_LONGITUDE ((float) 6.1033393 ) /*!< default longitude position */
#define MAX_GPS_POS ((int32_t) 8388607 ) /*!< 2^23 - 1 */
// System variables read from main unit
float meas_case_temperature; // Main unit case temperature
float meas_valves_current; // Current consumption of active valves
float meas_drives_current; // Current consumption of active drives
float meas_battery_voltage; // Vbat voltage
uint16_t VREF; // ADC reference voltage
// System variables read from CAN-BUS
// Temperature unit is degree Celsius
float gh_outsideTemperature[AIR_SENSORS]; // Outside temperature (eg. full sun, shade)
float gh_insideTemperature[AIR_SENSORS]; // Inside temperature - Used to control cooling system
uint8_t gh_insideHumidity[AIR_SENSORS]; // Inside relative humidity
float gh_solarIrradiance[AIR_SENSORS]; // Solar irradiance inside the greenhouse */
float gh_waterTankTemperature[WATER_SENSORS]; // Water tank temperature
uint8_t gh_waterTankLevel[WATER_SENSORS]; // Water tank level in percent
float gh_soilTemperature[SOIL_SENSORS]; // Soil temperature - Used to control heating cable or sprinklers
float gh_averageRainDropRate[AIR_SENSORS]; // Average rain drop rate in mm/h
float gh_averageRainDropSize[AIR_SENSORS]; // Average rain drop size in mm
float gh_averageRainDropSpeed[AIR_SENSORS]; // Average rain drop speed in m/s
uint16_t gh_rainDropCount[AIR_SENSORS]; // Total rain drop count
// Moisture unit is percent
float gh_soilMoisture[SOIL_SENSORS]; // Soil moisture - Used to control sprinklers
// Vibes unit is scale from 0(no vibes) to 5(very strong vibes)
uint8_t gh_soilVibesAiSimilarity[SOIL_SENSORS]; // Soil vibration detection AI similarity
// Atmospheric Pressure unit is hecto Pascal
uint16_t gh_atmPressure[AIR_SENSORS]; // Atmospheric pressure
// Wind speed unit is meter/second
uint16_t gh_windSpeed[AIR_SENSORS]; // Wind speed
// Wind direction unit is degree - 0 is north, 180 is south
uint16_t gh_windDirection[AIR_SENSORS]; // Wind direction
// Max wind speed in Beaufort
uint8_t gh_windMaxBeaufort[AIR_SENSORS];
// Current rain condition
uint8_t gh_rainingCondition[AIR_SENSORS];
bool gh_dropDetection[AIR_SENSORS]; // Rainy day 0=No, 1=Yes
float getAvgFloatValue( float tab[], uint16_t size )
{
float sum = 0;
uint16_t i=0, z=0;
while( i < size )
{
float t = tab[i++];
if( t == 0 ) z++;
sum += t;
}
if( size == z )
return 0;
else
return sum / (size-z);
}
// MCU_S_ANEMOMETER
float getOutsideTemperature( dev_anemometer s )
{
return s.MCU_OutsideTemp - 40;
}
uint16_t getAtmPressure( dev_anemometer s )
{
return (s.MCU_AtmPressure + 920 );
}
float getWindSpeed( dev_anemometer s )
{
return (s.MCU_WindSpeed * 0.1F );
}
uint8_t getWindDirection( dev_anemometer s )
{
return (s.MCU_WindDir );
}
uint8_t getWindBeaufort( dev_anemometer s )
{
return (s.MCU_MaxBeaufort );
}
// MCU_S_WATERTANK
uint8_t getWaterTankLevel( dev_watertank s )
{
return ( s.MCU_WaterTankLevel );
}
bool getRain( dev_watertank s )
{
return s.MCU_Rain;
}
// MCU_S_PYRANOMETER
float getSolarIrradiance( dev_pyranometer s )
{
return s.MCU_SolarIrradiance * 0.1F;
}
// MCU_S_THERMOMETER
float getInsideTemperature( dev_thermometer s )
{
return s.MCU_InsideTemp - 40;
}
uint8_t getInsideRelativeHumidity( dev_thermometer s )
{
return s.MCU_InsideHumidity;
}
// MCU_S_RAINGAUGE
uint8_t getRainingCondition( dev_rain_gauge s )
{
return s.MCU_RainingCondition;
}
// MCU_S_SUBSONICGAUGE
uint8_t getSubsonicAiSimilarity( dev_subsonic_gauge s )
{
return s.MCU_AiSimilarity;
}
// MCU_S_DISDROMETER
float getAvgRainDropRate( dev_disdrometer s )
{
return s.MCU_AvgRainDropRate * 0.01F; // mm/h;
}
float getAvgRainDropSize(dev_disdrometer s) {
return s.MCU_AvgRainDropSize * 0.01F; // mm
}
float getAvgRainDropSpeed(dev_disdrometer s) {
return s.MCU_AvgRainDropSpeed * 0.01F; // m/s
}
uint16_t getRainDropCount(dev_disdrometer s) {
return s.MCU_RainDropCount;
}
int32_t EnvSensors_Read(LoRaWAN_sensor_t *sensor_data)
{
/* USER CODE BEGIN EnvSensors_Read */
sensor_data->outsideAirTemperature = gh_outsideTemperature[0];
sensor_data->greenHouseAirTemperature = gh_insideTemperature[0];
sensor_data->greenHouseHumidity = gh_insideHumidity[0];
sensor_data->atmosphericPressure = gh_atmPressure[0];
sensor_data->waterLevel = gh_waterTankLevel[0];
sensor_data->dropDetection = gh_dropDetection[0];
sensor_data->solarIrradiance = gh_solarIrradiance[0];
//sensor_data->maxBeaufort = gh_windMaxBeaufort[0];
sensor_data->windDirection = gh_windDirection[0];
sensor_data->windSpeed = gh_windSpeed[0];
sensor_data->avgRainDropRate = gh_averageRainDropRate[0];
sensor_data->latitude = (int32_t)((STSOP_LATTITUDE * MAX_GPS_POS) / 90);
sensor_data->longitude = (int32_t)((STSOP_LONGITUDE * MAX_GPS_POS) / 180);
return 0;
/* USER CODE END EnvSensors_Read */
}
int32_t EventSensors_Read(LoRaWAN_event_sensor_t *sensor_data)
{
/* USER CODE BEGIN EventSensors_Read */
sensor_data->subsonic_AI_similarity = gh_soilVibesAiSimilarity[0];
return 0;
/* USER CODE END EnvSensors_Read */
}

View File

@@ -0,0 +1,404 @@
/**
******************************************************************************
* @file : stm32f4xx_nucleo_bus.c
* @brief : source file for the BSP BUS IO driver
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include <stm32_nucleo_bus.h>
__weak HAL_StatusTypeDef MX_SPI3_Init(SPI_HandleTypeDef* hspi);
/** @addtogroup BSP
* @{
*/
/** @addtogroup STM32F4XX_NUCLEO
* @{
*/
/** @defgroup STM32F4XX_NUCLEO_BUS STM32F4XX_NUCLEO BUS
* @{
*/
/** @defgroup STM32F4XX_NUCLEO_BUS_Exported_Variables BUS Exported Variables
* @{
*/
extern SPI_HandleTypeDef hspi3;
/**
* @}
*/
/** @defgroup STM32F4XX_NUCLEO_BUS_Private_Variables BUS Private Variables
* @{
*/
#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
static uint32_t IsSPI3MspCbValid = 0;
#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
static uint32_t SPI3InitCounter = 0;
/**
* @}
*/
/** @defgroup STM32F4XX_NUCLEO_BUS_Private_FunctionPrototypes BUS Private Function
* @{
*/
static void SPI3_MspInit(SPI_HandleTypeDef* hSPI);
static void SPI3_MspDeInit(SPI_HandleTypeDef* hSPI);
#if (USE_CUBEMX_BSP_V2 == 1)
static uint32_t SPI_GetPrescaler( uint32_t clk_src_hz, uint32_t baudrate_mbps );
#endif
/**
* @}
*/
/** @defgroup STM32F4XX_NUCLEO_LOW_LEVEL_Private_Functions STM32F4XX_NUCLEO LOW LEVEL Private Functions
* @{
*/
/** @defgroup STM32F4XX_NUCLEO_BUS_Exported_Functions STM32F4XX_NUCLEO_BUS Exported Functions
* @{
*/
/* BUS IO driver over SPI Peripheral */
/*******************************************************************************
BUS OPERATIONS OVER SPI
*******************************************************************************/
/**
* @brief Initializes SPI HAL.
* @retval BSP status
*/
int32_t BSP_SPI3_Init(void)
{
int32_t ret = BSP_ERROR_NONE;
hspi3.Instance = SPI3;
if(SPI3InitCounter++ == 0)
{
if (HAL_SPI_GetState(&hspi3) == HAL_SPI_STATE_RESET)
{
#if (USE_HAL_SPI_REGISTER_CALLBACKS == 0U)
/* Init the SPI Msp */
SPI3_MspInit(&hspi3);
#else
if(IsSPI3MspCbValid == 0U)
{
if(BSP_SPI3_RegisterDefaultMspCallbacks() != BSP_ERROR_NONE)
{
return BSP_ERROR_MSP_FAILURE;
}
}
#endif
if(ret == BSP_ERROR_NONE)
{
/* Init the SPI */
if (MX_SPI3_Init(&hspi3) != HAL_OK)
{
ret = BSP_ERROR_BUS_FAILURE;
}
}
}
}
return ret;
}
/**
* @brief DeInitializes SPI HAL.
* @retval None
* @retval BSP status
*/
int32_t BSP_SPI3_DeInit(void)
{
int32_t ret = BSP_ERROR_BUS_FAILURE;
if (SPI3InitCounter > 0)
{
if (--SPI3InitCounter == 0)
{
#if (USE_HAL_SPI_REGISTER_CALLBACKS == 0U)
SPI3_MspDeInit(&hspi3);
#endif
/* DeInit the SPI*/
if (HAL_SPI_DeInit(&hspi3) == HAL_OK)
{
ret = BSP_ERROR_NONE;
}
}
}
return ret;
}
/**
* @brief Write Data through SPI BUS.
* @param pData: Pointer to data buffer to send
* @param Length: Length of data in byte
* @retval BSP status
*/
int32_t BSP_SPI3_Send(uint8_t *pData, uint16_t Length)
{
int32_t ret = BSP_ERROR_NONE;
if(HAL_SPI_Transmit(&hspi3, pData, Length, BUS_SPI3_POLL_TIMEOUT) != HAL_OK)
{
ret = BSP_ERROR_UNKNOWN_FAILURE;
}
return ret;
}
/**
* @brief Receive Data from SPI BUS
* @param pData: Pointer to data buffer to receive
* @param Length: Length of data in byte
* @retval BSP status
*/
int32_t BSP_SPI3_Recv(uint8_t *pData, uint16_t Length)
{
int32_t ret = BSP_ERROR_NONE;
if(HAL_SPI_Receive(&hspi3, pData, Length, BUS_SPI3_POLL_TIMEOUT) != HAL_OK)
{
ret = BSP_ERROR_UNKNOWN_FAILURE;
}
return ret;
}
/**
* @brief Send and Receive data to/from SPI BUS (Full duplex)
* @param pData: Pointer to data buffer to send/receive
* @param Length: Length of data in byte
* @retval BSP status
*/
int32_t BSP_SPI3_SendRecv(uint8_t *pTxData, uint8_t *pRxData, uint16_t Length)
{
int32_t ret = BSP_ERROR_NONE;
if(HAL_SPI_TransmitReceive(&hspi3, pTxData, pRxData, Length, BUS_SPI3_POLL_TIMEOUT) != HAL_OK)
{
ret = BSP_ERROR_UNKNOWN_FAILURE;
}
return ret;
}
#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U)
/**
* @brief Register Default BSP SPI3 Bus Msp Callbacks
* @retval BSP status
*/
int32_t BSP_SPI3_RegisterDefaultMspCallbacks (void)
{
__HAL_SPI_RESET_HANDLE_STATE(&hspi3);
/* Register MspInit Callback */
if (HAL_SPI_RegisterCallback(&hspi3, HAL_SPI_MSPINIT_CB_ID, SPI3_MspInit) != HAL_OK)
{
return BSP_ERROR_PERIPH_FAILURE;
}
/* Register MspDeInit Callback */
if (HAL_SPI_RegisterCallback(&hspi3, HAL_SPI_MSPDEINIT_CB_ID, SPI3_MspDeInit) != HAL_OK)
{
return BSP_ERROR_PERIPH_FAILURE;
}
IsSPI3MspCbValid = 1;
return BSP_ERROR_NONE;
}
/**
* @brief BSP SPI3 Bus Msp Callback registering
* @param Callbacks pointer to SPI3 MspInit/MspDeInit callback functions
* @retval BSP status
*/
int32_t BSP_SPI3_RegisterMspCallbacks (BSP_SPI_Cb_t *Callbacks)
{
/* Prevent unused argument(s) compilation warning */
__HAL_SPI_RESET_HANDLE_STATE(&hspi3);
/* Register MspInit Callback */
if (HAL_SPI_RegisterCallback(&hspi3, HAL_SPI_MSPINIT_CB_ID, Callbacks->pMspInitCb) != HAL_OK)
{
return BSP_ERROR_PERIPH_FAILURE;
}
/* Register MspDeInit Callback */
if (HAL_SPI_RegisterCallback(&hspi3, HAL_SPI_MSPDEINIT_CB_ID, Callbacks->pMspDeInitCb) != HAL_OK)
{
return BSP_ERROR_PERIPH_FAILURE;
}
IsSPI3MspCbValid = 1;
return BSP_ERROR_NONE;
}
#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */
/**
* @brief Return system tick in ms
* @retval Current HAL time base time stamp
*/
int32_t BSP_GetTick(void) {
return HAL_GetTick();
}
/* SPI3 init function */
__weak HAL_StatusTypeDef MX_SPI3_Init(SPI_HandleTypeDef* hspi)
{
HAL_StatusTypeDef ret = HAL_OK;
hspi->Instance = SPI3;
hspi->Init.Mode = SPI_MODE_MASTER;
hspi->Init.Direction = SPI_DIRECTION_2LINES;
hspi->Init.DataSize = SPI_DATASIZE_8BIT;
hspi->Init.CLKPolarity = SPI_POLARITY_LOW;
hspi->Init.CLKPhase = SPI_PHASE_1EDGE;
hspi->Init.NSS = SPI_NSS_SOFT;
hspi->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
hspi->Init.FirstBit = SPI_FIRSTBIT_MSB;
hspi->Init.TIMode = SPI_TIMODE_DISABLE;
hspi->Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
hspi->Init.CRCPolynomial = 10;
if (HAL_SPI_Init(hspi) != HAL_OK)
{
ret = HAL_ERROR;
}
return ret;
}
static void SPI3_MspInit(SPI_HandleTypeDef* spiHandle)
{
GPIO_InitTypeDef GPIO_InitStruct;
/* USER CODE BEGIN SPI3_MspInit 0 */
/* USER CODE END SPI3_MspInit 0 */
/* Enable Peripheral clock */
__HAL_RCC_SPI3_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
/**SPI3 GPIO Configuration
PC10 ------> SPI3_SCK
PC11 ------> SPI3_MISO
PC12 ------> SPI3_MOSI
*/
GPIO_InitStruct.Pin = BUS_SPI3_SCK_GPIO_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = BUS_SPI3_SCK_GPIO_AF;
HAL_GPIO_Init(BUS_SPI3_SCK_GPIO_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = BUS_SPI3_MISO_GPIO_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = BUS_SPI3_MISO_GPIO_AF;
HAL_GPIO_Init(BUS_SPI3_MISO_GPIO_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = BUS_SPI3_MOSI_GPIO_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = BUS_SPI3_MOSI_GPIO_AF;
HAL_GPIO_Init(BUS_SPI3_MOSI_GPIO_PORT, &GPIO_InitStruct);
/* USER CODE BEGIN SPI3_MspInit 1 */
/* USER CODE END SPI3_MspInit 1 */
}
static void SPI3_MspDeInit(SPI_HandleTypeDef* spiHandle)
{
/* USER CODE BEGIN SPI3_MspDeInit 0 */
/* USER CODE END SPI3_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_SPI3_CLK_DISABLE();
/**SPI3 GPIO Configuration
PC10 ------> SPI3_SCK
PC11 ------> SPI3_MISO
PC12 ------> SPI3_MOSI
*/
HAL_GPIO_DeInit(BUS_SPI3_SCK_GPIO_PORT, BUS_SPI3_SCK_GPIO_PIN);
HAL_GPIO_DeInit(BUS_SPI3_MISO_GPIO_PORT, BUS_SPI3_MISO_GPIO_PIN);
HAL_GPIO_DeInit(BUS_SPI3_MOSI_GPIO_PORT, BUS_SPI3_MOSI_GPIO_PIN);
/* USER CODE BEGIN SPI3_MspDeInit 1 */
/* USER CODE END SPI3_MspDeInit 1 */
}
#if (USE_CUBEMX_BSP_V2 == 1)
/**
* @brief Convert the SPI baudrate into prescaler.
* @param clock_src_hz : SPI source clock in HZ.
* @param baudrate_mbps : SPI baud rate in mbps.
* @retval Prescaler dividor
*/
static uint32_t SPI_GetPrescaler( uint32_t clock_src_hz, uint32_t baudrate_mbps )
{
uint32_t divisor = 0;
uint32_t spi_clk = clock_src_hz;
uint32_t presc = 0;
static const uint32_t baudrate[]=
{
SPI_BAUDRATEPRESCALER_2,
SPI_BAUDRATEPRESCALER_4,
SPI_BAUDRATEPRESCALER_8,
SPI_BAUDRATEPRESCALER_16,
SPI_BAUDRATEPRESCALER_32,
SPI_BAUDRATEPRESCALER_64,
SPI_BAUDRATEPRESCALER_128,
SPI_BAUDRATEPRESCALER_256,
};
while( spi_clk > baudrate_mbps)
{
presc = baudrate[divisor];
if (++divisor > 7)
break;
spi_clk= ( spi_clk >> 1);
}
return presc;
}
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,771 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32l4xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
extern DMA_HandleTypeDef hdma_adc1;
extern DMA_HandleTypeDef hdma_adc2;
extern DMA_HandleTypeDef hdma_usart2_tx;
/* 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 */
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
PWR_PVDTypeDef sConfigPVD = {0};
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
/* System interrupt init*/
/* PendSV_IRQn interrupt configuration */
HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0);
/** PVD Configuration
*/
sConfigPVD.PVDLevel = PWR_PVDLEVEL_4;
sConfigPVD.Mode = PWR_PVD_MODE_EVENT_RISING;
HAL_PWR_ConfigPVD(&sConfigPVD);
/** Enable the PVD Output
*/
HAL_PWR_EnablePVD();
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
static uint32_t HAL_RCC_ADC_CLK_ENABLED=0;
/**
* @brief ADC MSP Initialization
* This function configures the hardware resources used in this example
* @param hadc: ADC handle pointer
* @retval None
*/
void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hadc->Instance==ADC1)
{
/* USER CODE BEGIN ADC1_MspInit 0 */
/* USER CODE END ADC1_MspInit 0 */
/* Peripheral clock enable */
HAL_RCC_ADC_CLK_ENABLED++;
if(HAL_RCC_ADC_CLK_ENABLED==1){
__HAL_RCC_ADC_CLK_ENABLE();
}
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**ADC1 GPIO Configuration
PC2 ------> ADC1_IN3
PA6 ------> ADC1_IN11
*/
GPIO_InitStruct.Pin = AIN_I_Drives_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(AIN_I_Drives_GPIO_Port, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_6;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* ADC1 DMA Init */
/* ADC1 Init */
hdma_adc1.Instance = DMA1_Channel1;
hdma_adc1.Init.Request = DMA_REQUEST_0;
hdma_adc1.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc1.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc1.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc1.Init.Mode = DMA_CIRCULAR;
hdma_adc1.Init.Priority = DMA_PRIORITY_LOW;
if (HAL_DMA_Init(&hdma_adc1) != HAL_OK)
{
Error_Handler();
}
__HAL_LINKDMA(hadc,DMA_Handle,hdma_adc1);
/* USER CODE BEGIN ADC1_MspInit 1 */
/* USER CODE END ADC1_MspInit 1 */
}
else if(hadc->Instance==ADC2)
{
/* USER CODE BEGIN ADC2_MspInit 0 */
/* USER CODE END ADC2_MspInit 0 */
/* Peripheral clock enable */
HAL_RCC_ADC_CLK_ENABLED++;
if(HAL_RCC_ADC_CLK_ENABLED==1){
__HAL_RCC_ADC_CLK_ENABLE();
}
__HAL_RCC_GPIOC_CLK_ENABLE();
/**ADC2 GPIO Configuration
PC2 ------> ADC2_IN3
PC3 ------> ADC2_IN4
*/
GPIO_InitStruct.Pin = AIN_I_Drives_Pin|AIN_I_Valves_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/* ADC2 DMA Init */
/* ADC2 Init */
hdma_adc2.Instance = DMA1_Channel2;
hdma_adc2.Init.Request = DMA_REQUEST_0;
hdma_adc2.Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_adc2.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_adc2.Init.MemInc = DMA_MINC_ENABLE;
hdma_adc2.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD;
hdma_adc2.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD;
hdma_adc2.Init.Mode = DMA_CIRCULAR;
hdma_adc2.Init.Priority = DMA_PRIORITY_LOW;
if (HAL_DMA_Init(&hdma_adc2) != HAL_OK)
{
Error_Handler();
}
__HAL_LINKDMA(hadc,DMA_Handle,hdma_adc2);
/* USER CODE BEGIN ADC2_MspInit 1 */
/* USER CODE END ADC2_MspInit 1 */
}
}
/**
* @brief ADC MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hadc: ADC handle pointer
* @retval None
*/
void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc)
{
if(hadc->Instance==ADC1)
{
/* USER CODE BEGIN ADC1_MspDeInit 0 */
/* USER CODE END ADC1_MspDeInit 0 */
/* Peripheral clock disable */
HAL_RCC_ADC_CLK_ENABLED--;
if(HAL_RCC_ADC_CLK_ENABLED==0){
__HAL_RCC_ADC_CLK_DISABLE();
}
/**ADC1 GPIO Configuration
PC2 ------> ADC1_IN3
PA6 ------> ADC1_IN11
*/
HAL_GPIO_DeInit(AIN_I_Drives_GPIO_Port, AIN_I_Drives_Pin);
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_6);
/* ADC1 DMA DeInit */
HAL_DMA_DeInit(hadc->DMA_Handle);
/* USER CODE BEGIN ADC1_MspDeInit 1 */
/* USER CODE END ADC1_MspDeInit 1 */
}
else if(hadc->Instance==ADC2)
{
/* USER CODE BEGIN ADC2_MspDeInit 0 */
/* USER CODE END ADC2_MspDeInit 0 */
/* Peripheral clock disable */
HAL_RCC_ADC_CLK_ENABLED--;
if(HAL_RCC_ADC_CLK_ENABLED==0){
__HAL_RCC_ADC_CLK_DISABLE();
}
/**ADC2 GPIO Configuration
PC2 ------> ADC2_IN3
PC3 ------> ADC2_IN4
*/
HAL_GPIO_DeInit(GPIOC, AIN_I_Drives_Pin|AIN_I_Valves_Pin);
/* ADC2 DMA DeInit */
HAL_DMA_DeInit(hadc->DMA_Handle);
/* USER CODE BEGIN ADC2_MspDeInit 1 */
/* USER CODE END ADC2_MspDeInit 1 */
}
}
/**
* @brief CAN MSP Initialization
* This function configures the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hcan->Instance==CAN1)
{
/* USER CODE BEGIN CAN1_MspInit 0 */
/* USER CODE END CAN1_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_CAN1_CLK_ENABLE();
__HAL_RCC_GPIOA_CLK_ENABLE();
/**CAN1 GPIO Configuration
PA11 ------> CAN1_RX
PA12 ------> CAN1_TX
*/
GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF9_CAN1;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* CAN1 interrupt Init */
HAL_NVIC_SetPriority(CAN1_RX0_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn);
/* USER CODE BEGIN CAN1_MspInit 1 */
/* USER CODE END CAN1_MspInit 1 */
}
}
/**
* @brief CAN MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hcan: CAN handle pointer
* @retval None
*/
void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan)
{
if(hcan->Instance==CAN1)
{
/* USER CODE BEGIN CAN1_MspDeInit 0 */
/* USER CODE END CAN1_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_CAN1_CLK_DISABLE();
/**CAN1 GPIO Configuration
PA11 ------> CAN1_RX
PA12 ------> CAN1_TX
*/
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
/* CAN1 interrupt DeInit */
HAL_NVIC_DisableIRQ(CAN1_RX0_IRQn);
/* USER CODE BEGIN CAN1_MspDeInit 1 */
/* USER CODE END CAN1_MspDeInit 1 */
}
}
/**
* @brief COMP MSP Initialization
* This function configures the hardware resources used in this example
* @param hcomp: COMP handle pointer
* @retval None
*/
void HAL_COMP_MspInit(COMP_HandleTypeDef* hcomp)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(hcomp->Instance==COMP2)
{
/* USER CODE BEGIN COMP2_MspInit 0 */
/* USER CODE END COMP2_MspInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE();
/**COMP2 GPIO Configuration
PB11 ------> COMP2_OUT
PB6 ------> COMP2_INP
PB7 ------> COMP2_INM
*/
GPIO_InitStruct.Pin = GPIO_PIN_11;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF12_COMP2;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* USER CODE BEGIN COMP2_MspInit 1 */
/* USER CODE END COMP2_MspInit 1 */
}
}
/**
* @brief COMP MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hcomp: COMP handle pointer
* @retval None
*/
void HAL_COMP_MspDeInit(COMP_HandleTypeDef* hcomp)
{
if(hcomp->Instance==COMP2)
{
/* USER CODE BEGIN COMP2_MspDeInit 0 */
/* USER CODE END COMP2_MspDeInit 0 */
/**COMP2 GPIO Configuration
PB11 ------> COMP2_OUT
PB6 ------> COMP2_INP
PB7 ------> COMP2_INM
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_11|GPIO_PIN_6|GPIO_PIN_7);
/* USER CODE BEGIN COMP2_MspDeInit 1 */
/* USER CODE END COMP2_MspDeInit 1 */
}
}
/**
* @brief RTC MSP Initialization
* This function configures the hardware resources used in this example
* @param hrtc: RTC handle pointer
* @retval None
*/
void HAL_RTC_MspInit(RTC_HandleTypeDef* hrtc)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
if(hrtc->Instance==RTC)
{
/* USER CODE BEGIN RTC_MspInit 0 */
/* USER CODE END RTC_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_RTC;
PeriphClkInit.RTCClockSelection = RCC_RTCCLKSOURCE_LSE;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
/* Peripheral clock enable */
__HAL_RCC_RTC_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
/**RTC GPIO Configuration
PB15 ------> RTC_REFIN
*/
GPIO_InitStruct.Pin = GPIO_PIN_15;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF0_RTC_50Hz;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* RTC interrupt Init */
HAL_NVIC_SetPriority(RTC_Alarm_IRQn, 5, 0);
HAL_NVIC_EnableIRQ(RTC_Alarm_IRQn);
/* USER CODE BEGIN RTC_MspInit 1 */
/* USER CODE END RTC_MspInit 1 */
}
}
/**
* @brief RTC MSP De-Initialization
* This function freeze the hardware resources used in this example
* @param hrtc: RTC handle pointer
* @retval None
*/
void HAL_RTC_MspDeInit(RTC_HandleTypeDef* hrtc)
{
if(hrtc->Instance==RTC)
{
/* USER CODE BEGIN RTC_MspDeInit 0 */
/* USER CODE END RTC_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_RTC_DISABLE();
/**RTC GPIO Configuration
PB15 ------> RTC_REFIN
*/
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_15);
/* RTC interrupt DeInit */
HAL_NVIC_DisableIRQ(RTC_Alarm_IRQn);
/* USER CODE BEGIN RTC_MspDeInit 1 */
/* USER CODE END RTC_MspDeInit 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==SPI3)
{
/* USER CODE BEGIN SPI3_MspInit 0 */
/* USER CODE END SPI3_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_SPI3_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
/**SPI3 GPIO Configuration
PC10 ------> SPI3_SCK
PC11 ------> SPI3_MISO
PC12 ------> SPI3_MOSI
*/
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = GPIO_AF6_SPI3;
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
/* USER CODE BEGIN SPI3_MspInit 1 */
/* USER CODE END SPI3_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==SPI3)
{
/* USER CODE BEGIN SPI3_MspDeInit 0 */
/* USER CODE END SPI3_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_SPI3_CLK_DISABLE();
/**SPI3 GPIO Configuration
PC10 ------> SPI3_SCK
PC11 ------> SPI3_MISO
PC12 ------> SPI3_MOSI
*/
HAL_GPIO_DeInit(GPIOC, GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12);
/* USER CODE BEGIN SPI3_MspDeInit 1 */
/* USER CODE END SPI3_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)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
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 */
}
else if(htim_base->Instance==TIM8)
{
/* USER CODE BEGIN TIM8_MspInit 0 */
/* USER CODE END TIM8_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM8_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
/**TIM8 GPIO Configuration
PC6 ------> TIM8_CH1
*/
GPIO_InitStruct.Pin = ZeroCrossing_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF3_TIM8;
HAL_GPIO_Init(ZeroCrossing_GPIO_Port, &GPIO_InitStruct);
/* USER CODE BEGIN TIM8_MspInit 1 */
/* USER CODE END TIM8_MspInit 1 */
}
}
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
{
GPIO_InitTypeDef GPIO_InitStruct = {0};
if(htim->Instance==TIM8)
{
/* USER CODE BEGIN TIM8_MspPostInit 0 */
/* USER CODE END TIM8_MspPostInit 0 */
__HAL_RCC_GPIOC_CLK_ENABLE();
/**TIM8 GPIO Configuration
PC7 ------> TIM8_CH2
*/
GPIO_InitStruct.Pin = AC_MOTOR_DRIVE_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF3_TIM8;
HAL_GPIO_Init(AC_MOTOR_DRIVE_GPIO_Port, &GPIO_InitStruct);
/* USER CODE BEGIN TIM8_MspPostInit 1 */
/* USER CODE END TIM8_MspPostInit 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 */
}
else if(htim_base->Instance==TIM8)
{
/* USER CODE BEGIN TIM8_MspDeInit 0 */
/* USER CODE END TIM8_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM8_CLK_DISABLE();
/**TIM8 GPIO Configuration
PC6 ------> TIM8_CH1
PC7 ------> TIM8_CH2
*/
HAL_GPIO_DeInit(GPIOC, ZeroCrossing_Pin|AC_MOTOR_DRIVE_Pin);
/* USER CODE BEGIN TIM8_MspDeInit 1 */
/* USER CODE END TIM8_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};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
if(huart->Instance==USART2)
{
/* USER CODE BEGIN USART2_MspInit 0 */
/* USER CODE END USART2_MspInit 0 */
/** Initializes the peripherals clock
*/
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2;
PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
{
Error_Handler();
}
/* 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 = GPIO_PIN_2|GPIO_PIN_3;
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);
/* USART2 DMA Init */
/* USART2_TX Init */
hdma_usart2_tx.Instance = DMA1_Channel7;
hdma_usart2_tx.Init.Request = DMA_REQUEST_2;
hdma_usart2_tx.Init.Direction = DMA_MEMORY_TO_PERIPH;
hdma_usart2_tx.Init.PeriphInc = DMA_PINC_DISABLE;
hdma_usart2_tx.Init.MemInc = DMA_MINC_ENABLE;
hdma_usart2_tx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_usart2_tx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_usart2_tx.Init.Mode = DMA_NORMAL;
hdma_usart2_tx.Init.Priority = DMA_PRIORITY_LOW;
if (HAL_DMA_Init(&hdma_usart2_tx) != HAL_OK)
{
Error_Handler();
}
__HAL_LINKDMA(huart,hdmatx,hdma_usart2_tx);
/* USART2 interrupt Init */
HAL_NVIC_SetPriority(USART2_IRQn, 7, 0);
HAL_NVIC_EnableIRQ(USART2_IRQn);
/* 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, GPIO_PIN_2|GPIO_PIN_3);
/* USART2 DMA DeInit */
HAL_DMA_DeInit(huart->hdmatx);
/* USART2 interrupt DeInit */
HAL_NVIC_DisableIRQ(USART2_IRQn);
/* USER CODE BEGIN USART2_MspDeInit 1 */
/* USER CODE END USART2_MspDeInit 1 */
}
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View File

@@ -0,0 +1,137 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32l4xx_hal_timebase_TIM.c
* @brief HAL time base based on the hardware TIM.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "stm32l4xx_hal.h"
#include "stm32l4xx_hal_tim.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
TIM_HandleTypeDef htim7;
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/**
* @brief This function configures the TIM7 as a time base source.
* The time source is configured to have 1ms time base with a dedicated
* Tick interrupt priority.
* @note This function is called automatically at the beginning of program after
* reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig().
* @param TickPriority: Tick interrupt priority.
* @retval HAL status
*/
HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
{
RCC_ClkInitTypeDef clkconfig;
uint32_t uwTimclock, uwAPB1Prescaler;
uint32_t uwPrescalerValue;
uint32_t pFLatency;
HAL_StatusTypeDef status = HAL_OK;
/* Enable TIM7 clock */
__HAL_RCC_TIM7_CLK_ENABLE();
/* Get clock configuration */
HAL_RCC_GetClockConfig(&clkconfig, &pFLatency);
/* Get APB1 prescaler */
uwAPB1Prescaler = clkconfig.APB1CLKDivider;
/* Compute TIM7 clock */
if (uwAPB1Prescaler == RCC_HCLK_DIV1)
{
uwTimclock = HAL_RCC_GetPCLK1Freq();
}
else
{
uwTimclock = 2UL * HAL_RCC_GetPCLK1Freq();
}
/* Compute the prescaler value to have TIM7 counter clock equal to 1MHz */
uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000U) - 1U);
/* Initialize TIM7 */
htim7.Instance = TIM7;
/* Initialize TIMx peripheral as follow:
* Period = [(TIM7CLK/1000) - 1]. to have a (1/1000) s time base.
* Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock.
* ClockDivision = 0
* Counter direction = Up
*/
htim7.Init.Period = (1000000U / 1000U) - 1U;
htim7.Init.Prescaler = uwPrescalerValue;
htim7.Init.ClockDivision = 0;
htim7.Init.CounterMode = TIM_COUNTERMODE_UP;
htim7.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
status = HAL_TIM_Base_Init(&htim7);
if (status == HAL_OK)
{
/* Start the TIM time Base generation in interrupt mode */
status = HAL_TIM_Base_Start_IT(&htim7);
if (status == HAL_OK)
{
/* Enable the TIM7 global Interrupt */
HAL_NVIC_EnableIRQ(TIM7_IRQn);
/* Configure the SysTick IRQ priority */
if (TickPriority < (1UL << __NVIC_PRIO_BITS))
{
/* Configure the TIM IRQ priority */
HAL_NVIC_SetPriority(TIM7_IRQn, TickPriority, 0U);
uwTickPrio = TickPriority;
}
else
{
status = HAL_ERROR;
}
}
}
/* Return function status */
return status;
}
/**
* @brief Suspend Tick increment.
* @note Disable the tick increment by disabling TIM7 update interrupt.
* @param None
* @retval None
*/
void HAL_SuspendTick(void)
{
/* Disable TIM7 update Interrupt */
__HAL_TIM_DISABLE_IT(&htim7, TIM_IT_UPDATE);
}
/**
* @brief Resume Tick increment.
* @note Enable the tick increment by Enabling TIM7 update interrupt.
* @param None
* @retval None
*/
void HAL_ResumeTick(void)
{
/* Enable TIM7 Update interrupt */
__HAL_TIM_ENABLE_IT(&htim7, TIM_IT_UPDATE);
}

View File

@@ -0,0 +1,356 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32l4xx_it.c
* @brief Interrupt Service Routines.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "stm32l4xx_it.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "sx1276mb1mas.h"
/* 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 --------------------------------------------------------*/
extern DMA_HandleTypeDef hdma_adc1;
extern DMA_HandleTypeDef hdma_adc2;
extern CAN_HandleTypeDef hcan1;
extern RTC_HandleTypeDef hrtc;
extern DMA_HandleTypeDef hdma_usart2_tx;
extern UART_HandleTypeDef huart2;
extern TIM_HandleTypeDef htim7;
/* 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 */
HAL_GPIO_WritePin(ERR_LED_GPIO_Port,ERR_LED_Pin,GPIO_PIN_SET);
/* 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 Prefetch 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 */
HAL_GPIO_WritePin(ERR_LED_GPIO_Port,ERR_LED_Pin,GPIO_PIN_SET);
/* 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 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 */
}
/******************************************************************************/
/* STM32L4xx 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_stm32l4xx.s). */
/******************************************************************************/
/**
* @brief This function handles EXTI line0 interrupt.
*/
void EXTI0_IRQHandler(void)
{
/* USER CODE BEGIN EXTI0_IRQn 0 */
/* USER CODE END EXTI0_IRQn 0 */
HAL_GPIO_EXTI_IRQHandler(VCC_ON_Pin);
/* USER CODE BEGIN EXTI0_IRQn 1 */
/* USER CODE END EXTI0_IRQn 1 */
}
/**
* @brief This function handles EXTI line2 interrupt.
*/
void EXTI2_IRQHandler(void)
{
/* USER CODE BEGIN EXTI2_IRQn 0 */
HAL_GPIO_EXTI_IRQHandler(HCI_TL_SPI_EXTI_PIN);
/* USER CODE END EXTI2_IRQn 0 */
/* USER CODE BEGIN EXTI2_IRQn 1 */
/* USER CODE END EXTI2_IRQn 1 */
}
/**
* @brief This function handles EXTI line3 interrupt.
*/
void EXTI3_IRQHandler(void)
{
/* USER CODE BEGIN EXTI3_IRQn 0 */
#if (defined(SX1276MB1MAS) | defined(SX1276MB1LAS) | defined(SX1272MB2DAS))
HAL_EXTI_IRQHandler(&H_EXTI_3);
#endif
/* USER CODE END EXTI3_IRQn 0 */
/* USER CODE BEGIN EXTI3_IRQn 1 */
/* USER CODE END EXTI3_IRQn 1 */
}
/**
* @brief This function handles EXTI line4 interrupt.
*/
void EXTI4_IRQHandler(void)
{
/* USER CODE BEGIN EXTI4_IRQn 0 */
HAL_EXTI_IRQHandler(&H_EXTI_4);
/* USER CODE END EXTI4_IRQn 0 */
/* USER CODE BEGIN EXTI4_IRQn 1 */
/* USER CODE END EXTI4_IRQn 1 */
}
/**
* @brief This function handles DMA1 channel1 global interrupt.
*/
void DMA1_Channel1_IRQHandler(void)
{
/* USER CODE BEGIN DMA1_Channel1_IRQn 0 */
/* USER CODE END DMA1_Channel1_IRQn 0 */
HAL_DMA_IRQHandler(&hdma_adc1);
/* USER CODE BEGIN DMA1_Channel1_IRQn 1 */
/* USER CODE END DMA1_Channel1_IRQn 1 */
}
/**
* @brief This function handles DMA1 channel2 global interrupt.
*/
void DMA1_Channel2_IRQHandler(void)
{
/* USER CODE BEGIN DMA1_Channel2_IRQn 0 */
/* USER CODE END DMA1_Channel2_IRQn 0 */
HAL_DMA_IRQHandler(&hdma_adc2);
/* USER CODE BEGIN DMA1_Channel2_IRQn 1 */
/* USER CODE END DMA1_Channel2_IRQn 1 */
}
/**
* @brief This function handles DMA1 channel7 global interrupt.
*/
void DMA1_Channel7_IRQHandler(void)
{
/* USER CODE BEGIN DMA1_Channel7_IRQn 0 */
/* USER CODE END DMA1_Channel7_IRQn 0 */
HAL_DMA_IRQHandler(&hdma_usart2_tx);
/* USER CODE BEGIN DMA1_Channel7_IRQn 1 */
/* USER CODE END DMA1_Channel7_IRQn 1 */
}
/**
* @brief This function handles CAN1 RX0 interrupt.
*/
void CAN1_RX0_IRQHandler(void)
{
/* USER CODE BEGIN CAN1_RX0_IRQn 0 */
/* USER CODE END CAN1_RX0_IRQn 0 */
HAL_CAN_IRQHandler(&hcan1);
/* USER CODE BEGIN CAN1_RX0_IRQn 1 */
/* USER CODE END CAN1_RX0_IRQn 1 */
}
/**
* @brief This function handles EXTI line[9:5] interrupts.
*/
void EXTI9_5_IRQHandler(void)
{
/* USER CODE BEGIN EXTI9_5_IRQn 0 */
#if (defined(SX1276MB1MAS) | defined(SX1276MB1LAS) | defined(SX1272MB2DAS))
HAL_EXTI_IRQHandler(&H_EXTI_5);
#endif
/* USER CODE END EXTI9_5_IRQn 0 */
/* USER CODE BEGIN EXTI9_5_IRQn 1 */
/* USER CODE END EXTI9_5_IRQn 1 */
}
/**
* @brief This function handles USART2 global interrupt.
*/
void USART2_IRQHandler(void)
{
/* USER CODE BEGIN USART2_IRQn 0 */
/* USER CODE END USART2_IRQn 0 */
HAL_UART_IRQHandler(&huart2);
/* USER CODE BEGIN USART2_IRQn 1 */
/* USER CODE END USART2_IRQn 1 */
}
/**
* @brief This function handles EXTI line[15:10] interrupts.
*/
void EXTI15_10_IRQHandler(void)
{
/* USER CODE BEGIN EXTI15_10_IRQn 0 */
#if (defined(SX1276MB1MAS) | defined(SX1276MB1LAS) | defined(SX1272MB2DAS))
HAL_EXTI_IRQHandler(&H_EXTI_10);
#endif
HAL_GPIO_EXTI_IRQHandler(USR_BTN_Pin);
/* USER CODE END EXTI15_10_IRQn 0 */
/* USER CODE BEGIN EXTI15_10_IRQn 1 */
/* USER CODE END EXTI15_10_IRQn 1 */
}
/**
* @brief This function handles RTC alarm interrupt through EXTI line 18.
*/
void RTC_Alarm_IRQHandler(void)
{
/* USER CODE BEGIN RTC_Alarm_IRQn 0 */
/* USER CODE END RTC_Alarm_IRQn 0 */
HAL_RTC_AlarmIRQHandler(&hrtc);
/* USER CODE BEGIN RTC_Alarm_IRQn 1 */
/* USER CODE END RTC_Alarm_IRQn 1 */
}
/**
* @brief This function handles TIM7 global interrupt.
*/
void TIM7_IRQHandler(void)
{
/* USER CODE BEGIN TIM7_IRQn 0 */
/* USER CODE END TIM7_IRQn 0 */
HAL_TIM_IRQHandler(&htim7);
/* USER CODE BEGIN TIM7_IRQn 1 */
/* USER CODE END TIM7_IRQn 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */

View File

@@ -0,0 +1,253 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file sys_app.c
* @author MCD Application Team
* @brief Initializes HW and SW system entities (not related to the radio)
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include <stdio.h>
#include "platform.h"
#include "sys_app.h"
#include "radio_board_if.h"
#include "stm32_seq.h"
#include "stm32_systime.h"
//#include "stm32_lpm.h"
#include "utilities_def.h"
//#include "sys_debug.h"
#include "rtc_if.h"
#include "signals.h"
//#include "sys_sensors.h"
/* USER CODE BEGIN Includes */
#include "stm32_adv_trace.h"
#include <string.h>
/* USER CODE END Includes */
/* External variables ---------------------------------------------------------*/
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
#define MAX_TS_SIZE (int) 16
/**
* Defines the maximum battery level
*/
#define LORAWAN_MAX_BAT 100
/* 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 */
/* Exported functions ---------------------------------------------------------*/
void SystemApp_Init(void)
{
/* USER CODE BEGIN SystemApp_Init_1 */
/* USER CODE END SystemApp_Init_1 */
/* Ensure that MSI is wake-up system clock */
__HAL_RCC_WAKEUPSTOP_CLK_CONFIG(RCC_STOP_WAKEUPCLOCK_MSI);
/*Initialize timer and RTC*/
//UTIL_TIMER_Init();
//Gpio_PreInit();
/* Debug config : disable serial wires and DbgMcu pins settings */
//DBG_Disable();
/* Initializes the SW probes pins and the monitor RF pins via Alternate Function */
//DBG_ProbesInit();
/*Initialize the terminal */
//UTIL_ADV_TRACE_Init();
//UTIL_ADV_TRACE_RegisterTimeStampFunction(TimestampNow);
/*Set verbose LEVEL*/
//UTIL_ADV_TRACE_SetVerboseLevel(VERBOSE_LEVEL);
/*Initialize the temperature and Battery measurement services */
//SYS_InitMeasurement();
//Sx_Board_Bus_Init();
//Sx_Board_IoInit();
/*Initialize the Sensors */
//EnvSensors_Init();
/*Init low power manager*/
//UTIL_LPM_Init();
/* Disable Stand-by mode */
//UTIL_LPM_SetOffMode((1 << CFG_LPM_APPLI_Id), UTIL_LPM_DISABLE);
#if defined (LOW_POWER_DISABLE) && (LOW_POWER_DISABLE == 1)
/* Disable Stop Mode */
//UTIL_LPM_SetStopMode((1 << CFG_LPM_APPLI_Id), UTIL_LPM_DISABLE);
#elif !defined (LOW_POWER_DISABLE)
#error LOW_POWER_DISABLE not defined
#endif /* LOW_POWER_DISABLE */
/* USER CODE BEGIN SystemApp_Init_2 */
/* USER CODE END SystemApp_Init_2 */
}
/**
* @brief redefines __weak function in stm32_seq.c such to enter low power
*/
void UTIL_SEQ_Idle(void)
{
/* USER CODE BEGIN UTIL_SEQ_Idle_1 */
/* USER CODE END UTIL_SEQ_Idle_1 */
//UTIL_LPM_EnterLowPower();
/* USER CODE BEGIN UTIL_SEQ_Idle_2 */
/* USER CODE END UTIL_SEQ_Idle_2 */
}
uint8_t GetBatteryLevel(void)
{
uint8_t batteryLevel = 0;
uint16_t batteryLevelmV;
/* USER CODE BEGIN GetBatteryLevel_0 */
/* USER CODE END GetBatteryLevel_0 */
batteryLevelmV = meas_battery_voltage;
/* Convert battery level from mV to linear scale: 1 (very low) to 254 (fully charged) */
if (batteryLevelmV > VDD_BAT)
{
batteryLevel = LORAWAN_MAX_BAT;
}
else if (batteryLevelmV < VDD_MIN)
{
batteryLevel = 0;
}
else
{
batteryLevel = (((uint32_t)(batteryLevelmV - VDD_MIN) * LORAWAN_MAX_BAT) / (VDD_BAT - VDD_MIN));
}
APP_LOG(TS_ON, VLEVEL_M, "Vbat= %d%%\r\n", batteryLevel);
/* USER CODE BEGIN GetBatteryLevel_2 */
/* USER CODE END GetBatteryLevel_2 */
return batteryLevel; /* 1 (very low) to 254 (fully charged) */
}
uint16_t GetTemperatureLevel(void)
{
uint16_t temperatureLevel = 0;
temperatureLevel = (uint16_t)(128 / 256);
/* USER CODE BEGIN GetTemperatureLevel */
/* USER CODE END GetTemperatureLevel */
return temperatureLevel;
}
void GetUniqueId(uint8_t *id)
{
/* USER CODE BEGIN GetUniqueId_1 */
/* USER CODE END GetUniqueId_1 */
uint32_t ID_1_3_val = HAL_GetUIDw0() + HAL_GetUIDw2();
uint32_t ID_2_val = HAL_GetUIDw1();
id[7] = (ID_1_3_val) >> 24;
id[6] = (ID_1_3_val) >> 16;
id[5] = (ID_1_3_val) >> 8;
id[4] = (ID_1_3_val);
id[3] = (ID_2_val) >> 24;
id[2] = (ID_2_val) >> 16;
id[1] = (ID_2_val) >> 8;
id[0] = (ID_2_val);
/* USER CODE BEGIN GetUniqueId_2 */
/* USER CODE END GetUniqueId_2 */
}
uint32_t GetDevAddr(void)
{
return ((HAL_GetUIDw0()) ^ (HAL_GetUIDw1()) ^ (HAL_GetUIDw2()));
}
/* USER CODE BEGIN EF */
/* USER CODE END EF */
/* Private functions ---------------------------------------------------------*/
/* Disable StopMode when traces need to be printed */
void UTIL_ADV_TRACE_PreSendHook(void)
{
/* USER CODE BEGIN UTIL_ADV_TRACE_PreSendHook_1 */
/* USER CODE END UTIL_ADV_TRACE_PreSendHook_1 */
//UTIL_LPM_SetStopMode((1 << CFG_LPM_UART_TX_Id), UTIL_LPM_DISABLE);
/* USER CODE BEGIN UTIL_ADV_TRACE_PreSendHook_2 */
/* USER CODE END UTIL_ADV_TRACE_PreSendHook_2 */
}
/* Re-enable StopMode when traces have been printed */
void UTIL_ADV_TRACE_PostSendHook(void)
{
/* USER CODE BEGIN UTIL_LPM_SetStopMode_1 */
/* USER CODE END UTIL_LPM_SetStopMode_1 */
//UTIL_LPM_SetStopMode((1 << CFG_LPM_UART_TX_Id), UTIL_LPM_ENABLE);
/* USER CODE BEGIN UTIL_LPM_SetStopMode_2 */
/* USER CODE END UTIL_LPM_SetStopMode_2 */
}
/* USER CODE BEGIN PrFD */
/* USER CODE END PrFD */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,159 @@
/**
******************************************************************************
* @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
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* 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 */
//#undef errno
extern int errno;
extern int __io_putchar(int ch) __attribute__((weak));
extern int __io_getchar(void) __attribute__((weak));
register char * stack_ptr asm("sp");
char *__env[1] = { 0 };
char **environ = __env;
/* Functions */
void initialise_monitor_handles()
{
}
int _getpid(void)
{
return 1;
}
int _kill(int pid, int 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)
{
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
*ptr++ = __io_getchar();
}
return len;
}
__attribute__((weak)) int _write(int file, char *ptr, int len)
{
int DataIdx;
for (DataIdx = 0; DataIdx < len; DataIdx++)
{
__io_putchar(*ptr++);
}
return len;
}
int _close(int file)
{
return -1;
}
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
int _isatty(int file)
{
return 1;
}
int _lseek(int file, int ptr, int dir)
{
return 0;
}
int _open(char *path, int flags, ...)
{
/* Pretend like we always fail */
return -1;
}
int _wait(int *status)
{
errno = ECHILD;
return -1;
}
int _unlink(char *name)
{
errno = ENOENT;
return -1;
}
int _times(struct tms *buf)
{
return -1;
}
int _stat(char *file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
int _link(char *old, char *new)
{
errno = EMLINK;
return -1;
}
int _fork(void)
{
errno = EAGAIN;
return -1;
}
int _execve(char *name, char **argv, char **env)
{
errno = ENOMEM;
return -1;
}

View File

@@ -0,0 +1,80 @@
/**
******************************************************************************
* @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
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* 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;
}

View File

@@ -0,0 +1,337 @@
/**
******************************************************************************
* @file system_stm32l4xx.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_stm32l4xx.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.
*
* After each device reset the MSI (4 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32l4xx.s" file, to
* configure the system clock before to branch to main program.
*
* This file configures the system clock as follows:
*=============================================================================
*-----------------------------------------------------------------------------
* System Clock source | MSI
*-----------------------------------------------------------------------------
* SYSCLK(Hz) | 4000000
*-----------------------------------------------------------------------------
* HCLK(Hz) | 4000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB1 Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 1
*-----------------------------------------------------------------------------
* PLL_M | 1
*-----------------------------------------------------------------------------
* PLL_N | 8
*-----------------------------------------------------------------------------
* PLL_P | 7
*-----------------------------------------------------------------------------
* PLL_Q | 2
*-----------------------------------------------------------------------------
* PLL_R | 2
*-----------------------------------------------------------------------------
* PLLSAI1_P | NA
*-----------------------------------------------------------------------------
* PLLSAI1_Q | NA
*-----------------------------------------------------------------------------
* PLLSAI1_R | NA
*-----------------------------------------------------------------------------
* PLLSAI2_P | NA
*-----------------------------------------------------------------------------
* PLLSAI2_Q | NA
*-----------------------------------------------------------------------------
* PLLSAI2_R | NA
*-----------------------------------------------------------------------------
* Require 48MHz for USB OTG FS, | Disabled
* SDIO and RNG clock |
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Apache License, Version 2.0,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/Apache-2.0
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32l4xx_system
* @{
*/
/** @addtogroup STM32L4xx_System_Private_Includes
* @{
*/
#include "stm32l4xx.h"
#if !defined (HSE_VALUE)
#define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (MSI_VALUE)
#define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* MSI_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Defines
* @{
*/
/************************* Miscellaneous Configuration ************************/
/*!< Uncomment the following line if you need to relocate your vector Table in
Internal SRAM. */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Variables
* @{
*/
/* The SystemCoreClock 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 = 4000000U;
const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U};
const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U};
const uint32_t MSIRangeTable[12] = {100000U, 200000U, 400000U, 800000U, 1000000U, 2000000U, \
4000000U, 8000000U, 16000000U, 24000000U, 32000000U, 48000000U};
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system.
* @param None
* @retval None
*/
void SystemInit(void)
{
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
#endif
/* Reset the RCC clock configuration to the default reset state ------------*/
/* Set MSION bit */
RCC->CR |= RCC_CR_MSION;
/* Reset CFGR register */
RCC->CFGR = 0x00000000U;
/* Reset HSEON, CSSON , HSION, and PLLON bits */
RCC->CR &= 0xEAF6FFFFU;
/* Reset PLLCFGR register */
RCC->PLLCFGR = 0x00001000U;
/* Reset HSEBYP bit */
RCC->CR &= 0xFFFBFFFFU;
/* Disable all interrupts */
RCC->CIER = 0x00000000U;
/* Configure the Vector Table location add offset address ------------------*/
#ifdef VECT_TAB_SRAM
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
#endif
}
/**
* @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 MSI, SystemCoreClock will contain the MSI_VALUE(*)
*
* - 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(*) or MSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (*) MSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value
* 4 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSI_VALUE is a constant defined in stm32l4xx_hal.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 stm32l4xx_hal.h file (default value
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
* frequency of the crystal used. Otherwise, this function may
* have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate(void)
{
uint32_t tmp = 0U, msirange = 0U, pllvco = 0U, pllr = 2U, pllsource = 0U, pllm = 2U;
/* Get MSI Range frequency--------------------------------------------------*/
if((RCC->CR & RCC_CR_MSIRGSEL) == RESET)
{ /* MSISRANGE from RCC_CSR applies */
msirange = (RCC->CSR & RCC_CSR_MSISRANGE) >> 8U;
}
else
{ /* MSIRANGE from RCC_CR applies */
msirange = (RCC->CR & RCC_CR_MSIRANGE) >> 4U;
}
/*MSI frequency range in HZ*/
msirange = MSIRangeTable[msirange];
/* Get SYSCLK source -------------------------------------------------------*/
switch (RCC->CFGR & RCC_CFGR_SWS)
{
case 0x00: /* MSI used as system clock source */
SystemCoreClock = msirange;
break;
case 0x04: /* HSI used as system clock source */
SystemCoreClock = HSI_VALUE;
break;
case 0x08: /* HSE used as system clock source */
SystemCoreClock = HSE_VALUE;
break;
case 0x0C: /* PLL used as system clock source */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN
SYSCLK = PLL_VCO / PLLR
*/
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4U) + 1U ;
switch (pllsource)
{
case 0x02: /* HSI used as PLL clock source */
pllvco = (HSI_VALUE / pllm);
break;
case 0x03: /* HSE used as PLL clock source */
pllvco = (HSE_VALUE / pllm);
break;
default: /* MSI used as PLL clock source */
pllvco = (msirange / pllm);
break;
}
pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8U);
pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25U) + 1U) * 2U;
SystemCoreClock = pllvco/pllr;
break;
default:
SystemCoreClock = msirange;
break;
}
/* Compute HCLK clock frequency --------------------------------------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4U)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,255 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file usart_if.c
* @author MCD Application Team
* @brief Configuration of UART driver interface for hyperterminal communication
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Ultimate Liberty license
* SLA0044, the "License"; You may not use this file except in compliance with
* the License. You may obtain a copy of the License at:
* www.st.com/SLA0044
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "usart_if.h"
/* USER CODE BEGIN Includes */
#include "main.h"
/* USER CODE END Includes */
/* External variables ---------------------------------------------------------*/
/**
* @brief DMA handle
*/
extern DMA_HandleTypeDef hdma_usart2_tx;
/**
* @brief UART handle
*/
extern UART_HandleTypeDef huart2;
/**
* @brief buffer to receive 1 character
*/
uint8_t charRx;
/* USER CODE BEGIN EV */
/* USER CODE END EV */
/* Private typedef -----------------------------------------------------------*/
/**
* @brief Trace driver callbacks handler
*/
const UTIL_ADV_TRACE_Driver_s UTIL_TraceDriver =
{
vcom_Init,
vcom_DeInit,
vcom_ReceiveInit,
vcom_Trace_DMA,
};
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/**
* @brief TX complete callback
* @return none
*/
static void (*TxCpltCallback)(void *);
/**
* @brief RX complete callback
* @param rxChar ptr of chars buffer sent by user
* @param size buffer size
* @param error errorcode
* @return none
*/
static void (*RxCpltCallback)(uint8_t *rxChar, uint16_t size, uint8_t error);
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Exported functions --------------------------------------------------------*/
UTIL_ADV_TRACE_Status_t vcom_Init(void (*cb)(void *))
{
/* USER CODE BEGIN vcom_Init_1 */
/* USER CODE END vcom_Init_1 */
TxCpltCallback = cb;
MX_USART2_UART_Init();
return UTIL_ADV_TRACE_OK;
/* USER CODE BEGIN vcom_Init_2 */
/* USER CODE END vcom_Init_2 */
}
UTIL_ADV_TRACE_Status_t vcom_DeInit(void)
{
/* USER CODE BEGIN vcom_DeInit_1 */
/* USER CODE END vcom_DeInit_1 */
/* ##-1- Reset peripherals ################################################## */
__HAL_RCC_USART2_FORCE_RESET();
__HAL_RCC_USART2_RELEASE_RESET();
/* ##-2- MspDeInit ################################################## */
HAL_UART_MspDeInit(&huart2);
/* ##-3- Disable the NVIC for DMA ########################################### */
/* USER CODE BEGIN 1 */
HAL_NVIC_DisableIRQ(DMA1_Channel7_IRQn);
return UTIL_ADV_TRACE_OK;
/* USER CODE END 1 */
/* USER CODE BEGIN vcom_DeInit_2 */
/* USER CODE END vcom_DeInit_2 */
}
void vcom_Trace(uint8_t *p_data, uint16_t size)
{
/* USER CODE BEGIN vcom_Trace_1 */
/* USER CODE END vcom_Trace_1 */
HAL_UART_Transmit(&huart2, p_data, size, 1000);
/* USER CODE BEGIN vcom_Trace_2 */
/* USER CODE END vcom_Trace_2 */
}
UTIL_ADV_TRACE_Status_t vcom_Trace_DMA(uint8_t *p_data, uint16_t size)
{
/* USER CODE BEGIN vcom_Trace_DMA_1 */
/* USER CODE END vcom_Trace_DMA_1 */
HAL_UART_Transmit_DMA(&huart2, p_data, size);
return UTIL_ADV_TRACE_OK;
/* USER CODE BEGIN vcom_Trace_DMA_2 */
/* USER CODE END vcom_Trace_DMA_2 */
}
UTIL_ADV_TRACE_Status_t vcom_ReceiveInit(void (*RxCb)(uint8_t *rxChar, uint16_t size, uint8_t error))
{
/* USER CODE BEGIN vcom_ReceiveInit_1 */
/* USER CODE END vcom_ReceiveInit_1 */
UART_WakeUpTypeDef WakeUpSelection;
/*record call back*/
RxCpltCallback = RxCb;
/*Set wakeUp event on start bit*/
WakeUpSelection.WakeUpEvent = UART_WAKEUP_ON_STARTBIT;
HAL_UARTEx_StopModeWakeUpSourceConfig(&huart2, WakeUpSelection);
/* Make sure that no UART transfer is on-going */
while (__HAL_UART_GET_FLAG(&huart2, USART_ISR_BUSY) == SET);
/* Make sure that UART is ready to receive) */
while (__HAL_UART_GET_FLAG(&huart2, USART_ISR_REACK) == RESET);
/* Enable USART interrupt */
__HAL_UART_ENABLE_IT(&huart2, UART_IT_WUF);
/*Enable wakeup from stop mode*/
HAL_UARTEx_EnableStopMode(&huart2);
/*Start LPUART receive on IT*/
HAL_UART_Receive_IT(&huart2, &charRx, 1);
return UTIL_ADV_TRACE_OK;
/* USER CODE BEGIN vcom_ReceiveInit_2 */
/* USER CODE END vcom_ReceiveInit_2 */
}
void vcom_Resume(void)
{
/* USER CODE BEGIN vcom_Resume_1 */
/* USER CODE END vcom_Resume_1 */
/*to re-enable lost UART settings*/
if (HAL_UART_Init(&huart2) != HAL_OK)
{
Error_Handler();
}
/*to re-enable lost DMA settings*/
if (HAL_DMA_Init(&hdma_usart2_tx) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN vcom_Resume_2 */
/* USER CODE END vcom_Resume_2 */
}
void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart2)
{
/* USER CODE BEGIN HAL_UART_TxCpltCallback_1 */
/* USER CODE END HAL_UART_TxCpltCallback_1 */
/* buffer transmission complete*/
TxCpltCallback(NULL);
/* USER CODE BEGIN HAL_UART_TxCpltCallback_2 */
/* USER CODE END HAL_UART_TxCpltCallback_2 */
}
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart2)
{
/* USER CODE BEGIN HAL_UART_RxCpltCallback_1 */
/* USER CODE END HAL_UART_RxCpltCallback_1 */
if ((NULL != RxCpltCallback) && (HAL_UART_ERROR_NONE == huart2->ErrorCode))
{
RxCpltCallback(&charRx, 1, 0);
}
HAL_UART_Receive_IT(huart2, &charRx, 1);
/* USER CODE BEGIN HAL_UART_RxCpltCallback_2 */
/* USER CODE END HAL_UART_RxCpltCallback_2 */
}
/* USER CODE BEGIN EF */
/* USER CODE END EF */
/* Private Functions Definition -----------------------------------------------*/
/* USER CODE BEGIN PrFD */
/* USER CODE END PrFD */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,166 @@
#include "cmsis_os.h"
#include "commonMsg.h"
#include "utils.h"
#define MAX_ERR_NO 4
#define VAL_PARSE 15
extern osMutexId errorListMutexHandle;
uint16_t ErrorNo[MAX_ERR_NO] = { 0 };
uint8_t CR = 255, last_CR = 255;
uint8_t checksum()
{
uint8_t sum = 0;
for( int i=0; i<MAX_ERR_NO; i++ )
{
sum += ErrorNo[i];
}
sum ^= 0xFF;
return sum;
}
int8_t isAnyError()
{
int c = 0;
for( int i=0; i<MAX_ERR_NO; i++, c++ )
{
if( ErrorNo[i] == 0 )
break;
}
return c;
}
int8_t addErrorToList( uint16_t code )
{
int c = -1;
osStatus status = osMutexWait(errorListMutexHandle, 5000);
if (status == osOK)
{
c = isAnyError();
if( c == MAX_ERR_NO-1 )
{
deleteErrorById( c );
}
ErrorNo[c] = code;
CR = checksum();
osMutexRelease(errorListMutexHandle);
}
return c;
}
void clearErrorList()
{
osStatus status = osMutexWait(errorListMutexHandle, 5000);
if (status == osOK)
{
memset(ErrorNo,0,sizeof( ErrorNo ));
CR = checksum();
osMutexRelease(errorListMutexHandle);
}
}
int8_t findErrorByNo( uint16_t code )
{
for( int i=0; i<MAX_ERR_NO; i++ )
{
if( ErrorNo[i] == code )
{
return i;
}
}
return -1;
}
uint16_t findErrorById( int8_t id )
{
uint16_t ret = -1;
if( id >= 0 && id < MAX_ERR_NO )
{
ret = ErrorNo[id];
}
return ret;
}
void deleteErrorById( int8_t id )
{
osStatus status = osMutexWait(errorListMutexHandle, 5000);
if (status == osOK)
{
if( id > 0 )
{
ErrorNo[id] = 0;
int i = id+1;
while( i < MAX_ERR_NO )
{
ErrorNo[i] = ErrorNo[i-1];
i++;
}
CR = checksum();
}
osMutexRelease(errorListMutexHandle);
}
}
void deleteErrorByNo( uint16_t code )
{
int8_t id = findErrorByNo( code );
deleteErrorById( id );
}
// C substring function definition
void substring(char s[], char sub[], int startIndex, int endIndex )
{
int c = 0;
endIndex -= startIndex;
while ( c < endIndex ) {
sub[c] = s[startIndex + c];
c++;
}
sub[c] = '\0';
}
int toInt( char in[], int startIndex, int endIndex )
{
char buff[VAL_PARSE] = {0};
substring(in,buff,startIndex,endIndex);
return atoi(buff);
}
int toIntLen( char in[], int length )
{
char buff[VAL_PARSE] = {0};
substring(in,buff,0,length);
return atoi(buff);
}
long toLongLen( char in[], int length )
{
char buff[VAL_PARSE] = {0};
substring(in,buff,0,length);
return atol(buff);
}
float toFloat( char in[], int startIndex, int endIndex )
{
char buff[VAL_PARSE] = {0};
substring(in,buff,startIndex,endIndex);
return atof(buff);
}
bool toBool( char in[], int startIndex )
{
int r = toInt( in, startIndex, startIndex+1 );
return r > 0;
}

View File

@@ -0,0 +1,509 @@
/**
******************************************************************************
* @file startup_stm32l476xx.s
* @author MCD Application Team
* @brief STM32L476xx devices vector table GCC toolchain.
* This module performs:
* - Set the initial SP
* - Set the initial PC == Reset_Handler,
* - Set the vector table entries with the exceptions ISR address,
* - Configure the clock system
* - Branches to main in the C library (which eventually
* calls main()).
* After Reset the Cortex-M4 processor is in Thread mode,
* priority is Privileged, and the Stack is set to Main.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Apache License, Version 2.0,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/Apache-2.0
*
******************************************************************************
*/
.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
.equ BootRAM, 0xF1E0F85F
/**
* @brief This is the code that gets called when the processor first
* starts execution following a reset event. Only the absolutely
* necessary set is performed, after which the application
* supplied main() routine is called.
* @param None
* @retval : None
*/
.section .text.Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
ldr sp, =_estack /* Set stack pointer */
/* Call the clock system initialization function.*/
bl SystemInit
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInit
CopyDataInit:
ldr r3, =_sidata
ldr r3, [r3, r1]
str r3, [r0, r1]
adds r1, r1, #4
LoopCopyDataInit:
ldr r0, =_sdata
ldr r3, =_edata
adds r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
FillZerobss:
movs r3, #0
str r3, [r2], #4
LoopFillZerobss:
ldr r3, = _ebss
cmp r2, r3
bcc FillZerobss
/* Call static constructors */
bl __libc_init_array
/* Call the application's entry point.*/
bl main
LoopForever:
b LoopForever
.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-M4. Note that the proper constructs
* must be placed on this to ensure that it ends up at physical address
* 0x0000.0000.
*
******************************************************************************/
.section .isr_vector,"a",%progbits
.type g_pfnVectors, %object
.size g_pfnVectors, .-g_pfnVectors
g_pfnVectors:
.word _estack
.word Reset_Handler
.word NMI_Handler
.word HardFault_Handler
.word MemManage_Handler
.word BusFault_Handler
.word UsageFault_Handler
.word 0
.word 0
.word 0
.word 0
.word SVC_Handler
.word DebugMon_Handler
.word 0
.word PendSV_Handler
.word SysTick_Handler
.word WWDG_IRQHandler
.word PVD_PVM_IRQHandler
.word TAMP_STAMP_IRQHandler
.word RTC_WKUP_IRQHandler
.word FLASH_IRQHandler
.word RCC_IRQHandler
.word EXTI0_IRQHandler
.word EXTI1_IRQHandler
.word EXTI2_IRQHandler
.word EXTI3_IRQHandler
.word EXTI4_IRQHandler
.word DMA1_Channel1_IRQHandler
.word DMA1_Channel2_IRQHandler
.word DMA1_Channel3_IRQHandler
.word DMA1_Channel4_IRQHandler
.word DMA1_Channel5_IRQHandler
.word DMA1_Channel6_IRQHandler
.word DMA1_Channel7_IRQHandler
.word ADC1_2_IRQHandler
.word CAN1_TX_IRQHandler
.word CAN1_RX0_IRQHandler
.word CAN1_RX1_IRQHandler
.word CAN1_SCE_IRQHandler
.word EXTI9_5_IRQHandler
.word TIM1_BRK_TIM15_IRQHandler
.word TIM1_UP_TIM16_IRQHandler
.word TIM1_TRG_COM_TIM17_IRQHandler
.word TIM1_CC_IRQHandler
.word TIM2_IRQHandler
.word TIM3_IRQHandler
.word TIM4_IRQHandler
.word I2C1_EV_IRQHandler
.word I2C1_ER_IRQHandler
.word I2C2_EV_IRQHandler
.word I2C2_ER_IRQHandler
.word SPI1_IRQHandler
.word SPI2_IRQHandler
.word USART1_IRQHandler
.word USART2_IRQHandler
.word USART3_IRQHandler
.word EXTI15_10_IRQHandler
.word RTC_Alarm_IRQHandler
.word DFSDM1_FLT3_IRQHandler
.word TIM8_BRK_IRQHandler
.word TIM8_UP_IRQHandler
.word TIM8_TRG_COM_IRQHandler
.word TIM8_CC_IRQHandler
.word ADC3_IRQHandler
.word FMC_IRQHandler
.word SDMMC1_IRQHandler
.word TIM5_IRQHandler
.word SPI3_IRQHandler
.word UART4_IRQHandler
.word UART5_IRQHandler
.word TIM6_DAC_IRQHandler
.word TIM7_IRQHandler
.word DMA2_Channel1_IRQHandler
.word DMA2_Channel2_IRQHandler
.word DMA2_Channel3_IRQHandler
.word DMA2_Channel4_IRQHandler
.word DMA2_Channel5_IRQHandler
.word DFSDM1_FLT0_IRQHandler
.word DFSDM1_FLT1_IRQHandler
.word DFSDM1_FLT2_IRQHandler
.word COMP_IRQHandler
.word LPTIM1_IRQHandler
.word LPTIM2_IRQHandler
.word OTG_FS_IRQHandler
.word DMA2_Channel6_IRQHandler
.word DMA2_Channel7_IRQHandler
.word LPUART1_IRQHandler
.word QUADSPI_IRQHandler
.word I2C3_EV_IRQHandler
.word I2C3_ER_IRQHandler
.word SAI1_IRQHandler
.word SAI2_IRQHandler
.word SWPMI1_IRQHandler
.word TSC_IRQHandler
.word LCD_IRQHandler
.word 0
.word RNG_IRQHandler
.word FPU_IRQHandler
/*******************************************************************************
*
* 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_PVM_IRQHandler
.thumb_set PVD_PVM_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_Channel1_IRQHandler
.thumb_set DMA1_Channel1_IRQHandler,Default_Handler
.weak DMA1_Channel2_IRQHandler
.thumb_set DMA1_Channel2_IRQHandler,Default_Handler
.weak DMA1_Channel3_IRQHandler
.thumb_set DMA1_Channel3_IRQHandler,Default_Handler
.weak DMA1_Channel4_IRQHandler
.thumb_set DMA1_Channel4_IRQHandler,Default_Handler
.weak DMA1_Channel5_IRQHandler
.thumb_set DMA1_Channel5_IRQHandler,Default_Handler
.weak DMA1_Channel6_IRQHandler
.thumb_set DMA1_Channel6_IRQHandler,Default_Handler
.weak DMA1_Channel7_IRQHandler
.thumb_set DMA1_Channel7_IRQHandler,Default_Handler
.weak ADC1_2_IRQHandler
.thumb_set ADC1_2_IRQHandler,Default_Handler
.weak CAN1_TX_IRQHandler
.thumb_set CAN1_TX_IRQHandler,Default_Handler
.weak CAN1_RX0_IRQHandler
.thumb_set CAN1_RX0_IRQHandler,Default_Handler
.weak CAN1_RX1_IRQHandler
.thumb_set CAN1_RX1_IRQHandler,Default_Handler
.weak CAN1_SCE_IRQHandler
.thumb_set CAN1_SCE_IRQHandler,Default_Handler
.weak EXTI9_5_IRQHandler
.thumb_set EXTI9_5_IRQHandler,Default_Handler
.weak TIM1_BRK_TIM15_IRQHandler
.thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler
.weak TIM1_UP_TIM16_IRQHandler
.thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler
.weak TIM1_TRG_COM_TIM17_IRQHandler
.thumb_set TIM1_TRG_COM_TIM17_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 DFSDM1_FLT3_IRQHandler
.thumb_set DFSDM1_FLT3_IRQHandler,Default_Handler
.weak TIM8_BRK_IRQHandler
.thumb_set TIM8_BRK_IRQHandler,Default_Handler
.weak TIM8_UP_IRQHandler
.thumb_set TIM8_UP_IRQHandler,Default_Handler
.weak TIM8_TRG_COM_IRQHandler
.thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
.weak TIM8_CC_IRQHandler
.thumb_set TIM8_CC_IRQHandler,Default_Handler
.weak ADC3_IRQHandler
.thumb_set ADC3_IRQHandler,Default_Handler
.weak FMC_IRQHandler
.thumb_set FMC_IRQHandler,Default_Handler
.weak SDMMC1_IRQHandler
.thumb_set SDMMC1_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_Channel1_IRQHandler
.thumb_set DMA2_Channel1_IRQHandler,Default_Handler
.weak DMA2_Channel2_IRQHandler
.thumb_set DMA2_Channel2_IRQHandler,Default_Handler
.weak DMA2_Channel3_IRQHandler
.thumb_set DMA2_Channel3_IRQHandler,Default_Handler
.weak DMA2_Channel4_IRQHandler
.thumb_set DMA2_Channel4_IRQHandler,Default_Handler
.weak DMA2_Channel5_IRQHandler
.thumb_set DMA2_Channel5_IRQHandler,Default_Handler
.weak DFSDM1_FLT0_IRQHandler
.thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler
.weak DFSDM1_FLT1_IRQHandler
.thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler
.weak DFSDM1_FLT2_IRQHandler
.thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler
.weak COMP_IRQHandler
.thumb_set COMP_IRQHandler,Default_Handler
.weak LPTIM1_IRQHandler
.thumb_set LPTIM1_IRQHandler,Default_Handler
.weak LPTIM2_IRQHandler
.thumb_set LPTIM2_IRQHandler,Default_Handler
.weak OTG_FS_IRQHandler
.thumb_set OTG_FS_IRQHandler,Default_Handler
.weak DMA2_Channel6_IRQHandler
.thumb_set DMA2_Channel6_IRQHandler,Default_Handler
.weak DMA2_Channel7_IRQHandler
.thumb_set DMA2_Channel7_IRQHandler,Default_Handler
.weak LPUART1_IRQHandler
.thumb_set LPUART1_IRQHandler,Default_Handler
.weak QUADSPI_IRQHandler
.thumb_set QUADSPI_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 SAI1_IRQHandler
.thumb_set SAI1_IRQHandler,Default_Handler
.weak SAI2_IRQHandler
.thumb_set SAI2_IRQHandler,Default_Handler
.weak SWPMI1_IRQHandler
.thumb_set SWPMI1_IRQHandler,Default_Handler
.weak TSC_IRQHandler
.thumb_set TSC_IRQHandler,Default_Handler
.weak LCD_IRQHandler
.thumb_set LCD_IRQHandler,Default_Handler
.weak RNG_IRQHandler
.thumb_set RNG_IRQHandler,Default_Handler
.weak FPU_IRQHandler
.thumb_set FPU_IRQHandler,Default_Handler
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,472 @@
/*!
* \file sx1276mb1mas-board.c
*
* \brief Target board SX1276MB1MAS shield driver implementation
*
* \copyright Revised BSD License, see section \ref LICENSE.
*
* \code
* ______ _
* / _____) _ | |
* ( (____ _____ ____ _| |_ _____ ____| |__
* \____ \| ___ | (_ _) ___ |/ ___) _ \
* _____) ) ____| | | || |_| ____( (___| | | |
* (______/|_____)_|_|_| \__)_____)\____)_| |_|
* (C)2013-2017 Semtech
*
* \endcode
*
* \author Miguel Luis ( Semtech )
*
* \author Gregory Cristian ( Semtech )
*/
/**
******************************************************************************
* @file sx1276mb1mas.c
* @author MCD Application Team
* @brief driver sx1276mb1mas board
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2018 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "sx1276mb1mas.h"
#define IRQ_HIGH_PRIORITY 10
#define RF_MID_BAND_THRESH 525000000
extern osMutexId SPIMutexHandle;
/* Private variables ---------------------------------------------------------*/
static const uint32_t RADIO_DIO_EXTI_LINE[RADIO_DIOn] =
{
RADIO_DIO_0_EXTI_LINE,
RADIO_DIO_1_EXTI_LINE,
RADIO_DIO_2_EXTI_LINE,
RADIO_DIO_3_EXTI_LINE,
#if( RADIO_DIOn > 4 )
RADIO_DIO_4_EXTI_LINE,
#endif
#if( RADIO_DIOn > 5 )
RADIO_DIO_5_EXTI_LINE,
#endif
};
#ifndef SPI3_HAL_CONFIG
static const uint32_t RADIO_DIO_IT_PRIO [RADIO_DIOn] =
{
RADIO_DIO_0_IT_PRIO,
RADIO_DIO_1_IT_PRIO,
RADIO_DIO_2_IT_PRIO,
RADIO_DIO_3_IT_PRIO,
#if( RADIO_DIOn > 4 )
RADIO_DIO_4_IT_PRIO,
#endif
#if( RADIO_DIOn > 5 )
RADIO_DIO_5_IT_PRIO,
#endif
};
static const IRQn_Type RADIO_DIO_IRQn [RADIO_DIOn] =
{
RADIO_DIO_0_IRQn,
RADIO_DIO_1_IRQn,
RADIO_DIO_2_IRQn,
RADIO_DIO_3_IRQn,
#if( RADIO_DIOn > 4 )
RADIO_DIO_4_IRQn,
#endif
#if( RADIO_DIOn > 5 )
RADIO_DIO_5_IRQn,
#endif
};
#endif
static GPIO_TypeDef *RADIO_DIO_PORT[RADIO_DIOn] =
{
RADIO_DIO_0_PORT,
RADIO_DIO_1_PORT,
RADIO_DIO_2_PORT,
RADIO_DIO_3_PORT,
#if( RADIO_DIOn > 4 )
RADIO_DIO_4_PORT,
#endif
#if( RADIO_DIOn > 5 )
RADIO_DIO_5_PORT,
#endif
};
static const uint16_t RADIO_DIO_PIN[RADIO_DIOn] =
{
RADIO_DIO_0_PIN,
RADIO_DIO_1_PIN,
RADIO_DIO_2_PIN,
RADIO_DIO_3_PIN,
#if( RADIO_DIOn > 4 )
RADIO_DIO_4_PIN,
#endif
#if( RADIO_DIOn > 5 )
RADIO_DIO_5_PIN,
#endif
};
static const uint32_t RADIO_DIO_MODE[RADIO_DIOn] =
{
GPIO_MODE_IT_RISING,
GPIO_MODE_IT_RISING_FALLING,
GPIO_MODE_IT_RISING,
GPIO_MODE_IT_RISING,
#if( RADIO_DIOn > 4 )
GPIO_MODE_IT_RISING,
#endif
#if( RADIO_DIOn > 5 )
GPIO_MODE_IT_RISING,
#endif
};
/* static */ EXTI_HandleTypeDef hRADIO_DIO_exti[RADIO_DIOn];
/* Private function prototypes -----------------------------------------------*/
static void SX1276MB1MAS_RADIO_SPI_IoInit(SPI_HandleTypeDef *spiHandle);
static void SX1276MB1MAS_RADIO_SPI_IoDeInit(void);
/* Exported functions ---------------------------------------------------------*/
uint32_t SX1276MB1MAS_RADIO_GetWakeUpTime(void)
{
return BOARD_WAKEUP_TIME;
}
void SX1276MB1MAS_RADIO_SetXO(uint8_t state)
{
}
void SX1276MB1MAS_RADIO_IoInit(void)
{
GPIO_InitTypeDef initStruct = {0};
SPI_HandleTypeDef dummy_hspi;
/* Enable DIO GPIO clock */
RADIO_DIO_0_GPIO_CLK_ENABLE();
RADIO_DIO_1_GPIO_CLK_ENABLE();
RADIO_DIO_2_GPIO_CLK_ENABLE();
RADIO_DIO_3_GPIO_CLK_ENABLE();
#if( RADIO_DIOn > 4 )
RADIO_DIO_4_GPIO_CLK_ENABLE();
#endif
#if( RADIO_DIOn > 5 )
RADIO_DIO_5_GPIO_CLK_ENABLE();
#endif
/* DIO IO Init */
initStruct.Pull = GPIO_PULLDOWN;
initStruct.Speed = GPIO_SPEED_HIGH;
for (uint32_t i = 0; i < RADIO_DIOn ; i++)
{
initStruct.Mode = RADIO_DIO_MODE[i];
initStruct.Pin = RADIO_DIO_PIN[i];
HAL_GPIO_Init(RADIO_DIO_PORT[i], &initStruct);
}
#ifdef RFM95
/* Antenna IO Init */
RADIO_ANT_CLK_ENABLE();
initStruct.Pin = RADIO_ANT_SWITCH_PIN;
initStruct.Mode = GPIO_MODE_OUTPUT_PP;
initStruct.Pull = GPIO_NOPULL;
initStruct.Speed = GPIO_SPEED_HIGH;
//HAL_GPIO_Init(RADIO_ANT_SWITCH_PORT, &initStruct);
#endif
/* SPI IO Init */
/* Normally done by the HAL_MSP callback but not for this applic */
SX1276MB1MAS_RADIO_SPI_IoInit(&dummy_hspi);
/* NSS initialization */
initStruct.Pin = RADIO_NSS_PIN;
initStruct.Mode = GPIO_MODE_OUTPUT_PP;
initStruct.Pull = GPIO_PULLUP;
/* Enable NSS */
RADIO_NSS_CLK_ENABLE();
HAL_GPIO_Init(RADIO_NSS_PORT, &initStruct);
HAL_GPIO_WritePin(RADIO_NSS_PORT, RADIO_NSS_PIN, GPIO_PIN_SET);
}
void SX1276MB1MAS_RADIO_IoDeInit(void)
{
GPIO_InitTypeDef initStruct = {0};
/* DIO IO DeInit */
initStruct.Pull = GPIO_PULLDOWN;
for (uint32_t i = 0; i < RADIO_DIOn ; i++)
{
initStruct.Mode = RADIO_DIO_MODE[i];
initStruct.Pin = RADIO_DIO_PIN[i];
HAL_GPIO_Init(RADIO_DIO_PORT[i], &initStruct);
}
/* SPI IO DeInit */
SX1276MB1MAS_RADIO_SPI_IoDeInit();
/* NSS IO DeInit is not done */
/* Antenna IO DeInit is not done */
/* Reset IO DeInit is not done */
}
void SX1276MB1MAS_RADIO_IoIrqInit(DioIrqHandler **irqHandlers)
{
CRITICAL_SECTION_BEGIN();
for (uint32_t i = 0; i < RADIO_DIOn ; i++)
{
HAL_EXTI_GetHandle(&hRADIO_DIO_exti[i], RADIO_DIO_EXTI_LINE[i]);
HAL_EXTI_RegisterCallback(&hRADIO_DIO_exti[i], HAL_EXTI_COMMON_CB_ID, irqHandlers[i]);
#ifndef SPI3_HAL_CONFIG
HAL_NVIC_SetPriority(RADIO_DIO_IRQn[i], RADIO_DIO_IT_PRIO[i], 0x00);
HAL_NVIC_EnableIRQ(RADIO_DIO_IRQn[i]);
#endif
}
CRITICAL_SECTION_END();
}
/*!
* @brief it points the demanded line in the EXTI_HandleTypeDef TABLE before calling HAL_EXTI_IRQHandler()
* @param [IN]: DIO extiLine demanded
* @retval none
* @note "stm32lyxx_it.c" code generated by MX do not call this function but directly the HAL_EXTI_IRQHandler()
*/
void SX1276MB1MAS_RADIO_IRQHandler(RADIO_DIO_TypeDef DIO)
{
HAL_EXTI_IRQHandler(&hRADIO_DIO_exti[DIO]);
}
TxConfig_TypeDef SX1276MB1MAS_RADIO_GetPaSelect(uint32_t channel)
{
#ifdef RFM95
return CONF_RFO_LF;
#else
if (channel > RF_MID_BAND_THRESH)
{
return CONF_RFO_LP;
}
else
{
return CONF_RFO_LF;
}
#endif
}
void SX1276MB1MAS_RADIO_SetAntSw(RfSw_TypeDef state)
{
#ifndef RFM95
switch (state)
{
case RFSW_OFF:
{
HAL_GPIO_WritePin(RADIO_ANT_SWITCH_PORT, RADIO_ANT_SWITCH_PIN, GPIO_PIN_RESET);
break;
}
case RFSW_RX:
{
HAL_GPIO_WritePin(RADIO_ANT_SWITCH_PORT, RADIO_ANT_SWITCH_PIN, GPIO_PIN_RESET);
break;
}
case RFSW_RFO_LP:
{
HAL_GPIO_WritePin(RADIO_ANT_SWITCH_PORT, RADIO_ANT_SWITCH_PIN, GPIO_PIN_SET);
break;
}
case RFSW_RFO_HP:
{
break;
}
case RFSW_RFO_LF:
{
break;
}
default:
HAL_GPIO_WritePin(RADIO_ANT_SWITCH_PORT, RADIO_ANT_SWITCH_PIN, GPIO_PIN_RESET);
break;
}
#endif
}
bool SX1276MB1MAS_RADIO_CheckRfFrequency(uint32_t frequency)
{
// Implement check. Currently all frequencies are supported
return true;
}
void SX1276MB1MAS_RADIO_Reset(void)
{
#ifndef RFM95
GPIO_InitTypeDef initStruct = { 0 };
initStruct.Mode = GPIO_MODE_OUTPUT_PP;
initStruct.Pull = GPIO_NOPULL;
initStruct.Speed = GPIO_SPEED_HIGH;
initStruct.Pin = RADIO_RESET_PIN;
// Set RESET pin to 0
HAL_GPIO_Init(RADIO_RESET_PORT, &initStruct);
HAL_GPIO_WritePin(RADIO_RESET_PORT, RADIO_RESET_PIN, GPIO_PIN_RESET);
// Wait 1 ms
osDelay(1);
// Configure RESET as input
initStruct.Mode = GPIO_NOPULL;
HAL_GPIO_Init(RADIO_RESET_PORT, &initStruct);
// Wait 6 ms
osDelay(6);
#else
HAL_GPIO_WritePin(RADIO_RESET_PORT, RADIO_RESET_PIN, GPIO_PIN_RESET);
// Wait 1 ms
osDelay(1);
HAL_GPIO_WritePin(RADIO_RESET_PORT, RADIO_RESET_PIN, GPIO_PIN_SET);
// Wait 6 ms
osDelay(6);
#endif
}
/* Bus mapping to SPI */
void SX1276MB1MAS_RADIO_Bus_Init(void)
{
RADIO_SPI_Init();
}
void SX1276MB1MAS_RADIO_Bus_deInit(void)
{
RADIO_SPI_DeInit();
}
/**
* @brief Send Receive data via SPI
* @param Data to send
* @retval Received data
*/
uint16_t SX1276MB1MAS_RADIO_SendRecv(uint16_t txData)
{
uint16_t rxData ;
RADIO_SPI_SendRecv((uint8_t *) &txData, (uint8_t *) &rxData, 1);
return rxData;
}
void SX1276MB1MAS_RADIO_ChipSelect(int32_t state)
{
if (state == 0)
{
osStatus status = osMutexWait(SPIMutexHandle, 10);
if( status == osOK )
{
HAL_GPIO_WritePin(RADIO_NSS_PORT, RADIO_NSS_PIN, GPIO_PIN_RESET);
}
}
else
{
HAL_GPIO_WritePin(RADIO_NSS_PORT, RADIO_NSS_PIN, GPIO_PIN_SET);
osMutexRelease(SPIMutexHandle);
}
}
uint32_t SX1276MB1MAS_RADIO_GetDio1PinState(void)
{
return HAL_GPIO_ReadPin(RADIO_DIO_1_PORT, RADIO_DIO_1_PIN);
}
/* Private functions --------------------------------------------------------*/
/**
* @brief Initializes SPI MSP.
* @param hspi SPI handler
* @retval None
*/
static void SX1276MB1MAS_RADIO_SPI_IoInit(SPI_HandleTypeDef *spiHandle)
{
GPIO_InitTypeDef GPIO_InitStruct;
/* USER CODE BEGIN SPI3_MspInit 0 */
/* USER CODE END SPI3_MspInit 0 */
/* Enable Peripheral clock */
RADIO_SPI_SCK_GPIO_CLK_ENABLE();
RADIO_SPI_MOSI_GPIO_CLK_ENABLE();
RADIO_SPI_MISO_GPIO_CLK_ENABLE();
/**SPI1 GPIO Configuration
PC10 ------> SPI3_SCK
PC11 ------> SPI3_MISO
PC12 ------> SPI3_MOSI
*/
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
GPIO_InitStruct.Alternate = RADIO_SPI_MOSI_GPIO_AF;
GPIO_InitStruct.Pin = RADIO_SPI_MOSI_GPIO_PIN;
HAL_GPIO_Init(RADIO_SPI_MOSI_GPIO_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Alternate = RADIO_SPI_MISO_GPIO_AF;
GPIO_InitStruct.Pin = RADIO_SPI_MISO_GPIO_PIN;
HAL_GPIO_Init(RADIO_SPI_MISO_GPIO_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Alternate = RADIO_SPI_SCK_GPIO_AF;
GPIO_InitStruct.Pin = RADIO_SPI_SCK_GPIO_PIN;
HAL_GPIO_Init(RADIO_SPI_SCK_GPIO_PORT, &GPIO_InitStruct);
}
/**
* @brief DeInitializes SPI MSP.
* @param hspi SPI handler
* @retval None
*/
static void SX1276MB1MAS_RADIO_SPI_IoDeInit(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
/* Peripheral clock disable */
/* no need to call SPI1_CLK_DISABLE() because going in LowPower it gets disabled automatically */
/* DeInitialize Peripheral GPIOs */
/* Instead of using HAL_GPIO_DeInit() which set ANALOG mode
it's preferred to set in OUTPUT_PP mode, with the pins set to 0 */
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Pin = RADIO_SPI_MOSI_GPIO_PIN;
HAL_GPIO_Init(RADIO_SPI_MOSI_GPIO_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = RADIO_SPI_MISO_GPIO_PIN;
HAL_GPIO_Init(RADIO_SPI_MISO_GPIO_PORT, &GPIO_InitStruct);
GPIO_InitStruct.Pin = RADIO_SPI_SCK_GPIO_PIN;
HAL_GPIO_Init(RADIO_SPI_SCK_GPIO_PORT, &GPIO_InitStruct);
HAL_GPIO_WritePin(RADIO_SPI_MOSI_GPIO_PORT, RADIO_SPI_MOSI_GPIO_PIN, GPIO_PIN_RESET);
HAL_GPIO_WritePin(RADIO_SPI_MISO_GPIO_PORT, RADIO_SPI_MISO_GPIO_PIN, GPIO_PIN_RESET);
HAL_GPIO_WritePin(RADIO_SPI_SCK_GPIO_PORT, RADIO_SPI_SCK_GPIO_PIN, GPIO_PIN_RESET);
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,199 @@
/*
/ _____) _ | |
( (____ _____ ____ _| |_ _____ ____| |__
\____ \| ___ | (_ _) ___ |/ ___) _ \
_____) ) ____| | | || |_| ____( (___| | | |
(______/|_____)_|_|_| \__)_____)\____)_| |_|
(C)2013 Semtech
Description: driver specific target board functions implementation
License: Revised BSD License, see LICENSE.TXT file include in the project
Maintainer: Miguel Luis and Gregory Cristian
*/
/**
******************************************************************************
* @file sx1276mb1mas.h
* @author MCD Application Team
* @brief driver for sx1276mb1mas board
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2018 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __SX1276MB1MAS__
#define __SX1276MB1MAS__
#ifdef __cplusplus
extern "C"
{
#endif
/* Includes ------------------------------------------------------------------*/
#include <stdint.h>
#include <stdbool.h>
#include "sx1276mb1mas_conf.h"
/**
* @brief Define for SX1276MB1XAS board
*/
#if !defined (USE_SX1276MB1XAS)
#define USE_SX1276MB1XAS
#endif
/* Exported types ------------------------------------------------------------*/
typedef enum
{
RFSW_OFF = 0,
RFSW_RX,
RFSW_RFO_LP,
RFSW_RFO_HP,
RFSW_RFO_LF,
} RfSw_TypeDef;
typedef enum
{
CONF_RFO_LP_HP = 0,
CONF_RFO_LP = 1,
CONF_RFO_HP = 2,
CONF_RFO_LF = 3,
} TxConfig_TypeDef;
/* RADIO_DIO_TypeDef is defined in case SX1276MB1MAS_RADIO_IRQHandler() API is used */
typedef enum
{
RADIO_DIO_0 = 0U,
RADIO_DIO_1 = 1U,
RADIO_DIO_2 = 2U,
RADIO_DIO_3 = 3U,
#if( RADIO_DIOn > 4 )
RADIO_DIO_4 = 4U,
#endif
#if( RADIO_DIOn > 5 )
RADIO_DIO_5 = 5U,
#endif
} RADIO_DIO_TypeDef;
/* Hardware IO IRQ callback function definition */
typedef void (DioIrqHandler)(void);
/* Exported constants --------------------------------------------------------*/
#define BOARD_WAKEUP_TIME 0 // no TCXO
/* Exported variables------------------------------------------------------- */
extern EXTI_HandleTypeDef hRADIO_DIO_exti[RADIO_DIOn];
/* Exported functions ------------------------------------------------------- */
/*!
* \brief Initializes the radio I/Os pins interface
*/
void SX1276MB1MAS_RADIO_IoInit(void);
/*!
* \brief De-initializes the radio I/Os pins interface.
*
* \remark Useful when going in MCU low power modes
*/
void SX1276MB1MAS_RADIO_IoDeInit(void);
/*!
* \brief Register Radio Irq Handler.
*
* \param array of callbacks wrt to DIO numbers
*/
void SX1276MB1MAS_RADIO_IoIrqInit(DioIrqHandler **irqHandlers);
/*!
* \brief Send a command that write data to the radio
*
* \param [in] txData data to be sent
* \return [out] rxdata data to be read
*/
uint16_t SX1276MB1MAS_RADIO_SendRecv(uint16_t txData);
/*!
* \brief Chip select of the board
*
* \param [in] state 0 state is 0, 1 otherwise
*/
void SX1276MB1MAS_RADIO_ChipSelect(int32_t state);
/*!
* \brief Gets current state of DIO1 pin state (FifoLevel).
*
* \retval state DIO1 pin current state.
*/
uint32_t SX1276MB1MAS_RADIO_GetDio1PinState(void);
/*!
* \brief Checks if the given RF frequency is supported by the hardware
*
* \param [IN] frequency RF frequency to be checked
* \retval isSupported [true: supported, false: unsupported]
*/
bool SX1276MB1MAS_RADIO_CheckRfFrequency(uint32_t frequency);
/*!
* \brief Resets the Radio
*/
void SX1276MB1MAS_RADIO_Reset(void);
/*!
* \brief Set the XO on/off
*
* \param [IN] 0 off, 1 On
* \remark not applicable for this board
*/
void SX1276MB1MAS_RADIO_SetXO(uint8_t state);
/*!
* \brief Get the wake up time of the board
*
* \return value time in ms
*/
uint32_t SX1276MB1MAS_RADIO_GetWakeUpTime(void);
/*!
* \brief Get the PA configuration of the board
* \param channel frequency at which the the transmission will occur
* \return PA configuration of the board
*/
TxConfig_TypeDef SX1276MB1MAS_RADIO_GetPaSelect(uint32_t channel);
/*!
* \brief Set the antenna switch on the requested input
* \param requested input
*/
void SX1276MB1MAS_RADIO_SetAntSw(RfSw_TypeDef state);
/*!
* \brief SPI Bus init
*/
void SX1276MB1MAS_RADIO_Bus_Init(void);
/*!
* \brief SPI Bus Deinit
*/
void SX1276MB1MAS_RADIO_Bus_deInit(void);
#ifdef __cplusplus
}
#endif
#endif /* __SX1276MB1MAS__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,303 @@
/**
******************************************************************************
* @file stm32l4xx.h
* @author MCD Application Team
* @brief CMSIS STM32L4xx Device Peripheral Access Layer Header File.
*
* The file is the unique include file that the application programmer
* is using in the C source code, usually in main.c. This file contains:
* - Configuration section that allows to select:
* - The STM32L4xx device used in the target application
* - To use or not the peripheral's drivers in application code(i.e.
* code will be based on direct access to peripheral's registers
* rather than drivers API), this option is controlled by
* "#define USE_HAL_DRIVER"
*
******************************************************************************
* @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 stm32l4xx
* @{
*/
#ifndef __STM32L4xx_H
#define __STM32L4xx_H
#ifdef __cplusplus
extern "C" {
#endif /* __cplusplus */
/** @addtogroup Library_configuration_section
* @{
*/
/**
* @brief STM32 Family
*/
#if !defined (STM32L4)
#define STM32L4
#endif /* STM32L4 */
/* Uncomment the line below according to the target STM32L4 device used in your
application
*/
#if !defined (STM32L412xx) && !defined (STM32L422xx) && \
!defined (STM32L431xx) && !defined (STM32L432xx) && !defined (STM32L433xx) && !defined (STM32L442xx) && !defined (STM32L443xx) && \
!defined (STM32L451xx) && !defined (STM32L452xx) && !defined (STM32L462xx) && \
!defined (STM32L471xx) && !defined (STM32L475xx) && !defined (STM32L476xx) && !defined (STM32L485xx) && !defined (STM32L486xx) && \
!defined (STM32L496xx) && !defined (STM32L4A6xx) && \
!defined (STM32L4P5xx) && !defined (STM32L4Q5xx) && \
!defined (STM32L4R5xx) && !defined (STM32L4R7xx) && !defined (STM32L4R9xx) && !defined (STM32L4S5xx) && !defined (STM32L4S7xx) && !defined (STM32L4S9xx)
/* #define STM32L412xx */ /*!< STM32L412xx Devices */
/* #define STM32L422xx */ /*!< STM32L422xx Devices */
/* #define STM32L431xx */ /*!< STM32L431xx Devices */
/* #define STM32L432xx */ /*!< STM32L432xx Devices */
/* #define STM32L433xx */ /*!< STM32L433xx Devices */
/* #define STM32L442xx */ /*!< STM32L442xx Devices */
/* #define STM32L443xx */ /*!< STM32L443xx Devices */
/* #define STM32L451xx */ /*!< STM32L451xx Devices */
/* #define STM32L452xx */ /*!< STM32L452xx Devices */
/* #define STM32L462xx */ /*!< STM32L462xx Devices */
/* #define STM32L471xx */ /*!< STM32L471xx Devices */
/* #define STM32L475xx */ /*!< STM32L475xx Devices */
/* #define STM32L476xx */ /*!< STM32L476xx Devices */
/* #define STM32L485xx */ /*!< STM32L485xx Devices */
/* #define STM32L486xx */ /*!< STM32L486xx Devices */
/* #define STM32L496xx */ /*!< STM32L496xx Devices */
/* #define STM32L4A6xx */ /*!< STM32L4A6xx Devices */
/* #define STM32L4P5xx */ /*!< STM32L4Q5xx Devices */
/* #define STM32L4R5xx */ /*!< STM32L4R5xx Devices */
/* #define STM32L4R7xx */ /*!< STM32L4R7xx Devices */
/* #define STM32L4R9xx */ /*!< STM32L4R9xx Devices */
/* #define STM32L4S5xx */ /*!< STM32L4S5xx Devices */
/* #define STM32L4S7xx */ /*!< STM32L4S7xx Devices */
/* #define STM32L4S9xx */ /*!< STM32L4S9xx Devices */
#endif
/* Tip: To avoid modifying this file each time you need to switch between these
devices, you can define the device in your toolchain compiler preprocessor.
*/
#if !defined (USE_HAL_DRIVER)
/**
* @brief Comment the line below if you will not use the peripherals drivers.
In this case, these drivers will not be included and the application code will
be based on direct access to peripherals registers
*/
/*#define USE_HAL_DRIVER */
#endif /* USE_HAL_DRIVER */
/**
* @brief CMSIS Device version number
*/
#define __STM32L4_CMSIS_VERSION_MAIN (0x01) /*!< [31:24] main version */
#define __STM32L4_CMSIS_VERSION_SUB1 (0x07) /*!< [23:16] sub1 version */
#define __STM32L4_CMSIS_VERSION_SUB2 (0x04) /*!< [15:8] sub2 version */
#define __STM32L4_CMSIS_VERSION_RC (0x00) /*!< [7:0] release candidate */
#define __STM32L4_CMSIS_VERSION ((__STM32L4_CMSIS_VERSION_MAIN << 24)\
|(__STM32L4_CMSIS_VERSION_SUB1 << 16)\
|(__STM32L4_CMSIS_VERSION_SUB2 << 8 )\
|(__STM32L4_CMSIS_VERSION_RC))
/**
* @}
*/
/** @addtogroup Device_Included
* @{
*/
#if defined(STM32L412xx)
#include "stm32l412xx.h"
#elif defined(STM32L422xx)
#include "stm32l422xx.h"
#elif defined(STM32L431xx)
#include "stm32l431xx.h"
#elif defined(STM32L432xx)
#include "stm32l432xx.h"
#elif defined(STM32L433xx)
#include "stm32l433xx.h"
#elif defined(STM32L442xx)
#include "stm32l442xx.h"
#elif defined(STM32L443xx)
#include "stm32l443xx.h"
#elif defined(STM32L451xx)
#include "stm32l451xx.h"
#elif defined(STM32L452xx)
#include "stm32l452xx.h"
#elif defined(STM32L462xx)
#include "stm32l462xx.h"
#elif defined(STM32L471xx)
#include "stm32l471xx.h"
#elif defined(STM32L475xx)
#include "stm32l475xx.h"
#elif defined(STM32L476xx)
#include "stm32l476xx.h"
#elif defined(STM32L485xx)
#include "stm32l485xx.h"
#elif defined(STM32L486xx)
#include "stm32l486xx.h"
#elif defined(STM32L496xx)
#include "stm32l496xx.h"
#elif defined(STM32L4A6xx)
#include "stm32l4a6xx.h"
#elif defined(STM32L4P5xx)
#include "stm32l4p5xx.h"
#elif defined(STM32L4Q5xx)
#include "stm32l4q5xx.h"
#elif defined(STM32L4R5xx)
#include "stm32l4r5xx.h"
#elif defined(STM32L4R7xx)
#include "stm32l4r7xx.h"
#elif defined(STM32L4R9xx)
#include "stm32l4r9xx.h"
#elif defined(STM32L4S5xx)
#include "stm32l4s5xx.h"
#elif defined(STM32L4S7xx)
#include "stm32l4s7xx.h"
#elif defined(STM32L4S9xx)
#include "stm32l4s9xx.h"
#else
#error "Please select first the target STM32L4xx device used in your application (in stm32l4xx.h file)"
#endif
/**
* @}
*/
/** @addtogroup Exported_types
* @{
*/
typedef enum
{
RESET = 0,
SET = !RESET
} FlagStatus, ITStatus;
typedef enum
{
DISABLE = 0,
ENABLE = !DISABLE
} FunctionalState;
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
typedef enum
{
SUCCESS = 0,
ERROR = !SUCCESS
} ErrorStatus;
/**
* @}
*/
/** @addtogroup Exported_macros
* @{
*/
#define SET_BIT(REG, BIT) ((REG) |= (BIT))
#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT))
#define READ_BIT(REG, BIT) ((REG) & (BIT))
#define CLEAR_REG(REG) ((REG) = (0x0))
#define WRITE_REG(REG, VAL) ((REG) = (VAL))
#define READ_REG(REG) ((REG))
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
/* Use of CMSIS compiler intrinsics for register exclusive access */
/* Atomic 32-bit register access macro to set one or several bits */
#define ATOMIC_SET_BIT(REG, BIT) \
do { \
uint32_t val; \
do { \
val = __LDREXW((__IO uint32_t *)&(REG)) | (BIT); \
} while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \
} while(0)
/* Atomic 32-bit register access macro to clear one or several bits */
#define ATOMIC_CLEAR_BIT(REG, BIT) \
do { \
uint32_t val; \
do { \
val = __LDREXW((__IO uint32_t *)&(REG)) & ~(BIT); \
} while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \
} while(0)
/* Atomic 32-bit register access macro to clear and set one or several bits */
#define ATOMIC_MODIFY_REG(REG, CLEARMSK, SETMASK) \
do { \
uint32_t val; \
do { \
val = (__LDREXW((__IO uint32_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \
} while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \
} while(0)
/* Atomic 16-bit register access macro to set one or several bits */
#define ATOMIC_SETH_BIT(REG, BIT) \
do { \
uint16_t val; \
do { \
val = __LDREXH((__IO uint16_t *)&(REG)) | (BIT); \
} while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \
} while(0)
/* Atomic 16-bit register access macro to clear one or several bits */
#define ATOMIC_CLEARH_BIT(REG, BIT) \
do { \
uint16_t val; \
do { \
val = __LDREXH((__IO uint16_t *)&(REG)) & ~(BIT); \
} while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \
} while(0)
/* Atomic 16-bit register access macro to clear and set one or several bits */
#define ATOMIC_MODIFYH_REG(REG, CLEARMSK, SETMASK) \
do { \
uint16_t val; \
do { \
val = (__LDREXH((__IO uint16_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \
} while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \
} while(0)
#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL)))
/**
* @}
*/
#if defined (USE_HAL_DRIVER)
#include "stm32l4xx_hal.h"
#endif /* USE_HAL_DRIVER */
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* __STM32L4xx_H */
/**
* @}
*/
/**
* @}
*/

View File

@@ -0,0 +1,106 @@
/**
******************************************************************************
* @file system_stm32l4xx.h
* @author MCD Application Team
* @brief CMSIS Cortex-M4 Device System Source File for STM32L4xx devices.
******************************************************************************
* @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 stm32l4xx_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32L4XX_H
#define __SYSTEM_STM32L4XX_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup STM32L4xx_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Exported_Variables
* @{
*/
/* The SystemCoreClock variable is updated in three ways:
1) by calling CMSIS function SystemCoreClockUpdate()
2) by calling HAL API function HAL_RCC_GetSysClockFreq()
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.
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */
extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */
extern const uint32_t MSIRangeTable[12]; /*!< MSI ranges table values */
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Exported_Constants
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Exported_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32L4xx_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32L4XX_H */
/**
* @}
*/
/**
* @}
*/

View File

@@ -0,0 +1,6 @@
This software component is provided to you as part of a software package and
applicable license terms are in the Package_license file. If you received this
software component outside of a package or without applicable license terms,
the terms of the Apache-2.0 license shall apply.
You may obtain a copy of the Apache-2.0 at:
https://opensource.org/licenses/Apache-2.0

View File

@@ -0,0 +1,83 @@
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction, and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all other entities that control, are controlled by, or are under common control with that entity. For the purposes of this definition, "control" means (i) the power, direct or indirect, to cause the direction or management of such entity, whether by contract or otherwise, or (ii) ownership of fifty percent (50%) or more of the outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications, including but not limited to software source code, documentation source, and configuration files.
"Object" form shall mean any form resulting from mechanical transformation or translation of a Source form, including but not limited to compiled object code, generated documentation, and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or Object form, made available under the License, as indicated by a copyright notice that is included in or attached to the work (an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object form, that is based on (or derived from) the Work and for which the editorial revisions, annotations, elaborations, or other modifications represent, as a whole, an original work of authorship. For the purposes of this License, Derivative Works shall not include works that remain separable from, or merely link (or bind by name) to the interfaces of, the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including the original version of the Work and any modifications or additions to that Work or Derivative Works thereof, that is intentionally submitted to Licensor for inclusion in the Work by the copyright owner or by an individual or Legal Entity authorized to submit on behalf of the copyright owner. For the purposes of this definition, "submitted" means any form of electronic, verbal, or written communication sent to the Licensor or its representatives, including but not limited to communication on electronic mailing lists, source code control systems, and issue tracking systems that are managed by, or on behalf of, the Licensor for the purpose of discussing and improving the Work, but excluding communication that is conspicuously marked or otherwise designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity on behalf of whom a Contribution has been received by Licensor and subsequently incorporated within the Work.
2. Grant of Copyright License.
Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable copyright license to reproduce, prepare Derivative Works of, publicly display, publicly perform, sublicense, and distribute the Work and such Derivative Works in Source or Object form.
3. Grant of Patent License.
Subject to the terms and conditions of this License, each Contributor hereby grants to You a perpetual, worldwide, non-exclusive, no-charge, royalty-free, irrevocable (except as stated in this section) patent license to make, have made, use, offer to sell, sell, import, and otherwise transfer the Work, where such license applies only to those patent claims licensable by such Contributor that are necessarily infringed by their Contribution(s) alone or by combination of their Contribution(s) with the Work to which such Contribution(s) was submitted. If You institute patent litigation against any entity (including a cross-claim or counterclaim in a lawsuit) alleging that the Work or a Contribution incorporated within the Work constitutes direct or contributory patent infringement, then any patent licenses granted to You under this License for that Work shall terminate as of the date such litigation is filed.
4. Redistribution.
You may reproduce and distribute copies of the Work or Derivative Works thereof in any medium, with or without modifications, and in Source or Object form, provided that You meet the following conditions:
1.You must give any other recipients of the Work or Derivative Works a copy of this License; and
2.You must cause any modified files to carry prominent notices stating that You changed the files; and
3.You must retain, in the Source form of any Derivative Works that You distribute, all copyright, patent, trademark, and attribution notices from the Source form of the Work, excluding those notices that do not pertain to any part of the Derivative Works; and
4.If the Work includes a "NOTICE" text file as part of its distribution, then any Derivative Works that You distribute must include a readable copy of the attribution notices contained within such NOTICE file, excluding those notices that do not pertain to any part of the Derivative Works, in at least one of the following places: within a NOTICE text file distributed as part of the Derivative Works; within the Source form or documentation, if provided along with the Derivative Works; or, within a display generated by the Derivative Works, if and wherever such third-party notices normally appear. The contents of the NOTICE file are for informational purposes only and do not modify the License. You may add Your own attribution notices within Derivative Works that You distribute, alongside or as an addendum to the NOTICE text from the Work, provided that such additional attribution notices cannot be construed as modifying the License.
You may add Your own copyright statement to Your modifications and may provide additional or different license terms and conditions for use, reproduction, or distribution of Your modifications, or for any such Derivative Works as a whole, provided Your use, reproduction, and distribution of the Work otherwise complies with the conditions stated in this License.
5. Submission of Contributions.
Unless You explicitly state otherwise, any Contribution intentionally submitted for inclusion in the Work by You to the Licensor shall be under the terms and conditions of this License, without any additional terms or conditions. Notwithstanding the above, nothing herein shall supersede or modify the terms of any separate license agreement you may have executed with Licensor regarding such Contributions.
6. Trademarks.
This License does not grant permission to use the trade names, trademarks, service marks, or product names of the Licensor, except as required for reasonable and customary use in describing the origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty.
Unless required by applicable law or agreed to in writing, Licensor provides the Work (and each Contributor provides its Contributions) on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied, including, without limitation, any warranties or conditions of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A PARTICULAR PURPOSE. You are solely responsible for determining the appropriateness of using or redistributing the Work and assume any risks associated with Your exercise of permissions under this License.
8. Limitation of Liability.
In no event and under no legal theory, whether in tort (including negligence), contract, or otherwise, unless required by applicable law (such as deliberate and grossly negligent acts) or agreed to in writing, shall any Contributor be liable to You for damages, including any direct, indirect, special, incidental, or consequential damages of any character arising as a result of this License or out of the use or inability to use the Work (including but not limited to damages for loss of goodwill, work stoppage, computer failure or malfunction, or any and all other commercial damages or losses), even if such Contributor has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability.
While redistributing the Work or Derivative Works thereof, You may choose to offer, and charge a fee for, acceptance of support, warranty, indemnity, or other liability obligations and/or rights consistent with this License. However, in accepting such obligations, You may act only on Your own behalf and on Your sole responsibility, not on behalf of any other Contributor, and only if You agree to indemnify, defend, and hold each Contributor harmless for any liability incurred by, or claims asserted against, such Contributor by reason of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX:
Copyright [2019] [STMicroelectronics]
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.

View File

@@ -0,0 +1,894 @@
/**************************************************************************//**
* @file cmsis_armcc.h
* @brief CMSIS compiler ARMCC (Arm Compiler 5) header file
* @version V5.1.0
* @date 08. May 2019
******************************************************************************/
/*
* Copyright (c) 2009-2019 Arm Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CMSIS_ARMCC_H
#define __CMSIS_ARMCC_H
#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 400677)
#error "Please use Arm Compiler Toolchain V4.0.677 or later!"
#endif
/* CMSIS compiler control architecture macros */
#if ((defined (__TARGET_ARCH_6_M ) && (__TARGET_ARCH_6_M == 1)) || \
(defined (__TARGET_ARCH_6S_M ) && (__TARGET_ARCH_6S_M == 1)) )
#define __ARM_ARCH_6M__ 1
#endif
#if (defined (__TARGET_ARCH_7_M ) && (__TARGET_ARCH_7_M == 1))
#define __ARM_ARCH_7M__ 1
#endif
#if (defined (__TARGET_ARCH_7E_M) && (__TARGET_ARCH_7E_M == 1))
#define __ARM_ARCH_7EM__ 1
#endif
/* __ARM_ARCH_8M_BASE__ not applicable */
/* __ARM_ARCH_8M_MAIN__ not applicable */
/* CMSIS compiler control DSP macros */
#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
#define __ARM_FEATURE_DSP 1
#endif
/* CMSIS compiler specific defines */
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE __inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static __inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE static __forceinline
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __declspec(noreturn)
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __attribute__((packed))
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT __packed struct
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION __packed union
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
#define __UNALIGNED_UINT32(x) (*((__packed uint32_t *)(x)))
#endif
#ifndef __UNALIGNED_UINT16_WRITE
#define __UNALIGNED_UINT16_WRITE(addr, val) ((*((__packed uint16_t *)(addr))) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
#define __UNALIGNED_UINT16_READ(addr) (*((const __packed uint16_t *)(addr)))
#endif
#ifndef __UNALIGNED_UINT32_WRITE
#define __UNALIGNED_UINT32_WRITE(addr, val) ((*((__packed uint32_t *)(addr))) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
#define __UNALIGNED_UINT32_READ(addr) (*((const __packed uint32_t *)(addr)))
#endif
#ifndef __ALIGNED
#define __ALIGNED(x) __attribute__((aligned(x)))
#endif
#ifndef __RESTRICT
#define __RESTRICT __restrict
#endif
#ifndef __COMPILER_BARRIER
#define __COMPILER_BARRIER() __memory_changed()
#endif
/* ######################### Startup and Lowlevel Init ######################## */
#ifndef __PROGRAM_START
#define __PROGRAM_START __main
#endif
#ifndef __INITIAL_SP
#define __INITIAL_SP Image$$ARM_LIB_STACK$$ZI$$Limit
#endif
#ifndef __STACK_LIMIT
#define __STACK_LIMIT Image$$ARM_LIB_STACK$$ZI$$Base
#endif
#ifndef __VECTOR_TABLE
#define __VECTOR_TABLE __Vectors
#endif
#ifndef __VECTOR_TABLE_ATTRIBUTE
#define __VECTOR_TABLE_ATTRIBUTE __attribute((used, section("RESET")))
#endif
/* ########################### Core Function Access ########################### */
/** \ingroup CMSIS_Core_FunctionInterface
\defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
@{
*/
/**
\brief Enable IRQ Interrupts
\details Enables IRQ interrupts by clearing the I-bit in the CPSR.
Can only be executed in Privileged modes.
*/
/* intrinsic void __enable_irq(); */
/**
\brief Disable IRQ Interrupts
\details Disables IRQ interrupts by setting the I-bit in the CPSR.
Can only be executed in Privileged modes.
*/
/* intrinsic void __disable_irq(); */
/**
\brief Get Control Register
\details Returns the content of the Control Register.
\return Control Register value
*/
__STATIC_INLINE uint32_t __get_CONTROL(void)
{
register uint32_t __regControl __ASM("control");
return(__regControl);
}
/**
\brief Set Control Register
\details Writes the given value to the Control Register.
\param [in] control Control Register value to set
*/
__STATIC_INLINE void __set_CONTROL(uint32_t control)
{
register uint32_t __regControl __ASM("control");
__regControl = control;
}
/**
\brief Get IPSR Register
\details Returns the content of the IPSR Register.
\return IPSR Register value
*/
__STATIC_INLINE uint32_t __get_IPSR(void)
{
register uint32_t __regIPSR __ASM("ipsr");
return(__regIPSR);
}
/**
\brief Get APSR Register
\details Returns the content of the APSR Register.
\return APSR Register value
*/
__STATIC_INLINE uint32_t __get_APSR(void)
{
register uint32_t __regAPSR __ASM("apsr");
return(__regAPSR);
}
/**
\brief Get xPSR Register
\details Returns the content of the xPSR Register.
\return xPSR Register value
*/
__STATIC_INLINE uint32_t __get_xPSR(void)
{
register uint32_t __regXPSR __ASM("xpsr");
return(__regXPSR);
}
/**
\brief Get Process Stack Pointer
\details Returns the current value of the Process Stack Pointer (PSP).
\return PSP Register value
*/
__STATIC_INLINE uint32_t __get_PSP(void)
{
register uint32_t __regProcessStackPointer __ASM("psp");
return(__regProcessStackPointer);
}
/**
\brief Set Process Stack Pointer
\details Assigns the given value to the Process Stack Pointer (PSP).
\param [in] topOfProcStack Process Stack Pointer value to set
*/
__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
{
register uint32_t __regProcessStackPointer __ASM("psp");
__regProcessStackPointer = topOfProcStack;
}
/**
\brief Get Main Stack Pointer
\details Returns the current value of the Main Stack Pointer (MSP).
\return MSP Register value
*/
__STATIC_INLINE uint32_t __get_MSP(void)
{
register uint32_t __regMainStackPointer __ASM("msp");
return(__regMainStackPointer);
}
/**
\brief Set Main Stack Pointer
\details Assigns the given value to the Main Stack Pointer (MSP).
\param [in] topOfMainStack Main Stack Pointer value to set
*/
__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
{
register uint32_t __regMainStackPointer __ASM("msp");
__regMainStackPointer = topOfMainStack;
}
/**
\brief Get Priority Mask
\details Returns the current state of the priority mask bit from the Priority Mask Register.
\return Priority Mask value
*/
__STATIC_INLINE uint32_t __get_PRIMASK(void)
{
register uint32_t __regPriMask __ASM("primask");
return(__regPriMask);
}
/**
\brief Set Priority Mask
\details Assigns the given value to the Priority Mask Register.
\param [in] priMask Priority Mask
*/
__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
{
register uint32_t __regPriMask __ASM("primask");
__regPriMask = (priMask);
}
#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
(defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
/**
\brief Enable FIQ
\details Enables FIQ interrupts by clearing the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
#define __enable_fault_irq __enable_fiq
/**
\brief Disable FIQ
\details Disables FIQ interrupts by setting the F-bit in the CPSR.
Can only be executed in Privileged modes.
*/
#define __disable_fault_irq __disable_fiq
/**
\brief Get Base Priority
\details Returns the current value of the Base Priority register.
\return Base Priority register value
*/
__STATIC_INLINE uint32_t __get_BASEPRI(void)
{
register uint32_t __regBasePri __ASM("basepri");
return(__regBasePri);
}
/**
\brief Set Base Priority
\details Assigns the given value to the Base Priority register.
\param [in] basePri Base Priority value to set
*/
__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
{
register uint32_t __regBasePri __ASM("basepri");
__regBasePri = (basePri & 0xFFU);
}
/**
\brief Set Base Priority with condition
\details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled,
or the new value increases the BASEPRI priority level.
\param [in] basePri Base Priority value to set
*/
__STATIC_INLINE void __set_BASEPRI_MAX(uint32_t basePri)
{
register uint32_t __regBasePriMax __ASM("basepri_max");
__regBasePriMax = (basePri & 0xFFU);
}
/**
\brief Get Fault Mask
\details Returns the current value of the Fault Mask register.
\return Fault Mask register value
*/
__STATIC_INLINE uint32_t __get_FAULTMASK(void)
{
register uint32_t __regFaultMask __ASM("faultmask");
return(__regFaultMask);
}
/**
\brief Set Fault Mask
\details Assigns the given value to the Fault Mask register.
\param [in] faultMask Fault Mask value to set
*/
__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
{
register uint32_t __regFaultMask __ASM("faultmask");
__regFaultMask = (faultMask & (uint32_t)1U);
}
#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
(defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */
/**
\brief Get FPSCR
\details Returns the current value of the Floating Point Status/Control register.
\return Floating Point Status/Control register value
*/
__STATIC_INLINE uint32_t __get_FPSCR(void)
{
#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
(defined (__FPU_USED ) && (__FPU_USED == 1U)) )
register uint32_t __regfpscr __ASM("fpscr");
return(__regfpscr);
#else
return(0U);
#endif
}
/**
\brief Set FPSCR
\details Assigns the given value to the Floating Point Status/Control register.
\param [in] fpscr Floating Point Status/Control value to set
*/
__STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
{
#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
(defined (__FPU_USED ) && (__FPU_USED == 1U)) )
register uint32_t __regfpscr __ASM("fpscr");
__regfpscr = (fpscr);
#else
(void)fpscr;
#endif
}
/*@} end of CMSIS_Core_RegAccFunctions */
/* ########################## Core Instruction Access ######################### */
/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
Access to dedicated instructions
@{
*/
/**
\brief No Operation
\details No Operation does nothing. This instruction can be used for code alignment purposes.
*/
#define __NOP __nop
/**
\brief Wait For Interrupt
\details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs.
*/
#define __WFI __wfi
/**
\brief Wait For Event
\details Wait For Event is a hint instruction that permits the processor to enter
a low-power state until one of a number of events occurs.
*/
#define __WFE __wfe
/**
\brief Send Event
\details Send Event is a hint instruction. It causes an event to be signaled to the CPU.
*/
#define __SEV __sev
/**
\brief Instruction Synchronization Barrier
\details Instruction Synchronization Barrier flushes the pipeline in the processor,
so that all instructions following the ISB are fetched from cache or memory,
after the instruction has been completed.
*/
#define __ISB() do {\
__schedule_barrier();\
__isb(0xF);\
__schedule_barrier();\
} while (0U)
/**
\brief Data Synchronization Barrier
\details Acts as a special kind of Data Memory Barrier.
It completes when all explicit memory accesses before this instruction complete.
*/
#define __DSB() do {\
__schedule_barrier();\
__dsb(0xF);\
__schedule_barrier();\
} while (0U)
/**
\brief Data Memory Barrier
\details Ensures the apparent order of the explicit memory operations before
and after the instruction, without ensuring their completion.
*/
#define __DMB() do {\
__schedule_barrier();\
__dmb(0xF);\
__schedule_barrier();\
} while (0U)
/**
\brief Reverse byte order (32 bit)
\details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412.
\param [in] value Value to reverse
\return Reversed value
*/
#define __REV __rev
/**
\brief Reverse byte order (16 bit)
\details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856.
\param [in] value Value to reverse
\return Reversed value
*/
#ifndef __NO_EMBEDDED_ASM
__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
{
rev16 r0, r0
bx lr
}
#endif
/**
\brief Reverse byte order (16 bit)
\details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000.
\param [in] value Value to reverse
\return Reversed value
*/
#ifndef __NO_EMBEDDED_ASM
__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int16_t __REVSH(int16_t value)
{
revsh r0, r0
bx lr
}
#endif
/**
\brief Rotate Right in unsigned value (32 bit)
\details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
\param [in] op1 Value to rotate
\param [in] op2 Number of Bits to rotate
\return Rotated value
*/
#define __ROR __ror
/**
\brief Breakpoint
\details Causes the processor to enter Debug state.
Debug tools can use this to investigate system state when the instruction at a particular address is reached.
\param [in] value is ignored by the processor.
If required, a debugger can use it to store additional information about the breakpoint.
*/
#define __BKPT(value) __breakpoint(value)
/**
\brief Reverse bit order of value
\details Reverses the bit order of the given value.
\param [in] value Value to reverse
\return Reversed value
*/
#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
(defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
#define __RBIT __rbit
#else
__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
{
uint32_t result;
uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */
result = value; /* r will be reversed bits of v; first get LSB of v */
for (value >>= 1U; value != 0U; value >>= 1U)
{
result <<= 1U;
result |= value & 1U;
s--;
}
result <<= s; /* shift when v's highest bits are zero */
return result;
}
#endif
/**
\brief Count leading zeros
\details Counts the number of leading zeros of a data value.
\param [in] value Value to count the leading zeros
\return number of leading zeros in value
*/
#define __CLZ __clz
#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
(defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
/**
\brief LDR Exclusive (8 bit)
\details Executes a exclusive LDR instruction for 8 bit value.
\param [in] ptr Pointer to data
\return value of type uint8_t at (*ptr)
*/
#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
#else
#define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop")
#endif
/**
\brief LDR Exclusive (16 bit)
\details Executes a exclusive LDR instruction for 16 bit values.
\param [in] ptr Pointer to data
\return value of type uint16_t at (*ptr)
*/
#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
#else
#define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop")
#endif
/**
\brief LDR Exclusive (32 bit)
\details Executes a exclusive LDR instruction for 32 bit values.
\param [in] ptr Pointer to data
\return value of type uint32_t at (*ptr)
*/
#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
#else
#define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop")
#endif
/**
\brief STR Exclusive (8 bit)
\details Executes a exclusive STR instruction for 8 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
#define __STREXB(value, ptr) __strex(value, ptr)
#else
#define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop")
#endif
/**
\brief STR Exclusive (16 bit)
\details Executes a exclusive STR instruction for 16 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
#define __STREXH(value, ptr) __strex(value, ptr)
#else
#define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop")
#endif
/**
\brief STR Exclusive (32 bit)
\details Executes a exclusive STR instruction for 32 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
\return 0 Function succeeded
\return 1 Function failed
*/
#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020)
#define __STREXW(value, ptr) __strex(value, ptr)
#else
#define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop")
#endif
/**
\brief Remove the exclusive lock
\details Removes the exclusive lock which is created by LDREX.
*/
#define __CLREX __clrex
/**
\brief Signed Saturate
\details Saturates a signed value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (1..32)
\return Saturated value
*/
#define __SSAT __ssat
/**
\brief Unsigned Saturate
\details Saturates an unsigned value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (0..31)
\return Saturated value
*/
#define __USAT __usat
/**
\brief Rotate Right with Extend (32 bit)
\details Moves each bit of a bitstring right by one bit.
The carry input is shifted in at the left end of the bitstring.
\param [in] value Value to rotate
\return Rotated value
*/
#ifndef __NO_EMBEDDED_ASM
__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value)
{
rrx r0, r0
bx lr
}
#endif
/**
\brief LDRT Unprivileged (8 bit)
\details Executes a Unprivileged LDRT instruction for 8 bit value.
\param [in] ptr Pointer to data
\return value of type uint8_t at (*ptr)
*/
#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr))
/**
\brief LDRT Unprivileged (16 bit)
\details Executes a Unprivileged LDRT instruction for 16 bit values.
\param [in] ptr Pointer to data
\return value of type uint16_t at (*ptr)
*/
#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr))
/**
\brief LDRT Unprivileged (32 bit)
\details Executes a Unprivileged LDRT instruction for 32 bit values.
\param [in] ptr Pointer to data
\return value of type uint32_t at (*ptr)
*/
#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr))
/**
\brief STRT Unprivileged (8 bit)
\details Executes a Unprivileged STRT instruction for 8 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
*/
#define __STRBT(value, ptr) __strt(value, ptr)
/**
\brief STRT Unprivileged (16 bit)
\details Executes a Unprivileged STRT instruction for 16 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
*/
#define __STRHT(value, ptr) __strt(value, ptr)
/**
\brief STRT Unprivileged (32 bit)
\details Executes a Unprivileged STRT instruction for 32 bit values.
\param [in] value Value to store
\param [in] ptr Pointer to location
*/
#define __STRT(value, ptr) __strt(value, ptr)
#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
(defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */
/**
\brief Signed Saturate
\details Saturates a signed value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (1..32)
\return Saturated value
*/
__attribute__((always_inline)) __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat)
{
if ((sat >= 1U) && (sat <= 32U))
{
const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U);
const int32_t min = -1 - max ;
if (val > max)
{
return max;
}
else if (val < min)
{
return min;
}
}
return val;
}
/**
\brief Unsigned Saturate
\details Saturates an unsigned value.
\param [in] value Value to be saturated
\param [in] sat Bit position to saturate to (0..31)
\return Saturated value
*/
__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat)
{
if (sat <= 31U)
{
const uint32_t max = ((1U << sat) - 1U);
if (val > (int32_t)max)
{
return max;
}
else if (val < 0)
{
return 0U;
}
}
return (uint32_t)val;
}
#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \
(defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */
/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
/* ################### Compiler specific Intrinsics ########################### */
/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
Access to dedicated SIMD instructions
@{
*/
#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) )
#define __SADD8 __sadd8
#define __QADD8 __qadd8
#define __SHADD8 __shadd8
#define __UADD8 __uadd8
#define __UQADD8 __uqadd8
#define __UHADD8 __uhadd8
#define __SSUB8 __ssub8
#define __QSUB8 __qsub8
#define __SHSUB8 __shsub8
#define __USUB8 __usub8
#define __UQSUB8 __uqsub8
#define __UHSUB8 __uhsub8
#define __SADD16 __sadd16
#define __QADD16 __qadd16
#define __SHADD16 __shadd16
#define __UADD16 __uadd16
#define __UQADD16 __uqadd16
#define __UHADD16 __uhadd16
#define __SSUB16 __ssub16
#define __QSUB16 __qsub16
#define __SHSUB16 __shsub16
#define __USUB16 __usub16
#define __UQSUB16 __uqsub16
#define __UHSUB16 __uhsub16
#define __SASX __sasx
#define __QASX __qasx
#define __SHASX __shasx
#define __UASX __uasx
#define __UQASX __uqasx
#define __UHASX __uhasx
#define __SSAX __ssax
#define __QSAX __qsax
#define __SHSAX __shsax
#define __USAX __usax
#define __UQSAX __uqsax
#define __UHSAX __uhsax
#define __USAD8 __usad8
#define __USADA8 __usada8
#define __SSAT16 __ssat16
#define __USAT16 __usat16
#define __UXTB16 __uxtb16
#define __UXTAB16 __uxtab16
#define __SXTB16 __sxtb16
#define __SXTAB16 __sxtab16
#define __SMUAD __smuad
#define __SMUADX __smuadx
#define __SMLAD __smlad
#define __SMLADX __smladx
#define __SMLALD __smlald
#define __SMLALDX __smlaldx
#define __SMUSD __smusd
#define __SMUSDX __smusdx
#define __SMLSD __smlsd
#define __SMLSDX __smlsdx
#define __SMLSLD __smlsld
#define __SMLSLDX __smlsldx
#define __SEL __sel
#define __QADD __qadd
#define __QSUB __qsub
#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \
((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) )
#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \
((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) )
#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \
((int64_t)(ARG3) << 32U) ) >> 32U))
#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */
/*@} end of group CMSIS_SIMD_intrinsics */
#endif /* __CMSIS_ARMCC_H */

View File

@@ -0,0 +1,283 @@
/**************************************************************************//**
* @file cmsis_compiler.h
* @brief CMSIS compiler generic header file
* @version V5.1.0
* @date 09. October 2018
******************************************************************************/
/*
* Copyright (c) 2009-2018 Arm Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CMSIS_COMPILER_H
#define __CMSIS_COMPILER_H
#include <stdint.h>
/*
* Arm Compiler 4/5
*/
#if defined ( __CC_ARM )
#include "cmsis_armcc.h"
/*
* Arm Compiler 6.6 LTM (armclang)
*/
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100)
#include "cmsis_armclang_ltm.h"
/*
* Arm Compiler above 6.10.1 (armclang)
*/
#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100)
#include "cmsis_armclang.h"
/*
* GNU Compiler
*/
#elif defined ( __GNUC__ )
#include "cmsis_gcc.h"
/*
* IAR Compiler
*/
#elif defined ( __ICCARM__ )
#include <cmsis_iccarm.h>
/*
* TI Arm Compiler
*/
#elif defined ( __TI_ARM__ )
#include <cmsis_ccs.h>
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __attribute__((packed))
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __attribute__((packed))
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __attribute__((packed))
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
struct __attribute__((packed)) T_UINT32 { uint32_t v; };
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#define __ALIGNED(x) __attribute__((aligned(x)))
#endif
#ifndef __RESTRICT
#define __RESTRICT __restrict
#endif
#ifndef __COMPILER_BARRIER
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored.
#define __COMPILER_BARRIER() (void)0
#endif
/*
* TASKING Compiler
*/
#elif defined ( __TASKING__ )
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all intrinsics,
* Including the CMSIS ones.
*/
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __packed__
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __packed__
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __packed__
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
struct __packed__ T_UINT32 { uint32_t v; };
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#define __ALIGNED(x) __align(x)
#endif
#ifndef __RESTRICT
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
#ifndef __COMPILER_BARRIER
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored.
#define __COMPILER_BARRIER() (void)0
#endif
/*
* COSMIC Compiler
*/
#elif defined ( __CSMC__ )
#include <cmsis_csm.h>
#ifndef __ASM
#define __ASM _asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __STATIC_INLINE
#endif
#ifndef __NO_RETURN
// NO RETURN is automatically detected hence no warning here
#define __NO_RETURN
#endif
#ifndef __USED
#warning No compiler specific solution for __USED. __USED is ignored.
#define __USED
#endif
#ifndef __WEAK
#define __WEAK __weak
#endif
#ifndef __PACKED
#define __PACKED @packed
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT @packed struct
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION @packed union
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
@packed struct T_UINT32 { uint32_t v; };
#define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
__PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
__PACKED_STRUCT T_UINT16_READ { uint16_t v; };
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
__PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
__PACKED_STRUCT T_UINT32_READ { uint32_t v; };
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
#ifndef __ALIGNED
#warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored.
#define __ALIGNED(x)
#endif
#ifndef __RESTRICT
#warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
#define __RESTRICT
#endif
#ifndef __COMPILER_BARRIER
#warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored.
#define __COMPILER_BARRIER() (void)0
#endif
#else
#error Unknown compiler.
#endif
#endif /* __CMSIS_COMPILER_H */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,964 @@
/**************************************************************************//**
* @file cmsis_iccarm.h
* @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file
* @version V5.1.0
* @date 08. May 2019
******************************************************************************/
//------------------------------------------------------------------------------
//
// Copyright (c) 2017-2019 IAR Systems
// Copyright (c) 2017-2019 Arm Limited. All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License")
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
//------------------------------------------------------------------------------
#ifndef __CMSIS_ICCARM_H__
#define __CMSIS_ICCARM_H__
#ifndef __ICCARM__
#error This file should only be compiled by ICCARM
#endif
#pragma system_include
#define __IAR_FT _Pragma("inline=forced") __intrinsic
#if (__VER__ >= 8000000)
#define __ICCARM_V8 1
#else
#define __ICCARM_V8 0
#endif
#ifndef __ALIGNED
#if __ICCARM_V8
#define __ALIGNED(x) __attribute__((aligned(x)))
#elif (__VER__ >= 7080000)
/* Needs IAR language extensions */
#define __ALIGNED(x) __attribute__((aligned(x)))
#else
#warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored.
#define __ALIGNED(x)
#endif
#endif
/* Define compiler macros for CPU architecture, used in CMSIS 5.
*/
#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__
/* Macros already defined */
#else
#if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__)
#define __ARM_ARCH_8M_MAIN__ 1
#elif defined(__ARM8M_BASELINE__)
#define __ARM_ARCH_8M_BASE__ 1
#elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M'
#if __ARM_ARCH == 6
#define __ARM_ARCH_6M__ 1
#elif __ARM_ARCH == 7
#if __ARM_FEATURE_DSP
#define __ARM_ARCH_7EM__ 1
#else
#define __ARM_ARCH_7M__ 1
#endif
#endif /* __ARM_ARCH */
#endif /* __ARM_ARCH_PROFILE == 'M' */
#endif
/* Alternativ core deduction for older ICCARM's */
#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \
!defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__)
#if defined(__ARM6M__) && (__CORE__ == __ARM6M__)
#define __ARM_ARCH_6M__ 1
#elif defined(__ARM7M__) && (__CORE__ == __ARM7M__)
#define __ARM_ARCH_7M__ 1
#elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__)
#define __ARM_ARCH_7EM__ 1
#elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__)
#define __ARM_ARCH_8M_BASE__ 1
#elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__)
#define __ARM_ARCH_8M_MAIN__ 1
#elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__)
#define __ARM_ARCH_8M_MAIN__ 1
#else
#error "Unknown target."
#endif
#endif
#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1
#define __IAR_M0_FAMILY 1
#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1
#define __IAR_M0_FAMILY 1
#else
#define __IAR_M0_FAMILY 0
#endif
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __COMPILER_BARRIER
#define __COMPILER_BARRIER() __ASM volatile("":::"memory")
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __NO_RETURN
#if __ICCARM_V8
#define __NO_RETURN __attribute__((__noreturn__))
#else
#define __NO_RETURN _Pragma("object_attribute=__noreturn")
#endif
#endif
#ifndef __PACKED
#if __ICCARM_V8
#define __PACKED __attribute__((packed, aligned(1)))
#else
/* Needs IAR language extensions */
#define __PACKED __packed
#endif
#endif
#ifndef __PACKED_STRUCT
#if __ICCARM_V8
#define __PACKED_STRUCT struct __attribute__((packed, aligned(1)))
#else
/* Needs IAR language extensions */
#define __PACKED_STRUCT __packed struct
#endif
#endif
#ifndef __PACKED_UNION
#if __ICCARM_V8
#define __PACKED_UNION union __attribute__((packed, aligned(1)))
#else
/* Needs IAR language extensions */
#define __PACKED_UNION __packed union
#endif
#endif
#ifndef __RESTRICT
#if __ICCARM_V8
#define __RESTRICT __restrict
#else
/* Needs IAR language extensions */
#define __RESTRICT restrict
#endif
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __FORCEINLINE
#define __FORCEINLINE _Pragma("inline=forced")
#endif
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE
#endif
#ifndef __UNALIGNED_UINT16_READ
#pragma language=save
#pragma language=extended
__IAR_FT uint16_t __iar_uint16_read(void const *ptr)
{
return *(__packed uint16_t*)(ptr);
}
#pragma language=restore
#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR)
#endif
#ifndef __UNALIGNED_UINT16_WRITE
#pragma language=save
#pragma language=extended
__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val)
{
*(__packed uint16_t*)(ptr) = val;;
}
#pragma language=restore
#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL)
#endif
#ifndef __UNALIGNED_UINT32_READ
#pragma language=save
#pragma language=extended
__IAR_FT uint32_t __iar_uint32_read(void const *ptr)
{
return *(__packed uint32_t*)(ptr);
}
#pragma language=restore
#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
#pragma language=save
#pragma language=extended
__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val)
{
*(__packed uint32_t*)(ptr) = val;;
}
#pragma language=restore
#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL)
#endif
#ifndef __UNALIGNED_UINT32 /* deprecated */
#pragma language=save
#pragma language=extended
__packed struct __iar_u32 { uint32_t v; };
#pragma language=restore
#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v)
#endif
#ifndef __USED
#if __ICCARM_V8
#define __USED __attribute__((used))
#else
#define __USED _Pragma("__root")
#endif
#endif
#ifndef __WEAK
#if __ICCARM_V8
#define __WEAK __attribute__((weak))
#else
#define __WEAK _Pragma("__weak")
#endif
#endif
#ifndef __PROGRAM_START
#define __PROGRAM_START __iar_program_start
#endif
#ifndef __INITIAL_SP
#define __INITIAL_SP CSTACK$$Limit
#endif
#ifndef __STACK_LIMIT
#define __STACK_LIMIT CSTACK$$Base
#endif
#ifndef __VECTOR_TABLE
#define __VECTOR_TABLE __vector_table
#endif
#ifndef __VECTOR_TABLE_ATTRIBUTE
#define __VECTOR_TABLE_ATTRIBUTE @".intvec"
#endif
#ifndef __ICCARM_INTRINSICS_VERSION__
#define __ICCARM_INTRINSICS_VERSION__ 0
#endif
#if __ICCARM_INTRINSICS_VERSION__ == 2
#if defined(__CLZ)
#undef __CLZ
#endif
#if defined(__REVSH)
#undef __REVSH
#endif
#if defined(__RBIT)
#undef __RBIT
#endif
#if defined(__SSAT)
#undef __SSAT
#endif
#if defined(__USAT)
#undef __USAT
#endif
#include "iccarm_builtin.h"
#define __disable_fault_irq __iar_builtin_disable_fiq
#define __disable_irq __iar_builtin_disable_interrupt
#define __enable_fault_irq __iar_builtin_enable_fiq
#define __enable_irq __iar_builtin_enable_interrupt
#define __arm_rsr __iar_builtin_rsr
#define __arm_wsr __iar_builtin_wsr
#define __get_APSR() (__arm_rsr("APSR"))
#define __get_BASEPRI() (__arm_rsr("BASEPRI"))
#define __get_CONTROL() (__arm_rsr("CONTROL"))
#define __get_FAULTMASK() (__arm_rsr("FAULTMASK"))
#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
(defined (__FPU_USED ) && (__FPU_USED == 1U)) )
#define __get_FPSCR() (__arm_rsr("FPSCR"))
#define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE)))
#else
#define __get_FPSCR() ( 0 )
#define __set_FPSCR(VALUE) ((void)VALUE)
#endif
#define __get_IPSR() (__arm_rsr("IPSR"))
#define __get_MSP() (__arm_rsr("MSP"))
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure MSPLIM is RAZ/WI
#define __get_MSPLIM() (0U)
#else
#define __get_MSPLIM() (__arm_rsr("MSPLIM"))
#endif
#define __get_PRIMASK() (__arm_rsr("PRIMASK"))
#define __get_PSP() (__arm_rsr("PSP"))
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure PSPLIM is RAZ/WI
#define __get_PSPLIM() (0U)
#else
#define __get_PSPLIM() (__arm_rsr("PSPLIM"))
#endif
#define __get_xPSR() (__arm_rsr("xPSR"))
#define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE)))
#define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE)))
#define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE)))
#define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE)))
#define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE)))
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure MSPLIM is RAZ/WI
#define __set_MSPLIM(VALUE) ((void)(VALUE))
#else
#define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE)))
#endif
#define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE)))
#define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE)))
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure PSPLIM is RAZ/WI
#define __set_PSPLIM(VALUE) ((void)(VALUE))
#else
#define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE)))
#endif
#define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS"))
#define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE)))
#define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS"))
#define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE)))
#define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS"))
#define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE)))
#define __TZ_get_SP_NS() (__arm_rsr("SP_NS"))
#define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE)))
#define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS"))
#define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE)))
#define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS"))
#define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE)))
#define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS"))
#define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE)))
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure PSPLIM is RAZ/WI
#define __TZ_get_PSPLIM_NS() (0U)
#define __TZ_set_PSPLIM_NS(VALUE) ((void)(VALUE))
#else
#define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS"))
#define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE)))
#endif
#define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS"))
#define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE)))
#define __NOP __iar_builtin_no_operation
#define __CLZ __iar_builtin_CLZ
#define __CLREX __iar_builtin_CLREX
#define __DMB __iar_builtin_DMB
#define __DSB __iar_builtin_DSB
#define __ISB __iar_builtin_ISB
#define __LDREXB __iar_builtin_LDREXB
#define __LDREXH __iar_builtin_LDREXH
#define __LDREXW __iar_builtin_LDREX
#define __RBIT __iar_builtin_RBIT
#define __REV __iar_builtin_REV
#define __REV16 __iar_builtin_REV16
__IAR_FT int16_t __REVSH(int16_t val)
{
return (int16_t) __iar_builtin_REVSH(val);
}
#define __ROR __iar_builtin_ROR
#define __RRX __iar_builtin_RRX
#define __SEV __iar_builtin_SEV
#if !__IAR_M0_FAMILY
#define __SSAT __iar_builtin_SSAT
#endif
#define __STREXB __iar_builtin_STREXB
#define __STREXH __iar_builtin_STREXH
#define __STREXW __iar_builtin_STREX
#if !__IAR_M0_FAMILY
#define __USAT __iar_builtin_USAT
#endif
#define __WFE __iar_builtin_WFE
#define __WFI __iar_builtin_WFI
#if __ARM_MEDIA__
#define __SADD8 __iar_builtin_SADD8
#define __QADD8 __iar_builtin_QADD8
#define __SHADD8 __iar_builtin_SHADD8
#define __UADD8 __iar_builtin_UADD8
#define __UQADD8 __iar_builtin_UQADD8
#define __UHADD8 __iar_builtin_UHADD8
#define __SSUB8 __iar_builtin_SSUB8
#define __QSUB8 __iar_builtin_QSUB8
#define __SHSUB8 __iar_builtin_SHSUB8
#define __USUB8 __iar_builtin_USUB8
#define __UQSUB8 __iar_builtin_UQSUB8
#define __UHSUB8 __iar_builtin_UHSUB8
#define __SADD16 __iar_builtin_SADD16
#define __QADD16 __iar_builtin_QADD16
#define __SHADD16 __iar_builtin_SHADD16
#define __UADD16 __iar_builtin_UADD16
#define __UQADD16 __iar_builtin_UQADD16
#define __UHADD16 __iar_builtin_UHADD16
#define __SSUB16 __iar_builtin_SSUB16
#define __QSUB16 __iar_builtin_QSUB16
#define __SHSUB16 __iar_builtin_SHSUB16
#define __USUB16 __iar_builtin_USUB16
#define __UQSUB16 __iar_builtin_UQSUB16
#define __UHSUB16 __iar_builtin_UHSUB16
#define __SASX __iar_builtin_SASX
#define __QASX __iar_builtin_QASX
#define __SHASX __iar_builtin_SHASX
#define __UASX __iar_builtin_UASX
#define __UQASX __iar_builtin_UQASX
#define __UHASX __iar_builtin_UHASX
#define __SSAX __iar_builtin_SSAX
#define __QSAX __iar_builtin_QSAX
#define __SHSAX __iar_builtin_SHSAX
#define __USAX __iar_builtin_USAX
#define __UQSAX __iar_builtin_UQSAX
#define __UHSAX __iar_builtin_UHSAX
#define __USAD8 __iar_builtin_USAD8
#define __USADA8 __iar_builtin_USADA8
#define __SSAT16 __iar_builtin_SSAT16
#define __USAT16 __iar_builtin_USAT16
#define __UXTB16 __iar_builtin_UXTB16
#define __UXTAB16 __iar_builtin_UXTAB16
#define __SXTB16 __iar_builtin_SXTB16
#define __SXTAB16 __iar_builtin_SXTAB16
#define __SMUAD __iar_builtin_SMUAD
#define __SMUADX __iar_builtin_SMUADX
#define __SMMLA __iar_builtin_SMMLA
#define __SMLAD __iar_builtin_SMLAD
#define __SMLADX __iar_builtin_SMLADX
#define __SMLALD __iar_builtin_SMLALD
#define __SMLALDX __iar_builtin_SMLALDX
#define __SMUSD __iar_builtin_SMUSD
#define __SMUSDX __iar_builtin_SMUSDX
#define __SMLSD __iar_builtin_SMLSD
#define __SMLSDX __iar_builtin_SMLSDX
#define __SMLSLD __iar_builtin_SMLSLD
#define __SMLSLDX __iar_builtin_SMLSLDX
#define __SEL __iar_builtin_SEL
#define __QADD __iar_builtin_QADD
#define __QSUB __iar_builtin_QSUB
#define __PKHBT __iar_builtin_PKHBT
#define __PKHTB __iar_builtin_PKHTB
#endif
#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */
#if __IAR_M0_FAMILY
/* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */
#define __CLZ __cmsis_iar_clz_not_active
#define __SSAT __cmsis_iar_ssat_not_active
#define __USAT __cmsis_iar_usat_not_active
#define __RBIT __cmsis_iar_rbit_not_active
#define __get_APSR __cmsis_iar_get_APSR_not_active
#endif
#if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
(defined (__FPU_USED ) && (__FPU_USED == 1U)) ))
#define __get_FPSCR __cmsis_iar_get_FPSR_not_active
#define __set_FPSCR __cmsis_iar_set_FPSR_not_active
#endif
#ifdef __INTRINSICS_INCLUDED
#error intrinsics.h is already included previously!
#endif
#include <intrinsics.h>
#if __IAR_M0_FAMILY
/* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */
#undef __CLZ
#undef __SSAT
#undef __USAT
#undef __RBIT
#undef __get_APSR
__STATIC_INLINE uint8_t __CLZ(uint32_t data)
{
if (data == 0U) { return 32U; }
uint32_t count = 0U;
uint32_t mask = 0x80000000U;
while ((data & mask) == 0U)
{
count += 1U;
mask = mask >> 1U;
}
return count;
}
__STATIC_INLINE uint32_t __RBIT(uint32_t v)
{
uint8_t sc = 31U;
uint32_t r = v;
for (v >>= 1U; v; v >>= 1U)
{
r <<= 1U;
r |= v & 1U;
sc--;
}
return (r << sc);
}
__STATIC_INLINE uint32_t __get_APSR(void)
{
uint32_t res;
__asm("MRS %0,APSR" : "=r" (res));
return res;
}
#endif
#if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \
(defined (__FPU_USED ) && (__FPU_USED == 1U)) ))
#undef __get_FPSCR
#undef __set_FPSCR
#define __get_FPSCR() (0)
#define __set_FPSCR(VALUE) ((void)VALUE)
#endif
#pragma diag_suppress=Pe940
#pragma diag_suppress=Pe177
#define __enable_irq __enable_interrupt
#define __disable_irq __disable_interrupt
#define __NOP __no_operation
#define __get_xPSR __get_PSR
#if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0)
__IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr)
{
return __LDREX((unsigned long *)ptr);
}
__IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr)
{
return __STREX(value, (unsigned long *)ptr);
}
#endif
/* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */
#if (__CORTEX_M >= 0x03)
__IAR_FT uint32_t __RRX(uint32_t value)
{
uint32_t result;
__ASM("RRX %0, %1" : "=r"(result) : "r" (value) : "cc");
return(result);
}
__IAR_FT void __set_BASEPRI_MAX(uint32_t value)
{
__asm volatile("MSR BASEPRI_MAX,%0"::"r" (value));
}
#define __enable_fault_irq __enable_fiq
#define __disable_fault_irq __disable_fiq
#endif /* (__CORTEX_M >= 0x03) */
__IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2)
{
return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2));
}
#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
(defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) )
__IAR_FT uint32_t __get_MSPLIM(void)
{
uint32_t res;
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure MSPLIM is RAZ/WI
res = 0U;
#else
__asm volatile("MRS %0,MSPLIM" : "=r" (res));
#endif
return res;
}
__IAR_FT void __set_MSPLIM(uint32_t value)
{
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure MSPLIM is RAZ/WI
(void)value;
#else
__asm volatile("MSR MSPLIM,%0" :: "r" (value));
#endif
}
__IAR_FT uint32_t __get_PSPLIM(void)
{
uint32_t res;
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure PSPLIM is RAZ/WI
res = 0U;
#else
__asm volatile("MRS %0,PSPLIM" : "=r" (res));
#endif
return res;
}
__IAR_FT void __set_PSPLIM(uint32_t value)
{
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure PSPLIM is RAZ/WI
(void)value;
#else
__asm volatile("MSR PSPLIM,%0" :: "r" (value));
#endif
}
__IAR_FT uint32_t __TZ_get_CONTROL_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,CONTROL_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_CONTROL_NS(uint32_t value)
{
__asm volatile("MSR CONTROL_NS,%0" :: "r" (value));
}
__IAR_FT uint32_t __TZ_get_PSP_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,PSP_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_PSP_NS(uint32_t value)
{
__asm volatile("MSR PSP_NS,%0" :: "r" (value));
}
__IAR_FT uint32_t __TZ_get_MSP_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,MSP_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_MSP_NS(uint32_t value)
{
__asm volatile("MSR MSP_NS,%0" :: "r" (value));
}
__IAR_FT uint32_t __TZ_get_SP_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,SP_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_SP_NS(uint32_t value)
{
__asm volatile("MSR SP_NS,%0" :: "r" (value));
}
__IAR_FT uint32_t __TZ_get_PRIMASK_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,PRIMASK_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value)
{
__asm volatile("MSR PRIMASK_NS,%0" :: "r" (value));
}
__IAR_FT uint32_t __TZ_get_BASEPRI_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,BASEPRI_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value)
{
__asm volatile("MSR BASEPRI_NS,%0" :: "r" (value));
}
__IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value)
{
__asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value));
}
__IAR_FT uint32_t __TZ_get_PSPLIM_NS(void)
{
uint32_t res;
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure PSPLIM is RAZ/WI
res = 0U;
#else
__asm volatile("MRS %0,PSPLIM_NS" : "=r" (res));
#endif
return res;
}
__IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value)
{
#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \
(!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3)))
// without main extensions, the non-secure PSPLIM is RAZ/WI
(void)value;
#else
__asm volatile("MSR PSPLIM_NS,%0" :: "r" (value));
#endif
}
__IAR_FT uint32_t __TZ_get_MSPLIM_NS(void)
{
uint32_t res;
__asm volatile("MRS %0,MSPLIM_NS" : "=r" (res));
return res;
}
__IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value)
{
__asm volatile("MSR MSPLIM_NS,%0" :: "r" (value));
}
#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */
#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */
#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value))
#if __IAR_M0_FAMILY
__STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat)
{
if ((sat >= 1U) && (sat <= 32U))
{
const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U);
const int32_t min = -1 - max ;
if (val > max)
{
return max;
}
else if (val < min)
{
return min;
}
}
return val;
}
__STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat)
{
if (sat <= 31U)
{
const uint32_t max = ((1U << sat) - 1U);
if (val > (int32_t)max)
{
return max;
}
else if (val < 0)
{
return 0U;
}
}
return (uint32_t)val;
}
#endif
#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */
__IAR_FT uint8_t __LDRBT(volatile uint8_t *addr)
{
uint32_t res;
__ASM("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory");
return ((uint8_t)res);
}
__IAR_FT uint16_t __LDRHT(volatile uint16_t *addr)
{
uint32_t res;
__ASM("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory");
return ((uint16_t)res);
}
__IAR_FT uint32_t __LDRT(volatile uint32_t *addr)
{
uint32_t res;
__ASM("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory");
return res;
}
__IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr)
{
__ASM("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory");
}
__IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr)
{
__ASM("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory");
}
__IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr)
{
__ASM("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory");
}
#endif /* (__CORTEX_M >= 0x03) */
#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \
(defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) )
__IAR_FT uint8_t __LDAB(volatile uint8_t *ptr)
{
uint32_t res;
__ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory");
return ((uint8_t)res);
}
__IAR_FT uint16_t __LDAH(volatile uint16_t *ptr)
{
uint32_t res;
__ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory");
return ((uint16_t)res);
}
__IAR_FT uint32_t __LDA(volatile uint32_t *ptr)
{
uint32_t res;
__ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (ptr) : "memory");
return res;
}
__IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr)
{
__ASM volatile ("STLB %1, [%0]" :: "r" (ptr), "r" (value) : "memory");
}
__IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr)
{
__ASM volatile ("STLH %1, [%0]" :: "r" (ptr), "r" (value) : "memory");
}
__IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr)
{
__ASM volatile ("STL %1, [%0]" :: "r" (ptr), "r" (value) : "memory");
}
__IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr)
{
uint32_t res;
__ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory");
return ((uint8_t)res);
}
__IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr)
{
uint32_t res;
__ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory");
return ((uint16_t)res);
}
__IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr)
{
uint32_t res;
__ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (ptr) : "memory");
return res;
}
__IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr)
{
uint32_t res;
__ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory");
return res;
}
__IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr)
{
uint32_t res;
__ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory");
return res;
}
__IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr)
{
uint32_t res;
__ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory");
return res;
}
#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */
#undef __IAR_FT
#undef __IAR_M0_FAMILY
#undef __ICCARM_V8
#pragma diag_default=Pe940
#pragma diag_default=Pe177
#endif /* __CMSIS_ICCARM_H__ */

View File

@@ -0,0 +1,39 @@
/**************************************************************************//**
* @file cmsis_version.h
* @brief CMSIS Core(M) Version definitions
* @version V5.0.3
* @date 24. June 2019
******************************************************************************/
/*
* Copyright (c) 2009-2019 ARM Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#if defined ( __ICCARM__ )
#pragma system_include /* treat file as system include file for MISRA check */
#elif defined (__clang__)
#pragma clang system_header /* treat file as system include file */
#endif
#ifndef __CMSIS_VERSION_H
#define __CMSIS_VERSION_H
/* CMSIS Version definitions */
#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */
#define __CM_CMSIS_VERSION_SUB ( 3U) /*!< [15:0] CMSIS Core(M) sub version */
#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \
__CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */
#endif

Some files were not shown because too many files have changed in this diff Show More