parent
9bbed9f1c4
commit
58afb1e8a5
File diff suppressed because one or more lines are too long
@ -1,52 +0,0 @@ |
||||
/* USER CODE BEGIN Header */ |
||||
/**
|
||||
****************************************************************************** |
||||
* @file rtc.h |
||||
* @brief This file contains all the function prototypes for |
||||
* the rtc.c file |
||||
****************************************************************************** |
||||
* @attention |
||||
* |
||||
* Copyright (c) 2023 STMicroelectronics. |
||||
* All rights reserved. |
||||
* |
||||
* This software is licensed under terms that can be found in the LICENSE file |
||||
* in the root directory of this software component. |
||||
* If no LICENSE file comes with this software, it is provided AS-IS. |
||||
* |
||||
****************************************************************************** |
||||
*/ |
||||
/* USER CODE END Header */ |
||||
/* Define to prevent recursive inclusion -------------------------------------*/ |
||||
#ifndef __RTC_H__ |
||||
#define __RTC_H__ |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Includes ------------------------------------------------------------------*/ |
||||
#include "main.h" |
||||
|
||||
/* USER CODE BEGIN Includes */ |
||||
|
||||
/* USER CODE END Includes */ |
||||
|
||||
extern RTC_HandleTypeDef hrtc; |
||||
|
||||
/* USER CODE BEGIN Private defines */ |
||||
|
||||
/* USER CODE END Private defines */ |
||||
|
||||
void MX_RTC_Init(void); |
||||
|
||||
/* USER CODE BEGIN Prototypes */ |
||||
|
||||
/* USER CODE END Prototypes */ |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* __RTC_H__ */ |
||||
|
@ -0,0 +1,210 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#include "main.h" |
||||
#include <stdbool.h> |
||||
#include <stdint.h> |
||||
#include <string.h> |
||||
#include "app_analog.h" |
||||
#include "adc.h" |
||||
|
||||
/* DMA dest */ |
||||
static volatile uint16_t adc_values[4]; |
||||
|
||||
const float V_REFINT = 1.23f; |
||||
|
||||
#define AVERAGEBUF_DEPTH 16 |
||||
#define OVENTEMP_HISTORY_DEPTH 10 |
||||
|
||||
static struct App { |
||||
float oven_temp; |
||||
float soc_temp; |
||||
float v_sensor; |
||||
uint16_t adc_averagebuf[AVERAGEBUF_DEPTH * 4]; |
||||
uint8_t averagebuf_ptr; |
||||
float adc_averages[4]; |
||||
float oventemp_history[OVENTEMP_HISTORY_DEPTH]; |
||||
uint8_t oventemp_history_ptr; |
||||
} s_analog = {}; |
||||
|
||||
#define TSENSE_LOOKUP_LEN 101 |
||||
#define TSENSE_T_STEP 5.0f |
||||
#define TSENSE_T_MIN 0.0f |
||||
#define TSENSE_T_MAX 500.0f |
||||
static const float TSENSE_LOOKUP[TSENSE_LOOKUP_LEN] = { |
||||
0.092678405931418f, |
||||
0.0943174479327356f, |
||||
0.095948157844312f, |
||||
0.0975706768542549f, |
||||
0.0991848957506647f, |
||||
0.100791037522732f, |
||||
0.102388993070241f, |
||||
0.103978983136042f, |
||||
0.105560980458654f, |
||||
0.107135039851509f, |
||||
0.108701215616829f, |
||||
0.110259642413441f, |
||||
0.111810211533421f, |
||||
0.113353137226489f, |
||||
0.114888310929339f, |
||||
0.11641594480226f, |
||||
0.117936009906507f, |
||||
0.119448557132363f, |
||||
0.120953636903929f, |
||||
0.122451377845456f, |
||||
0.12394167187544f, |
||||
0.125424725109556f, |
||||
0.126900429638119f, |
||||
0.128368989630084f, |
||||
0.129830374697352f, |
||||
0.131284632150064f, |
||||
0.132731808872517f, |
||||
0.134172027901771f, |
||||
0.135605181883591f, |
||||
0.13703146935069f, |
||||
0.138450783142958f, |
||||
0.139863319976468f, |
||||
0.14126904821384f, |
||||
0.142668011892657f, |
||||
0.144060254660872f, |
||||
0.145445894373796f, |
||||
0.146824824486877f, |
||||
0.14819723645253f, |
||||
0.149563023938454f, |
||||
0.150922376699229f, |
||||
0.15227526202401f, |
||||
0.153621720954182f, |
||||
0.15496179417407f, |
||||
0.156295594725426f, |
||||
0.157623016940038f, |
||||
0.158944245649448f, |
||||
0.160259175412251f, |
||||
0.16156798947087f, |
||||
0.162870654195634f, |
||||
0.164167207880495f, |
||||
0.165457688491696f, |
||||
0.166742204592451f, |
||||
0.168020651444079f, |
||||
0.169293207677971f, |
||||
0.170559768793747f, |
||||
0.171820511933356f, |
||||
0.173075402684405f, |
||||
0.174324476817747f, |
||||
0.175567769803026f, |
||||
0.176805386030345f, |
||||
0.178037221732226f, |
||||
0.179263449725904f, |
||||
0.180483966491086f, |
||||
0.181698943447122f, |
||||
0.182908345518766f, |
||||
0.184112206156428f, |
||||
0.185310558533273f, |
||||
0.186503503145257f, |
||||
0.187690937227925f, |
||||
0.188873028139146f, |
||||
0.190049673368296f, |
||||
0.191221038959601f, |
||||
0.192387089280576f, |
||||
0.193547855644572f, |
||||
0.194703369109397f, |
||||
0.195853726532112f, |
||||
0.196998826174689f, |
||||
0.19813883026229f, |
||||
0.199273637315452f, |
||||
0.200403408323351f, |
||||
0.201528107189346f, |
||||
0.20264776325594f, |
||||
0.203762405629782f, |
||||
0.204872127762998f, |
||||
0.205976828960191f, |
||||
0.207076666615101f, |
||||
0.208171540293999f, |
||||
0.209261606226334f, |
||||
0.210346827933364f, |
||||
0.211427232937629f, |
||||
0.212502848543705f, |
||||
0.213573765013592f, |
||||
0.214639882704581f, |
||||
0.215701354457324f, |
||||
0.216758080892489f, |
||||
0.217810213752734f, |
||||
0.218857716249547f, |
||||
0.219900614222686f, |
||||
0.220938933310224f, |
||||
0.221972760781578f, |
||||
0.223001998051553f, |
||||
}; |
||||
|
||||
void app_analog_init() |
||||
{ |
||||
HAL_ADCEx_Calibration_Start(&hadc1); |
||||
|
||||
/* Start periodic reading of the ADC channels */ |
||||
HAL_ADC_Start_DMA(&hadc1, (uint32_t *) (void *) adc_values, 4); |
||||
} |
||||
|
||||
static float val_to_c(float val) |
||||
{ |
||||
// TODO use binary search.. lol
|
||||
for (int i = 1; i < TSENSE_LOOKUP_LEN; i++) { |
||||
float cur = TSENSE_LOOKUP[i]; |
||||
if (cur >= val) { |
||||
float prev = TSENSE_LOOKUP[i - 1]; |
||||
|
||||
float ratio = (val - prev) / (cur - prev); |
||||
return TSENSE_T_MIN + ((float) i + ratio) * TSENSE_T_STEP; |
||||
} |
||||
} |
||||
return TSENSE_T_MAX; |
||||
} |
||||
|
||||
float app_analog_get_temp() |
||||
{ |
||||
uint32_t sums[4] = {}; |
||||
for (int i = 0; i < AVERAGEBUF_DEPTH * 4; i += 4) { |
||||
sums[0] += s_analog.adc_averagebuf[i]; |
||||
sums[1] += s_analog.adc_averagebuf[i + 1]; |
||||
sums[2] += s_analog.adc_averagebuf[i + 2]; |
||||
sums[3] += s_analog.adc_averagebuf[i + 3]; |
||||
} |
||||
s_analog.adc_averages[0] = (float) sums[0] / AVERAGEBUF_DEPTH; |
||||
s_analog.adc_averages[1] = (float) sums[1] / AVERAGEBUF_DEPTH; |
||||
s_analog.adc_averages[2] = (float) sums[2] / AVERAGEBUF_DEPTH; |
||||
s_analog.adc_averages[3] = (float) sums[3] / AVERAGEBUF_DEPTH; |
||||
|
||||
/* r_pt100, r_ref, internal_temp, v_ref_int */ |
||||
float refint = s_analog.adc_averages[3]; |
||||
float scale = V_REFINT / refint; |
||||
|
||||
const float avg_slope = 4.3f * scale; |
||||
const float v25 = 1.43f; |
||||
const float v_tsen = s_analog.adc_averages[2] * scale; |
||||
|
||||
s_analog.soc_temp = (v25 - v_tsen) / avg_slope + 25.f; |
||||
s_analog.v_sensor = s_analog.adc_averages[0] * scale; // good for debug/tuning
|
||||
|
||||
|
||||
// using a voltage divider, so assuming the reference resistor is measured well,
|
||||
// we can just use the ratio and the exact voltage value is not important.
|
||||
float actual_temp = val_to_c(s_analog.adc_averages[0] / s_analog.adc_averages[1]); |
||||
|
||||
s_analog.oventemp_history[s_analog.oventemp_history_ptr] = actual_temp; |
||||
s_analog.oventemp_history_ptr = (s_analog.oventemp_history_ptr + 1) % OVENTEMP_HISTORY_DEPTH; |
||||
|
||||
float sum = 0; |
||||
for (int i = 0; i < OVENTEMP_HISTORY_DEPTH; i++) { |
||||
sum += s_analog.oventemp_history[i]; |
||||
} |
||||
sum /= OVENTEMP_HISTORY_DEPTH; |
||||
s_analog.oven_temp = sum; |
||||
|
||||
return s_analog.oven_temp; |
||||
} |
||||
|
||||
void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef *hadc) |
||||
{ |
||||
// notify
|
||||
memcpy((void *) &s_analog.adc_averagebuf[s_analog.averagebuf_ptr * 4], (const void *) adc_values, 8); |
||||
s_analog.averagebuf_ptr = (s_analog.averagebuf_ptr + 1) % AVERAGEBUF_DEPTH; |
||||
} |
@ -0,0 +1,19 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#ifndef BLUEPILLTROUBA_APP_ANALOG_H |
||||
#define BLUEPILLTROUBA_APP_ANALOG_H |
||||
|
||||
void app_analog_init(); |
||||
|
||||
/**
|
||||
* Get current oven temp. |
||||
* |
||||
* A slow float calculation is done here - call only when needed, at a roughly constant rate (e.g. 1s) to make smoothing work properly. |
||||
* |
||||
* @return the value in celsius |
||||
*/ |
||||
float app_analog_get_temp(); |
||||
|
||||
#endif //BLUEPILLTROUBA_APP_ANALOG_H
|
@ -0,0 +1,25 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#include "main.h" |
||||
#include "app_buzzer.h" |
||||
#include "tim.h" |
||||
#include "FreeRTOS.h" |
||||
#include "task.h" |
||||
|
||||
void app_buzzer_init() |
||||
{ |
||||
/* Enable buzzer PWM */ |
||||
HAL_TIM_PWM_Start(&htim2, TIM_CHANNEL_1); |
||||
} |
||||
|
||||
void app_buzzer_beep() { |
||||
|
||||
// TODO make this non-blocking
|
||||
TIM2->ARR = 25714; |
||||
TIM2->CCR1 = TIM2->ARR/2; |
||||
vTaskDelay(50); |
||||
TIM2->CCR1 = 0; |
||||
vTaskDelay(50); |
||||
} |
@ -0,0 +1,13 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#ifndef BLUEPILLTROUBA_APP_BUZZER_H |
||||
#define BLUEPILLTROUBA_APP_BUZZER_H |
||||
|
||||
void app_buzzer_init(); |
||||
|
||||
|
||||
void app_buzzer_beep(); |
||||
|
||||
#endif //BLUEPILLTROUBA_APP_BUZZER_H
|
@ -0,0 +1,25 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#include "main.h" |
||||
#include "app_heater.h" |
||||
#include "tim.h" |
||||
|
||||
void app_heater_init() |
||||
{ |
||||
HAL_TIM_PWM_Start(&htim3, TIM_CHANNEL_1); |
||||
TIM3->ARR = 25714; |
||||
} |
||||
|
||||
|
||||
void app_heater_set(bool active) |
||||
{ |
||||
if (active) { |
||||
TIM3->CCR1 = TIM3->ARR / 2; // testing - 50%
|
||||
} else { |
||||
TIM3->CCR1 = 0; |
||||
} |
||||
|
||||
//HAL_GPIO_WritePin(HEATER_GPIO_Port, HEATER_Pin, active);
|
||||
} |
@ -0,0 +1,14 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#ifndef BLUEPILLTROUBA_APP_HEATER_H |
||||
#define BLUEPILLTROUBA_APP_HEATER_H |
||||
|
||||
#include <stdbool.h> |
||||
|
||||
void app_heater_init(); |
||||
|
||||
void app_heater_set(bool active); |
||||
|
||||
#endif //BLUEPILLTROUBA_APP_HEATER_H
|
@ -0,0 +1,23 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#include <stdbool.h> |
||||
#include "main.h" |
||||
#include "app_knob.h" |
||||
#include "tim.h" |
||||
|
||||
static struct { |
||||
uint16_t wheel; |
||||
bool push; |
||||
} s_knob = {}; |
||||
|
||||
void app_knob_init() |
||||
{ |
||||
/* Enable the rotary encoder */ |
||||
HAL_TIM_Encoder_Start(&htim4, TIM_CHANNEL_ALL); |
||||
} |
||||
|
||||
uint16_t app_knob_get_raw() { |
||||
return htim4.Instance->CNT; |
||||
} |
@ -0,0 +1,12 @@ |
||||
/**
|
||||
* TODO file description |
||||
*/ |
||||
|
||||
#ifndef BLUEPILLTROUBA_APP_KNOB_H |
||||
#define BLUEPILLTROUBA_APP_KNOB_H |
||||
|
||||
void app_knob_init(); |
||||
|
||||
uint16_t app_knob_get_raw(); |
||||
|
||||
#endif //BLUEPILLTROUBA_APP_KNOB_H
|
@ -0,0 +1,108 @@ |
||||
#include "app_pid.h" |
||||
#include <stdbool.h> |
||||
#include <stdint.h> |
||||
#include <FreeRTOS.h> |
||||
#include <task.h> |
||||
|
||||
static void clampOutput(struct PID *self) |
||||
{ |
||||
if (self->Output > self->outMax) { self->Output = self->outMax; } |
||||
else if (self->Output < self->outMin) { self->Output = self->outMin; } |
||||
} |
||||
|
||||
static void clampIterm(struct PID *self) |
||||
{ |
||||
if (self->ITerm > self->outMax) { self->ITerm = self->outMax; } |
||||
else if (self->ITerm < self->outMin) { self->ITerm = self->outMin; } |
||||
} |
||||
|
||||
void PID_Compute(struct PID *self, float Input) |
||||
{ |
||||
if (!self->ctlMode) { return; } |
||||
self->Input = Input; |
||||
|
||||
uint32_t now = xTaskGetTickCount(); |
||||
int32_t timeChange = (now - self->lastTime) * (uint32_t) 1000 / (uint32_t) configTICK_RATE_HZ; |
||||
if (timeChange >= self->SampleTime) { |
||||
/*Compute all the working error variables*/ |
||||
float error = self->Setpoint - Input; |
||||
self->ITerm += (self->ki * error); |
||||
|
||||
clampIterm(self); |
||||
|
||||
float dInput = (Input - self->lastInput); |
||||
|
||||
/*Compute PID Output*/ |
||||
self->Output = self->kp * error + self->ITerm - self->kd * dInput; |
||||
|
||||
clampOutput(self); |
||||
|
||||
/*Remember some variables for next time*/ |
||||
self->lastInput = Input; |
||||
self->lastTime = now; |
||||
} |
||||
} |
||||
|
||||
void PID_SetSetpoint(struct PID *self, float Setpoint) |
||||
{ |
||||
self->Setpoint = Setpoint; |
||||
} |
||||
|
||||
void PID_SetTunings(struct PID *self, float Kp, float Ki, float Kd) |
||||
{ |
||||
if (Kp < 0 || Ki < 0 || Kd < 0) { return; } |
||||
|
||||
float SampleTimeInSec = ((float) self->SampleTime) / 1000; |
||||
self->kp = Kp; |
||||
self->ki = Ki * SampleTimeInSec; |
||||
self->kd = Kd / SampleTimeInSec; |
||||
|
||||
if (self->controllerDirection == PID_REVERSE) { |
||||
self->kp = -self->kp; |
||||
self->ki = -self->ki; |
||||
self->kd = -self->kd; |
||||
} |
||||
} |
||||
|
||||
void PID_SetSampleTime(struct PID *self, uint32_t NewSampleTime) |
||||
{ |
||||
if (NewSampleTime > 0) { |
||||
float ratio = (float) NewSampleTime |
||||
/ (float) self->SampleTime; |
||||
self->ki *= ratio; |
||||
self->kd /= ratio; |
||||
self->SampleTime = (uint32_t) NewSampleTime; |
||||
} |
||||
} |
||||
|
||||
void PID_SetOutputLimits(struct PID *self, float Min, float Max) |
||||
{ |
||||
if (Min > Max) { return; } |
||||
self->outMin = Min; |
||||
self->outMax = Max; |
||||
|
||||
clampOutput(self); |
||||
clampIterm(self); |
||||
} |
||||
|
||||
void PID_SetCtlMode(struct PID *self, enum PIDCtlMode Mode) |
||||
{ |
||||
bool newAuto = (Mode == PID_AUTOMATIC); |
||||
if (newAuto == !self->ctlMode) { /*we just went from manual to auto*/ |
||||
PID_Initialize(self); |
||||
} |
||||
self->ctlMode = newAuto; |
||||
} |
||||
|
||||
void PID_Initialize(struct PID *self) |
||||
{ |
||||
self->lastInput = self->Input; |
||||
self->ITerm = self->Output; |
||||
|
||||
clampIterm(self); |
||||
} |
||||
|
||||
void PID_SetControllerDirection(struct PID *self, enum PIDDirection Direction) |
||||
{ |
||||
self->controllerDirection = Direction; |
||||
} |
@ -0,0 +1,52 @@ |
||||
/**
|
||||
* adapted from the Arduino PID library |
||||
* |
||||
* Created on 2020/01/08. |
||||
*/ |
||||
|
||||
#ifndef ARDUINOPID_H |
||||
#define ARDUINOPID_H |
||||
|
||||
#include <stdint.h> |
||||
|
||||
enum PIDCtlMode { |
||||
PID_MANUAL = 0, |
||||
PID_AUTOMATIC = 1, |
||||
}; |
||||
|
||||
enum PIDDirection { |
||||
PID_DIRECT = 0, |
||||
PID_REVERSE = 1, |
||||
}; |
||||
|
||||
struct PID { |
||||
/*working variables*/ |
||||
uint32_t lastTime; |
||||
float Input, Output, Setpoint; |
||||
float ITerm, lastInput; |
||||
float kp, ki, kd; |
||||
uint32_t SampleTime; // millis
|
||||
float outMin, outMax; |
||||
enum PIDCtlMode ctlMode; // false
|
||||
enum PIDDirection controllerDirection; |
||||
}; |
||||
|
||||
#define PID_DEFAULT() { .SampleTime = 1000, .ctlMode=PID_MANUAL, .controllerDirection=PID_DIRECT } |
||||
|
||||
void PID_Compute(struct PID *self, float Input); |
||||
|
||||
void PID_SetTunings(struct PID *self, float Kp, float Ki, float Kd); |
||||
|
||||
void PID_SetSampleTime(struct PID *self, uint32_t NewSampleTime); |
||||
|
||||
void PID_SetOutputLimits(struct PID *self, float Min, float Max); |
||||
|
||||
void PID_SetCtlMode(struct PID *self, enum PIDCtlMode Mode); |
||||
|
||||
void PID_Initialize(struct PID *self); |
||||
|
||||
void PID_SetSetpoint(struct PID *self, float Setpoint); |
||||
|
||||
void PID_SetControllerDirection(struct PID *self, enum PIDDirection Direction); |
||||
|
||||
#endif //ARDUINOPID_H
|
@ -1,120 +0,0 @@ |
||||
/* USER CODE BEGIN Header */ |
||||
/**
|
||||
****************************************************************************** |
||||
* @file rtc.c |
||||
* @brief This file provides code for the configuration |
||||
* of the RTC instances. |
||||
****************************************************************************** |
||||
* @attention |
||||
* |
||||
* Copyright (c) 2023 STMicroelectronics. |
||||
* All rights reserved. |
||||
* |
||||
* This software is licensed under terms that can be found in the LICENSE file |
||||
* in the root directory of this software component. |
||||
* If no LICENSE file comes with this software, it is provided AS-IS. |
||||
* |
||||
****************************************************************************** |
||||
*/ |
||||
/* USER CODE END Header */ |
||||
/* Includes ------------------------------------------------------------------*/ |
||||
#include "rtc.h" |
||||
|
||||
/* USER CODE BEGIN 0 */ |
||||
|
||||
/* USER CODE END 0 */ |
||||
|
||||
RTC_HandleTypeDef hrtc; |
||||
|
||||
/* RTC init function */ |
||||
void MX_RTC_Init(void) |
||||
{ |
||||
|
||||
/* USER CODE BEGIN RTC_Init 0 */ |
||||
|
||||
/* USER CODE END RTC_Init 0 */ |
||||
|
||||
RTC_TimeTypeDef sTime = {0}; |
||||
RTC_DateTypeDef DateToUpdate = {0}; |
||||
|
||||
/* USER CODE BEGIN RTC_Init 1 */ |
||||
|
||||
/* USER CODE END RTC_Init 1 */ |
||||
|
||||
/** Initialize RTC Only
|
||||
*/ |
||||
hrtc.Instance = RTC; |
||||
hrtc.Init.AsynchPrediv = RTC_AUTO_1_SECOND; |
||||
hrtc.Init.OutPut = RTC_OUTPUTSOURCE_NONE; |
||||
if (HAL_RTC_Init(&hrtc) != HAL_OK) |
||||
{ |
||||
Error_Handler(); |
||||
} |
||||
|
||||
/* USER CODE BEGIN Check_RTC_BKUP */ |
||||
|
||||
/* USER CODE END Check_RTC_BKUP */ |
||||
|
||||
/** Initialize RTC and set the Time and Date
|
||||
*/ |
||||
sTime.Hours = 0x0; |
||||
sTime.Minutes = 0x0; |
||||
sTime.Seconds = 0x0; |
||||
|
||||
if (HAL_RTC_SetTime(&hrtc, &sTime, RTC_FORMAT_BCD) != HAL_OK) |
||||
{ |
||||
Error_Handler(); |
||||
} |
||||
DateToUpdate.WeekDay = RTC_WEEKDAY_MONDAY; |
||||
DateToUpdate.Month = RTC_MONTH_JANUARY; |
||||
DateToUpdate.Date = 0x1; |
||||
DateToUpdate.Year = 0x0; |
||||
|
||||
if (HAL_RTC_SetDate(&hrtc, &DateToUpdate, RTC_FORMAT_BCD) != HAL_OK) |
||||
{ |
||||
Error_Handler(); |
||||
} |
||||
/* USER CODE BEGIN RTC_Init 2 */ |
||||
|
||||
/* USER CODE END RTC_Init 2 */ |
||||
|
||||
} |
||||
|
||||
void HAL_RTC_MspInit(RTC_HandleTypeDef* rtcHandle) |
||||
{ |
||||
|
||||
if(rtcHandle->Instance==RTC) |
||||
{ |
||||
/* USER CODE BEGIN RTC_MspInit 0 */ |
||||
|
||||
/* USER CODE END RTC_MspInit 0 */ |
||||
HAL_PWR_EnableBkUpAccess(); |
||||
/* Enable BKP CLK enable for backup registers */ |
||||
__HAL_RCC_BKP_CLK_ENABLE(); |
||||
/* RTC clock enable */ |
||||
__HAL_RCC_RTC_ENABLE(); |
||||
/* USER CODE BEGIN RTC_MspInit 1 */ |
||||
|
||||
/* USER CODE END RTC_MspInit 1 */ |
||||
} |
||||
} |
||||
|
||||
void HAL_RTC_MspDeInit(RTC_HandleTypeDef* rtcHandle) |
||||
{ |
||||
|
||||
if(rtcHandle->Instance==RTC) |
||||
{ |
||||
/* USER CODE BEGIN RTC_MspDeInit 0 */ |
||||
|
||||
/* USER CODE END RTC_MspDeInit 0 */ |
||||
/* Peripheral clock disable */ |
||||
__HAL_RCC_RTC_DISABLE(); |
||||
/* USER CODE BEGIN RTC_MspDeInit 1 */ |
||||
|
||||
/* USER CODE END RTC_MspDeInit 1 */ |
||||
} |
||||
} |
||||
|
||||
/* USER CODE BEGIN 1 */ |
||||
|
||||
/* USER CODE END 1 */ |
@ -1,607 +0,0 @@ |
||||
/**
|
||||
****************************************************************************** |
||||
* @file stm32f1xx_hal_rtc.h |
||||
* @author MCD Application Team |
||||
* @brief Header file of RTC HAL module. |
||||
****************************************************************************** |
||||
* @attention |
||||
* |
||||
* <h2><center>© Copyright (c) 2016 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 __STM32F1xx_HAL_RTC_H |
||||
#define __STM32F1xx_HAL_RTC_H |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Includes ------------------------------------------------------------------*/ |
||||
#include "stm32f1xx_hal_def.h" |
||||
|
||||
/** @addtogroup STM32F1xx_HAL_Driver
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @addtogroup RTC
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @addtogroup RTC_Private_Macros
|
||||
* @{ |
||||
*/ |
||||
|
||||
#define IS_RTC_ASYNCH_PREDIV(PREDIV) (((PREDIV) <= 0xFFFFFU) || ((PREDIV) == RTC_AUTO_1_SECOND)) |
||||
#define IS_RTC_HOUR24(HOUR) ((HOUR) <= 23U) |
||||
#define IS_RTC_MINUTES(MINUTES) ((MINUTES) <= 59U) |
||||
#define IS_RTC_SECONDS(SECONDS) ((SECONDS) <= 59U) |
||||
#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == RTC_FORMAT_BIN) || ((FORMAT) == RTC_FORMAT_BCD)) |
||||
#define IS_RTC_YEAR(YEAR) ((YEAR) <= 99U) |
||||
#define IS_RTC_MONTH(MONTH) (((MONTH) >= 1U) && ((MONTH) <= 12U)) |
||||
#define IS_RTC_DATE(DATE) (((DATE) >= 1U) && ((DATE) <= 31U)) |
||||
#define IS_RTC_ALARM(ALARM) ((ALARM) == RTC_ALARM_A) |
||||
#define IS_RTC_CALIB_OUTPUT(__OUTPUT__) (((__OUTPUT__) == RTC_OUTPUTSOURCE_NONE) || \ |
||||
((__OUTPUT__) == RTC_OUTPUTSOURCE_CALIBCLOCK) || \
|
||||
((__OUTPUT__) == RTC_OUTPUTSOURCE_ALARM) || \
|
||||
((__OUTPUT__) == RTC_OUTPUTSOURCE_SECOND)) |
||||
|
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @addtogroup RTC_Private_Constants
|
||||
* @{ |
||||
*/ |
||||
/** @defgroup RTC_Timeout_Value Default Timeout Value
|
||||
* @{ |
||||
*/ |
||||
#define RTC_TIMEOUT_VALUE 1000U |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTC_EXTI_Line_Event RTC EXTI Line event
|
||||
* @{ |
||||
*/ |
||||
#define RTC_EXTI_LINE_ALARM_EVENT ((uint32_t)EXTI_IMR_MR17) /*!< External interrupt line 17 Connected to the RTC Alarm event */ |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Exported types ------------------------------------------------------------*/ |
||||
/** @defgroup RTC_Exported_Types RTC Exported Types
|
||||
* @{ |
||||
*/ |
||||
/**
|
||||
* @brief RTC Time structure definition |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
uint8_t Hours; /*!< Specifies the RTC Time Hour.
|
||||
This parameter must be a number between Min_Data = 0 and Max_Data = 23 */ |
||||
|
||||
uint8_t Minutes; /*!< Specifies the RTC Time Minutes.
|
||||
This parameter must be a number between Min_Data = 0 and Max_Data = 59 */ |
||||
|
||||
uint8_t Seconds; /*!< Specifies the RTC Time Seconds.
|
||||
This parameter must be a number between Min_Data = 0 and Max_Data = 59 */ |
||||
|
||||
} RTC_TimeTypeDef; |
||||
|
||||
/**
|
||||
* @brief RTC Alarm structure definition |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
RTC_TimeTypeDef AlarmTime; /*!< Specifies the RTC Alarm Time members */ |
||||
|
||||
uint32_t Alarm; /*!< Specifies the alarm ID (only 1 alarm ID for STM32F1).
|
||||
This parameter can be a value of @ref RTC_Alarms_Definitions */ |
||||
} RTC_AlarmTypeDef; |
||||
|
||||
/**
|
||||
* @brief HAL State structures definition |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
HAL_RTC_STATE_RESET = 0x00U, /*!< RTC not yet initialized or disabled */ |
||||
HAL_RTC_STATE_READY = 0x01U, /*!< RTC initialized and ready for use */ |
||||
HAL_RTC_STATE_BUSY = 0x02U, /*!< RTC process is ongoing */ |
||||
HAL_RTC_STATE_TIMEOUT = 0x03U, /*!< RTC timeout state */ |
||||
HAL_RTC_STATE_ERROR = 0x04U /*!< RTC error state */ |
||||
|
||||
} HAL_RTCStateTypeDef; |
||||
|
||||
/**
|
||||
* @brief RTC Configuration Structure definition |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
uint32_t AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value.
|
||||
This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFFF or RTC_AUTO_1_SECOND |
||||
If RTC_AUTO_1_SECOND is selected, AsynchPrediv will be set automatically to get 1sec timebase */ |
||||
|
||||
uint32_t OutPut; /*!< Specifies which signal will be routed to the RTC Tamper pin.
|
||||
This parameter can be a value of @ref RTC_output_source_to_output_on_the_Tamper_pin */ |
||||
|
||||
} RTC_InitTypeDef; |
||||
|
||||
/**
|
||||
* @brief RTC Date structure definition |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
uint8_t WeekDay; /*!< Specifies the RTC Date WeekDay (not necessary for HAL_RTC_SetDate).
|
||||
This parameter can be a value of @ref RTC_WeekDay_Definitions */ |
||||
|
||||
uint8_t Month; /*!< Specifies the RTC Date Month (in BCD format).
|
||||
This parameter can be a value of @ref RTC_Month_Date_Definitions */ |
||||
|
||||
uint8_t Date; /*!< Specifies the RTC Date.
|
||||
This parameter must be a number between Min_Data = 1 and Max_Data = 31 */ |
||||
|
||||
uint8_t Year; /*!< Specifies the RTC Date Year.
|
||||
This parameter must be a number between Min_Data = 0 and Max_Data = 99 */ |
||||
|
||||
} RTC_DateTypeDef; |
||||
|
||||
/**
|
||||
* @brief Time Handle Structure definition |
||||
*/ |
||||
#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) |
||||
typedef struct __RTC_HandleTypeDef |
||||
#else |
||||
typedef struct |
||||
#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ |
||||
{ |
||||
RTC_TypeDef *Instance; /*!< Register base address */ |
||||
|
||||
RTC_InitTypeDef Init; /*!< RTC required parameters */ |
||||
|
||||
RTC_DateTypeDef DateToUpdate; /*!< Current date set by user and updated automatically */ |
||||
|
||||
HAL_LockTypeDef Lock; /*!< RTC locking object */ |
||||
|
||||
__IO HAL_RTCStateTypeDef State; /*!< Time communication state */ |
||||
|
||||
#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) |
||||
void (* AlarmAEventCallback)(struct __RTC_HandleTypeDef *hrtc); /*!< RTC Alarm A Event callback */ |
||||
|
||||
void (* Tamper1EventCallback)(struct __RTC_HandleTypeDef *hrtc); /*!< RTC Tamper 1 Event callback */ |
||||
|
||||
void (* MspInitCallback)(struct __RTC_HandleTypeDef *hrtc); /*!< RTC Msp Init callback */ |
||||
|
||||
void (* MspDeInitCallback)(struct __RTC_HandleTypeDef *hrtc); /*!< RTC Msp DeInit callback */ |
||||
|
||||
#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ |
||||
|
||||
} RTC_HandleTypeDef; |
||||
|
||||
#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) |
||||
/**
|
||||
* @brief HAL RTC Callback ID enumeration definition |
||||
*/ |
||||
typedef enum |
||||
{ |
||||
HAL_RTC_ALARM_A_EVENT_CB_ID = 0x00u, /*!< RTC Alarm A Event Callback ID */ |
||||
HAL_RTC_TAMPER1_EVENT_CB_ID = 0x04u, /*!< RTC Tamper 1 Callback ID */ |
||||
HAL_RTC_MSPINIT_CB_ID = 0x0Eu, /*!< RTC Msp Init callback ID */ |
||||
HAL_RTC_MSPDEINIT_CB_ID = 0x0Fu /*!< RTC Msp DeInit callback ID */ |
||||
} HAL_RTC_CallbackIDTypeDef; |
||||
|
||||
/**
|
||||
* @brief HAL RTC Callback pointer definition |
||||
*/ |
||||
typedef void (*pRTC_CallbackTypeDef)(RTC_HandleTypeDef *hrtc); /*!< pointer to an RTC callback function */ |
||||
#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Exported constants --------------------------------------------------------*/ |
||||
/** @defgroup RTC_Exported_Constants RTC Exported Constants
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @defgroup RTC_Automatic_Prediv_1_Second Automatic calculation of prediv for 1sec timebase
|
||||
* @{ |
||||
*/ |
||||
#define RTC_AUTO_1_SECOND 0xFFFFFFFFU |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTC_Input_parameter_format_definitions Input Parameter Format
|
||||
* @{ |
||||
*/ |
||||
#define RTC_FORMAT_BIN 0x000000000U |
||||
#define RTC_FORMAT_BCD 0x000000001U |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTC_Month_Date_Definitions Month Definitions
|
||||
* @{ |
||||
*/ |
||||
|
||||
/* Coded in BCD format */ |
||||
#define RTC_MONTH_JANUARY ((uint8_t)0x01) |
||||
#define RTC_MONTH_FEBRUARY ((uint8_t)0x02) |
||||
#define RTC_MONTH_MARCH ((uint8_t)0x03) |
||||
#define RTC_MONTH_APRIL ((uint8_t)0x04) |
||||
#define RTC_MONTH_MAY ((uint8_t)0x05) |
||||
#define RTC_MONTH_JUNE ((uint8_t)0x06) |
||||
#define RTC_MONTH_JULY ((uint8_t)0x07) |
||||
#define RTC_MONTH_AUGUST ((uint8_t)0x08) |
||||
#define RTC_MONTH_SEPTEMBER ((uint8_t)0x09) |
||||
#define RTC_MONTH_OCTOBER ((uint8_t)0x10) |
||||
#define RTC_MONTH_NOVEMBER ((uint8_t)0x11) |
||||
#define RTC_MONTH_DECEMBER ((uint8_t)0x12) |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTC_WeekDay_Definitions WeekDay Definitions
|
||||
* @{ |
||||
*/ |
||||
#define RTC_WEEKDAY_MONDAY ((uint8_t)0x01) |
||||
#define RTC_WEEKDAY_TUESDAY ((uint8_t)0x02) |
||||
#define RTC_WEEKDAY_WEDNESDAY ((uint8_t)0x03) |
||||
#define RTC_WEEKDAY_THURSDAY ((uint8_t)0x04) |
||||
#define RTC_WEEKDAY_FRIDAY ((uint8_t)0x05) |
||||
#define RTC_WEEKDAY_SATURDAY ((uint8_t)0x06) |
||||
#define RTC_WEEKDAY_SUNDAY ((uint8_t)0x00) |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTC_Alarms_Definitions Alarms Definitions
|
||||
* @{ |
||||
*/ |
||||
#define RTC_ALARM_A 0U /*!< Specify alarm ID (mainly for legacy purposes) */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
|
||||
/** @defgroup RTC_output_source_to_output_on_the_Tamper_pin Output source to output on the Tamper pin
|
||||
* @{ |
||||
*/ |
||||
|
||||
#define RTC_OUTPUTSOURCE_NONE 0x00000000U /*!< No output on the TAMPER pin */ |
||||
#define RTC_OUTPUTSOURCE_CALIBCLOCK BKP_RTCCR_CCO /*!< RTC clock with a frequency divided by 64 on the TAMPER pin */ |
||||
#define RTC_OUTPUTSOURCE_ALARM BKP_RTCCR_ASOE /*!< Alarm pulse signal on the TAMPER pin */ |
||||
#define RTC_OUTPUTSOURCE_SECOND (BKP_RTCCR_ASOS | BKP_RTCCR_ASOE) /*!< Second pulse signal on the TAMPER pin */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTC_Interrupts_Definitions Interrupts Definitions
|
||||
* @{ |
||||
*/ |
||||
#define RTC_IT_OW RTC_CRH_OWIE /*!< Overflow interrupt */ |
||||
#define RTC_IT_ALRA RTC_CRH_ALRIE /*!< Alarm interrupt */ |
||||
#define RTC_IT_SEC RTC_CRH_SECIE /*!< Second interrupt */ |
||||
#define RTC_IT_TAMP1 BKP_CSR_TPIE /*!< TAMPER Pin interrupt enable */ |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTC_Flags_Definitions Flags Definitions
|
||||
* @{ |
||||
*/ |
||||
#define RTC_FLAG_RTOFF RTC_CRL_RTOFF /*!< RTC Operation OFF flag */ |
||||
#define RTC_FLAG_RSF RTC_CRL_RSF /*!< Registers Synchronized flag */ |
||||
#define RTC_FLAG_OW RTC_CRL_OWF /*!< Overflow flag */ |
||||
#define RTC_FLAG_ALRAF RTC_CRL_ALRF /*!< Alarm flag */ |
||||
#define RTC_FLAG_SEC RTC_CRL_SECF /*!< Second flag */ |
||||
#define RTC_FLAG_TAMP1F BKP_CSR_TEF /*!< Tamper Interrupt Flag */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Exported macro ------------------------------------------------------------*/ |
||||
/** @defgroup RTC_Exported_macros RTC Exported Macros
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @brief Reset RTC handle state
|
||||
* @param __HANDLE__: RTC handle. |
||||
* @retval None |
||||
*/ |
||||
#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) |
||||
#define __HAL_RTC_RESET_HANDLE_STATE(__HANDLE__) do{\ |
||||
(__HANDLE__)->State = HAL_RTC_STATE_RESET;\
|
||||
(__HANDLE__)->MspInitCallback = NULL;\
|
||||
(__HANDLE__)->MspDeInitCallback = NULL;\
|
||||
}while(0u) |
||||
#else |
||||
#define __HAL_RTC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_RTC_STATE_RESET) |
||||
#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ |
||||
|
||||
/**
|
||||
* @brief Disable the write protection for RTC registers. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_WRITEPROTECTION_DISABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CRL, RTC_CRL_CNF) |
||||
|
||||
/**
|
||||
* @brief Enable the write protection for RTC registers. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_WRITEPROTECTION_ENABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CRL, RTC_CRL_CNF) |
||||
|
||||
/**
|
||||
* @brief Enable the RTC Alarm interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Alarm interrupt sources to be enabled or disabled. |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_ALRA: Alarm A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_ALARM_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CRH, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Disable the RTC Alarm interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Alarm interrupt sources to be enabled or disabled. |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_ALRA: Alarm A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_ALARM_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CRH, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Check whether the specified RTC Alarm interrupt has been enabled or not. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Alarm interrupt sources to be checked |
||||
* This parameter can be: |
||||
* @arg RTC_IT_ALRA: Alarm A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_ALARM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((((__HANDLE__)->Instance->CRH)& ((__INTERRUPT__)))) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Get the selected RTC Alarm's flag status. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Alarm Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_ALRAF |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_ALARM_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->CRL) & (__FLAG__)) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Check whether the specified RTC Alarm interrupt has occurred or not. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Alarm interrupt sources to check. |
||||
* This parameter can be: |
||||
* @arg RTC_IT_ALRA: Alarm A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_ALARM_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->CRL) & (__INTERRUPT__)) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Clear the RTC Alarm's pending flags. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Alarm Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_ALRAF |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_ALARM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->CRL) &= ~(__FLAG__) |
||||
|
||||
/**
|
||||
* @brief Enable interrupt on ALARM Exti Line 17. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_ENABLE_IT() SET_BIT(EXTI->IMR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
/**
|
||||
* @brief Disable interrupt on ALARM Exti Line 17. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_DISABLE_IT() CLEAR_BIT(EXTI->IMR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
/**
|
||||
* @brief Enable event on ALARM Exti Line 17. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_ENABLE_EVENT() SET_BIT(EXTI->EMR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
/**
|
||||
* @brief Disable event on ALARM Exti Line 17. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_DISABLE_EVENT() CLEAR_BIT(EXTI->EMR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
|
||||
/**
|
||||
* @brief ALARM EXTI line configuration: set falling edge trigger. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_ENABLE_FALLING_EDGE() SET_BIT(EXTI->FTSR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
|
||||
/**
|
||||
* @brief Disable the ALARM Extended Interrupt Falling Trigger. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_DISABLE_FALLING_EDGE() CLEAR_BIT(EXTI->FTSR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
|
||||
/**
|
||||
* @brief ALARM EXTI line configuration: set rising edge trigger. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE() SET_BIT(EXTI->RTSR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
/**
|
||||
* @brief Disable the ALARM Extended Interrupt Rising Trigger. |
||||
* This parameter can be: |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_DISABLE_RISING_EDGE() CLEAR_BIT(EXTI->RTSR, RTC_EXTI_LINE_ALARM_EVENT) |
||||
|
||||
/**
|
||||
* @brief ALARM EXTI line configuration: set rising & falling edge trigger. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_ENABLE_RISING_FALLING_EDGE() \ |
||||
do{ \
|
||||
__HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE(); \
|
||||
__HAL_RTC_ALARM_EXTI_ENABLE_FALLING_EDGE(); \
|
||||
} while(0U) |
||||
|
||||
/**
|
||||
* @brief Disable the ALARM Extended Interrupt Rising & Falling Trigger. |
||||
* This parameter can be: |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_DISABLE_RISING_FALLING_EDGE() \ |
||||
do{ \
|
||||
__HAL_RTC_ALARM_EXTI_DISABLE_RISING_EDGE(); \
|
||||
__HAL_RTC_ALARM_EXTI_DISABLE_FALLING_EDGE(); \
|
||||
} while(0U) |
||||
|
||||
/**
|
||||
* @brief Check whether the specified ALARM EXTI interrupt flag is set or not. |
||||
* @retval EXTI ALARM Line Status. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_GET_FLAG() (EXTI->PR & (RTC_EXTI_LINE_ALARM_EVENT)) |
||||
|
||||
/**
|
||||
* @brief Clear the ALARM EXTI flag. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() (EXTI->PR = (RTC_EXTI_LINE_ALARM_EVENT)) |
||||
|
||||
/**
|
||||
* @brief Generate a Software interrupt on selected EXTI line. |
||||
* @retval None. |
||||
*/ |
||||
#define __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() SET_BIT(EXTI->SWIER, RTC_EXTI_LINE_ALARM_EVENT) |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Include RTC HAL Extension module */ |
||||
#include "stm32f1xx_hal_rtc_ex.h" |
||||
|
||||
/* Exported functions --------------------------------------------------------*/ |
||||
/** @addtogroup RTC_Exported_Functions
|
||||
* @{ |
||||
*/ |
||||
|
||||
|
||||
/* Initialization and de-initialization functions ****************************/ |
||||
/** @addtogroup RTC_Exported_Functions_Group1
|
||||
* @{ |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTC_Init(RTC_HandleTypeDef *hrtc); |
||||
HAL_StatusTypeDef HAL_RTC_DeInit(RTC_HandleTypeDef *hrtc); |
||||
void HAL_RTC_MspInit(RTC_HandleTypeDef *hrtc); |
||||
void HAL_RTC_MspDeInit(RTC_HandleTypeDef *hrtc); |
||||
|
||||
/* Callbacks Register/UnRegister functions ***********************************/ |
||||
#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) |
||||
HAL_StatusTypeDef HAL_RTC_RegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID, pRTC_CallbackTypeDef pCallback); |
||||
HAL_StatusTypeDef HAL_RTC_UnRegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID); |
||||
#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* RTC Time and Date functions ************************************************/ |
||||
/** @addtogroup RTC_Exported_Functions_Group2
|
||||
* @{ |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTC_SetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format); |
||||
HAL_StatusTypeDef HAL_RTC_GetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format); |
||||
HAL_StatusTypeDef HAL_RTC_SetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format); |
||||
HAL_StatusTypeDef HAL_RTC_GetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format); |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* RTC Alarm functions ********************************************************/ |
||||
/** @addtogroup RTC_Exported_Functions_Group3
|
||||
* @{ |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTC_SetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format); |
||||
HAL_StatusTypeDef HAL_RTC_SetAlarm_IT(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format); |
||||
HAL_StatusTypeDef HAL_RTC_DeactivateAlarm(RTC_HandleTypeDef *hrtc, uint32_t Alarm); |
||||
HAL_StatusTypeDef HAL_RTC_GetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Alarm, uint32_t Format); |
||||
void HAL_RTC_AlarmIRQHandler(RTC_HandleTypeDef *hrtc); |
||||
HAL_StatusTypeDef HAL_RTC_PollForAlarmAEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); |
||||
void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc); |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Peripheral State functions *************************************************/ |
||||
/** @addtogroup RTC_Exported_Functions_Group4
|
||||
* @{ |
||||
*/ |
||||
HAL_RTCStateTypeDef HAL_RTC_GetState(RTC_HandleTypeDef *hrtc); |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Peripheral Control functions ***********************************************/ |
||||
/** @addtogroup RTC_Exported_Functions_Group5
|
||||
* @{ |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTC_WaitForSynchro(RTC_HandleTypeDef *hrtc); |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* __STM32F1xx_HAL_RTC_H */ |
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
@ -1,412 +0,0 @@ |
||||
/**
|
||||
****************************************************************************** |
||||
* @file stm32f1xx_hal_rtc_ex.h |
||||
* @author MCD Application Team |
||||
* @brief Header file of RTC HAL Extension module. |
||||
****************************************************************************** |
||||
* @attention |
||||
* |
||||
* <h2><center>© Copyright (c) 2016 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 __STM32F1xx_HAL_RTC_EX_H |
||||
#define __STM32F1xx_HAL_RTC_EX_H |
||||
|
||||
#ifdef __cplusplus |
||||
extern "C" { |
||||
#endif |
||||
|
||||
/* Includes ------------------------------------------------------------------*/ |
||||
#include "stm32f1xx_hal_def.h" |
||||
|
||||
/** @addtogroup STM32F1xx_HAL_Driver
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @addtogroup RTCEx
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @addtogroup RTCEx_Private_Macros
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_Alias_For_Legacy Alias define maintained for legacy
|
||||
* @{ |
||||
*/ |
||||
#define HAL_RTCEx_TamperTimeStampIRQHandler HAL_RTCEx_TamperIRQHandler |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_IS_RTC_Definitions Private macros to check input parameters
|
||||
* @{ |
||||
*/ |
||||
#define IS_RTC_TAMPER(__TAMPER__) ((__TAMPER__) == RTC_TAMPER_1) |
||||
|
||||
#define IS_RTC_TAMPER_TRIGGER(__TRIGGER__) (((__TRIGGER__) == RTC_TAMPERTRIGGER_LOWLEVEL) || \ |
||||
((__TRIGGER__) == RTC_TAMPERTRIGGER_HIGHLEVEL)) |
||||
|
||||
#if RTC_BKP_NUMBER > 10U |
||||
#define IS_RTC_BKP(BKP) (((BKP) <= (uint32_t)RTC_BKP_DR10) || (((BKP) >= (uint32_t)RTC_BKP_DR11) && ((BKP) <= (uint32_t)RTC_BKP_DR42))) |
||||
#else |
||||
#define IS_RTC_BKP(BKP) ((BKP) <= (uint32_t)RTC_BKP_NUMBER) |
||||
#endif |
||||
#define IS_RTC_SMOOTH_CALIB_MINUS(__VALUE__) ((__VALUE__) <= 0x0000007FU) |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Exported types ------------------------------------------------------------*/ |
||||
/** @defgroup RTCEx_Exported_Types RTCEx Exported Types
|
||||
* @{ |
||||
*/ |
||||
/**
|
||||
* @brief RTC Tamper structure definition |
||||
*/ |
||||
typedef struct |
||||
{ |
||||
uint32_t Tamper; /*!< Specifies the Tamper Pin.
|
||||
This parameter can be a value of @ref RTCEx_Tamper_Pins_Definitions */ |
||||
|
||||
uint32_t Trigger; /*!< Specifies the Tamper Trigger.
|
||||
This parameter can be a value of @ref RTCEx_Tamper_Trigger_Definitions */ |
||||
|
||||
} RTC_TamperTypeDef; |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Exported constants --------------------------------------------------------*/ |
||||
/** @defgroup RTCEx_Exported_Constants RTCEx Exported Constants
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_Tamper_Pins_Definitions Tamper Pins Definitions
|
||||
* @{ |
||||
*/ |
||||
#define RTC_TAMPER_1 BKP_CR_TPE /*!< Select tamper to be enabled (mainly for legacy purposes) */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_Tamper_Trigger_Definitions Tamper Trigger Definitions
|
||||
* @{ |
||||
*/ |
||||
#define RTC_TAMPERTRIGGER_LOWLEVEL BKP_CR_TPAL /*!< A high level on the TAMPER pin resets all data backup registers (if TPE bit is set) */ |
||||
#define RTC_TAMPERTRIGGER_HIGHLEVEL 0x00000000U /*!< A low level on the TAMPER pin resets all data backup registers (if TPE bit is set) */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_Backup_Registers_Definitions Backup Registers Definitions
|
||||
* @{ |
||||
*/ |
||||
#if RTC_BKP_NUMBER > 0U |
||||
#define RTC_BKP_DR1 0x00000001U |
||||
#define RTC_BKP_DR2 0x00000002U |
||||
#define RTC_BKP_DR3 0x00000003U |
||||
#define RTC_BKP_DR4 0x00000004U |
||||
#define RTC_BKP_DR5 0x00000005U |
||||
#define RTC_BKP_DR6 0x00000006U |
||||
#define RTC_BKP_DR7 0x00000007U |
||||
#define RTC_BKP_DR8 0x00000008U |
||||
#define RTC_BKP_DR9 0x00000009U |
||||
#define RTC_BKP_DR10 0x0000000AU |
||||
#endif /* RTC_BKP_NUMBER > 0 */ |
||||
|
||||
#if RTC_BKP_NUMBER > 10U |
||||
#define RTC_BKP_DR11 0x00000010U |
||||
#define RTC_BKP_DR12 0x00000011U |
||||
#define RTC_BKP_DR13 0x00000012U |
||||
#define RTC_BKP_DR14 0x00000013U |
||||
#define RTC_BKP_DR15 0x00000014U |
||||
#define RTC_BKP_DR16 0x00000015U |
||||
#define RTC_BKP_DR17 0x00000016U |
||||
#define RTC_BKP_DR18 0x00000017U |
||||
#define RTC_BKP_DR19 0x00000018U |
||||
#define RTC_BKP_DR20 0x00000019U |
||||
#define RTC_BKP_DR21 0x0000001AU |
||||
#define RTC_BKP_DR22 0x0000001BU |
||||
#define RTC_BKP_DR23 0x0000001CU |
||||
#define RTC_BKP_DR24 0x0000001DU |
||||
#define RTC_BKP_DR25 0x0000001EU |
||||
#define RTC_BKP_DR26 0x0000001FU |
||||
#define RTC_BKP_DR27 0x00000020U |
||||
#define RTC_BKP_DR28 0x00000021U |
||||
#define RTC_BKP_DR29 0x00000022U |
||||
#define RTC_BKP_DR30 0x00000023U |
||||
#define RTC_BKP_DR31 0x00000024U |
||||
#define RTC_BKP_DR32 0x00000025U |
||||
#define RTC_BKP_DR33 0x00000026U |
||||
#define RTC_BKP_DR34 0x00000027U |
||||
#define RTC_BKP_DR35 0x00000028U |
||||
#define RTC_BKP_DR36 0x00000029U |
||||
#define RTC_BKP_DR37 0x0000002AU |
||||
#define RTC_BKP_DR38 0x0000002BU |
||||
#define RTC_BKP_DR39 0x0000002CU |
||||
#define RTC_BKP_DR40 0x0000002DU |
||||
#define RTC_BKP_DR41 0x0000002EU |
||||
#define RTC_BKP_DR42 0x0000002FU |
||||
#endif /* RTC_BKP_NUMBER > 10 */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Exported macro ------------------------------------------------------------*/ |
||||
/** @defgroup RTCEx_Exported_Macros RTCEx Exported Macros
|
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* @brief Enable the RTC Tamper interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Tamper interrupt sources to be enabled |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_TAMP1: Tamper A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_TAMPER_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT(BKP->CSR, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Disable the RTC Tamper interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Tamper interrupt sources to be disabled. |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_TAMP1: Tamper A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_TAMPER_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT(BKP->CSR, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Check whether the specified RTC Tamper interrupt has been enabled or not. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Tamper interrupt sources to be checked. |
||||
* This parameter can be: |
||||
* @arg RTC_IT_TAMP1 |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_TAMPER_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((BKP->CSR) & ((__INTERRUPT__))) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Get the selected RTC Tamper's flag status. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Tamper Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_TAMP1F |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_TAMPER_GET_FLAG(__HANDLE__, __FLAG__) ((((BKP->CSR) & (__FLAG__)) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Get the selected RTC Tamper's flag status. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Tamper interrupt sources to be checked. |
||||
* This parameter can be: |
||||
* @arg RTC_IT_TAMP1 |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_TAMPER_GET_IT(__HANDLE__, __INTERRUPT__) ((((BKP->CSR) & (BKP_CSR_TEF)) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Clear the RTC Tamper's pending flags. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Tamper Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_TAMP1F |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_TAMPER_CLEAR_FLAG(__HANDLE__, __FLAG__) SET_BIT(BKP->CSR, BKP_CSR_CTE | BKP_CSR_CTI) |
||||
|
||||
/**
|
||||
* @brief Enable the RTC Second interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Second interrupt sources to be enabled |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_SEC: Second A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_SECOND_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CRH, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Disable the RTC Second interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Second interrupt sources to be disabled. |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_SEC: Second A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_SECOND_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CRH, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Check whether the specified RTC Second interrupt has occurred or not. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Second interrupt sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_IT_SEC: Second A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_SECOND_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((((__HANDLE__)->Instance->CRH)& ((__INTERRUPT__)))) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Get the selected RTC Second's flag status. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Second Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_SEC |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_SECOND_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->CRL) & (__FLAG__)) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Clear the RTC Second's pending flags. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Second Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_SEC |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_SECOND_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->CRL) &= ~(__FLAG__) |
||||
|
||||
/**
|
||||
* @brief Enable the RTC Overflow interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Overflow interrupt sources to be enabled |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_OW: Overflow A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_OVERFLOW_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CRH, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Disable the RTC Overflow interrupt. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Overflow interrupt sources to be disabled. |
||||
* This parameter can be any combination of the following values: |
||||
* @arg RTC_IT_OW: Overflow A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_OVERFLOW_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CRH, (__INTERRUPT__)) |
||||
|
||||
/**
|
||||
* @brief Check whether the specified RTC Overflow interrupt has occurred or not. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __INTERRUPT__: specifies the RTC Overflow interrupt sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_IT_OW: Overflow A interrupt |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_OVERFLOW_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((((__HANDLE__)->Instance->CRH)& ((__INTERRUPT__))) ) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Get the selected RTC Overflow's flag status. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Overflow Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_OW |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_OVERFLOW_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->CRL) & (__FLAG__)) != RESET)? SET : RESET) |
||||
|
||||
/**
|
||||
* @brief Clear the RTC Overflow's pending flags. |
||||
* @param __HANDLE__: specifies the RTC handle. |
||||
* @param __FLAG__: specifies the RTC Overflow Flag sources to be enabled or disabled. |
||||
* This parameter can be: |
||||
* @arg RTC_FLAG_OW |
||||
* @retval None |
||||
*/ |
||||
#define __HAL_RTC_OVERFLOW_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->CRL) = ~(__FLAG__) |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Exported functions --------------------------------------------------------*/ |
||||
/** @addtogroup RTCEx_Exported_Functions
|
||||
* @{ |
||||
*/ |
||||
|
||||
/* RTC Tamper functions *****************************************/ |
||||
/** @addtogroup RTCEx_Exported_Functions_Group1
|
||||
* @{ |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_SetTamper(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef *sTamper); |
||||
HAL_StatusTypeDef HAL_RTCEx_SetTamper_IT(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef *sTamper); |
||||
HAL_StatusTypeDef HAL_RTCEx_DeactivateTamper(RTC_HandleTypeDef *hrtc, uint32_t Tamper); |
||||
void HAL_RTCEx_TamperIRQHandler(RTC_HandleTypeDef *hrtc); |
||||
void HAL_RTCEx_Tamper1EventCallback(RTC_HandleTypeDef *hrtc); |
||||
HAL_StatusTypeDef HAL_RTCEx_PollForTamper1Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout); |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* RTC Second functions *****************************************/ |
||||
/** @addtogroup RTCEx_Exported_Functions_Group2
|
||||
* @{ |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_SetSecond_IT(RTC_HandleTypeDef *hrtc); |
||||
HAL_StatusTypeDef HAL_RTCEx_DeactivateSecond(RTC_HandleTypeDef *hrtc); |
||||
void HAL_RTCEx_RTCIRQHandler(RTC_HandleTypeDef *hrtc); |
||||
void HAL_RTCEx_RTCEventCallback(RTC_HandleTypeDef *hrtc); |
||||
void HAL_RTCEx_RTCEventErrorCallback(RTC_HandleTypeDef *hrtc); |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Extension Control functions ************************************************/ |
||||
/** @addtogroup RTCEx_Exported_Functions_Group3
|
||||
* @{ |
||||
*/ |
||||
void HAL_RTCEx_BKUPWrite(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister, uint32_t Data); |
||||
uint32_t HAL_RTCEx_BKUPRead(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister); |
||||
|
||||
HAL_StatusTypeDef HAL_RTCEx_SetSmoothCalib(RTC_HandleTypeDef *hrtc, uint32_t SmoothCalibPeriod, uint32_t SmoothCalibPlusPulses, uint32_t SmouthCalibMinusPulsesValue); |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
#ifdef __cplusplus |
||||
} |
||||
#endif |
||||
|
||||
#endif /* __STM32F1xx_HAL_RTC_EX_H */ |
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
File diff suppressed because it is too large
Load Diff
@ -1,579 +0,0 @@ |
||||
/**
|
||||
****************************************************************************** |
||||
* @file stm32f1xx_hal_rtc_ex.c |
||||
* @author MCD Application Team |
||||
* @brief Extended RTC HAL module driver. |
||||
* This file provides firmware functions to manage the following |
||||
* functionalities of the Real Time Clock (RTC) Extension peripheral: |
||||
* + RTC Tamper functions |
||||
* + Extension Control functions |
||||
* + Extension RTC features functions |
||||
* |
||||
****************************************************************************** |
||||
* @attention |
||||
* |
||||
* <h2><center>© Copyright (c) 2016 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 "stm32f1xx_hal.h" |
||||
|
||||
/** @addtogroup STM32F1xx_HAL_Driver
|
||||
* @{ |
||||
*/ |
||||
|
||||
#ifdef HAL_RTC_MODULE_ENABLED |
||||
|
||||
/** @defgroup RTCEx RTCEx
|
||||
* @brief RTC Extended HAL module driver |
||||
* @{ |
||||
*/ |
||||
|
||||
/* Private typedef -----------------------------------------------------------*/ |
||||
/* Private define ------------------------------------------------------------*/ |
||||
/* Private macro -------------------------------------------------------------*/ |
||||
/** @defgroup RTCEx_Private_Macros RTCEx Private Macros
|
||||
* @{ |
||||
*/ |
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/* Private variables ---------------------------------------------------------*/ |
||||
/* Private function prototypes -----------------------------------------------*/ |
||||
/* Private functions ---------------------------------------------------------*/ |
||||
|
||||
/** @defgroup RTCEx_Exported_Functions RTCEx Exported Functions
|
||||
* @{ |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_Exported_Functions_Group1 RTC Tamper functions
|
||||
* @brief RTC Tamper functions |
||||
* |
||||
@verbatim |
||||
=============================================================================== |
||||
##### RTC Tamper functions ##### |
||||
=============================================================================== |
||||
|
||||
[..] This section provides functions allowing to configure Tamper feature |
||||
|
||||
@endverbatim |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* @brief Sets Tamper |
||||
* @note By calling this API we disable the tamper interrupt for all tampers. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @param sTamper: Pointer to Tamper Structure. |
||||
* @note Tamper can be enabled only if ASOE and CCO bit are reset |
||||
* @retval HAL status |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_SetTamper(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef *sTamper) |
||||
{ |
||||
/* Check input parameters */ |
||||
if ((hrtc == NULL) || (sTamper == NULL)) |
||||
{ |
||||
return HAL_ERROR; |
||||
} |
||||
|
||||
/* Check the parameters */ |
||||
assert_param(IS_RTC_TAMPER(sTamper->Tamper)); |
||||
assert_param(IS_RTC_TAMPER_TRIGGER(sTamper->Trigger)); |
||||
|
||||
/* Process Locked */ |
||||
__HAL_LOCK(hrtc); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_BUSY; |
||||
|
||||
if (HAL_IS_BIT_SET(BKP->RTCCR, (BKP_RTCCR_CCO | BKP_RTCCR_ASOE))) |
||||
{ |
||||
hrtc->State = HAL_RTC_STATE_ERROR; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_ERROR; |
||||
} |
||||
|
||||
MODIFY_REG(BKP->CR, (BKP_CR_TPE | BKP_CR_TPAL), (sTamper->Tamper | (sTamper->Trigger))); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_OK; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Sets Tamper with interrupt. |
||||
* @note By calling this API we force the tamper interrupt for all tampers. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @param sTamper: Pointer to RTC Tamper. |
||||
* @note Tamper can be enabled only if ASOE and CCO bit are reset |
||||
* @retval HAL status |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_SetTamper_IT(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef *sTamper) |
||||
{ |
||||
/* Check input parameters */ |
||||
if ((hrtc == NULL) || (sTamper == NULL)) |
||||
{ |
||||
return HAL_ERROR; |
||||
} |
||||
|
||||
/* Check the parameters */ |
||||
assert_param(IS_RTC_TAMPER(sTamper->Tamper)); |
||||
assert_param(IS_RTC_TAMPER_TRIGGER(sTamper->Trigger)); |
||||
|
||||
/* Process Locked */ |
||||
__HAL_LOCK(hrtc); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_BUSY; |
||||
|
||||
if (HAL_IS_BIT_SET(BKP->RTCCR, (BKP_RTCCR_CCO | BKP_RTCCR_ASOE))) |
||||
{ |
||||
hrtc->State = HAL_RTC_STATE_ERROR; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_ERROR; |
||||
} |
||||
|
||||
MODIFY_REG(BKP->CR, (BKP_CR_TPE | BKP_CR_TPAL), (sTamper->Tamper | (sTamper->Trigger))); |
||||
|
||||
/* Configure the Tamper Interrupt in the BKP->CSR */ |
||||
__HAL_RTC_TAMPER_ENABLE_IT(hrtc, RTC_IT_TAMP1); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_OK; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Deactivates Tamper. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @param Tamper: Selected tamper pin. |
||||
* This parameter can be a value of @ref RTCEx_Tamper_Pins_Definitions |
||||
* @retval HAL status |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_DeactivateTamper(RTC_HandleTypeDef *hrtc, uint32_t Tamper) |
||||
{ |
||||
/* Check input parameters */ |
||||
if (hrtc == NULL) |
||||
{ |
||||
return HAL_ERROR; |
||||
} |
||||
/* Prevent unused argument(s) compilation warning */ |
||||
UNUSED(Tamper); |
||||
|
||||
assert_param(IS_RTC_TAMPER(Tamper)); |
||||
|
||||
/* Process Locked */ |
||||
__HAL_LOCK(hrtc); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_BUSY; |
||||
|
||||
/* Disable the selected Tamper pin */ |
||||
CLEAR_BIT(BKP->CR, BKP_CR_TPE); |
||||
|
||||
/* Disable the Tamper Interrupt in the BKP->CSR */ |
||||
/* Configure the Tamper Interrupt in the BKP->CSR */ |
||||
__HAL_RTC_TAMPER_DISABLE_IT(hrtc, RTC_IT_TAMP1); |
||||
|
||||
/* Clear the Tamper interrupt pending bit */ |
||||
__HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP1F); |
||||
SET_BIT(BKP->CSR, BKP_CSR_CTE); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_OK; |
||||
} |
||||
|
||||
/**
|
||||
* @brief This function handles Tamper interrupt request. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @retval None |
||||
*/ |
||||
void HAL_RTCEx_TamperIRQHandler(RTC_HandleTypeDef *hrtc) |
||||
{ |
||||
/* Get the status of the Interrupt */ |
||||
if (__HAL_RTC_TAMPER_GET_IT_SOURCE(hrtc, RTC_IT_TAMP1)) |
||||
{ |
||||
/* Get the TAMPER Interrupt enable bit and pending bit */ |
||||
if (__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP1F) != (uint32_t)RESET) |
||||
{ |
||||
/* Tamper callback */ |
||||
#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) |
||||
hrtc->Tamper1EventCallback(hrtc); |
||||
#else |
||||
HAL_RTCEx_Tamper1EventCallback(hrtc); |
||||
#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ |
||||
|
||||
/* Clear the Tamper interrupt pending bit */ |
||||
__HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP1F); |
||||
} |
||||
} |
||||
|
||||
/* Change RTC state */ |
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Tamper 1 callback. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @retval None |
||||
*/ |
||||
__weak void HAL_RTCEx_Tamper1EventCallback(RTC_HandleTypeDef *hrtc) |
||||
{ |
||||
/* Prevent unused argument(s) compilation warning */ |
||||
UNUSED(hrtc); |
||||
/* NOTE : This function Should not be modified, when the callback is needed,
|
||||
the HAL_RTCEx_Tamper1EventCallback could be implemented in the user file |
||||
*/ |
||||
} |
||||
|
||||
/**
|
||||
* @brief This function handles Tamper1 Polling. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @param Timeout: Timeout duration |
||||
* @retval HAL status |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_PollForTamper1Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout) |
||||
{ |
||||
uint32_t tickstart = HAL_GetTick(); |
||||
|
||||
/* Check input parameters */ |
||||
if (hrtc == NULL) |
||||
{ |
||||
return HAL_ERROR; |
||||
} |
||||
|
||||
/* Get the status of the Interrupt */ |
||||
while (__HAL_RTC_TAMPER_GET_FLAG(hrtc, RTC_FLAG_TAMP1F) == RESET) |
||||
{ |
||||
if (Timeout != HAL_MAX_DELAY) |
||||
{ |
||||
if ((Timeout == 0U) || ((HAL_GetTick() - tickstart) > Timeout)) |
||||
{ |
||||
hrtc->State = HAL_RTC_STATE_TIMEOUT; |
||||
return HAL_TIMEOUT; |
||||
} |
||||
} |
||||
} |
||||
|
||||
/* Clear the Tamper Flag */ |
||||
__HAL_RTC_TAMPER_CLEAR_FLAG(hrtc, RTC_FLAG_TAMP1F); |
||||
|
||||
/* Change RTC state */ |
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
|
||||
return HAL_OK; |
||||
} |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_Exported_Functions_Group2 RTC Second functions
|
||||
* @brief RTC Second functions |
||||
* |
||||
@verbatim |
||||
=============================================================================== |
||||
##### RTC Second functions ##### |
||||
=============================================================================== |
||||
|
||||
[..] This section provides functions implementing second interupt handlers |
||||
|
||||
@endverbatim |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* @brief Sets Interrupt for second |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @retval HAL status |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_SetSecond_IT(RTC_HandleTypeDef *hrtc) |
||||
{ |
||||
/* Check input parameters */ |
||||
if (hrtc == NULL) |
||||
{ |
||||
return HAL_ERROR; |
||||
} |
||||
|
||||
/* Process Locked */ |
||||
__HAL_LOCK(hrtc); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_BUSY; |
||||
|
||||
/* Enable Second interuption */ |
||||
__HAL_RTC_SECOND_ENABLE_IT(hrtc, RTC_IT_SEC); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_OK; |
||||
} |
||||
|
||||
/**
|
||||
* @brief Deactivates Second. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @retval HAL status |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_DeactivateSecond(RTC_HandleTypeDef *hrtc) |
||||
{ |
||||
/* Check input parameters */ |
||||
if (hrtc == NULL) |
||||
{ |
||||
return HAL_ERROR; |
||||
} |
||||
|
||||
/* Process Locked */ |
||||
__HAL_LOCK(hrtc); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_BUSY; |
||||
|
||||
/* Deactivate Second interuption*/ |
||||
__HAL_RTC_SECOND_DISABLE_IT(hrtc, RTC_IT_SEC); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_OK; |
||||
} |
||||
|
||||
/**
|
||||
* @brief This function handles second interrupt request. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @retval None |
||||
*/ |
||||
void HAL_RTCEx_RTCIRQHandler(RTC_HandleTypeDef *hrtc) |
||||
{ |
||||
if (__HAL_RTC_SECOND_GET_IT_SOURCE(hrtc, RTC_IT_SEC)) |
||||
{ |
||||
/* Get the status of the Interrupt */ |
||||
if (__HAL_RTC_SECOND_GET_FLAG(hrtc, RTC_FLAG_SEC)) |
||||
{ |
||||
/* Check if Overrun occurred */ |
||||
if (__HAL_RTC_SECOND_GET_FLAG(hrtc, RTC_FLAG_OW)) |
||||
{ |
||||
/* Second error callback */ |
||||
HAL_RTCEx_RTCEventErrorCallback(hrtc); |
||||
|
||||
/* Clear flag Second */ |
||||
__HAL_RTC_OVERFLOW_CLEAR_FLAG(hrtc, RTC_FLAG_OW); |
||||
|
||||
/* Change RTC state */ |
||||
hrtc->State = HAL_RTC_STATE_ERROR; |
||||
} |
||||
else |
||||
{ |
||||
/* Second callback */ |
||||
HAL_RTCEx_RTCEventCallback(hrtc); |
||||
|
||||
/* Change RTC state */ |
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
} |
||||
|
||||
/* Clear flag Second */ |
||||
__HAL_RTC_SECOND_CLEAR_FLAG(hrtc, RTC_FLAG_SEC); |
||||
} |
||||
} |
||||
} |
||||
|
||||
/**
|
||||
* @brief Second event callback. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @retval None |
||||
*/ |
||||
__weak void HAL_RTCEx_RTCEventCallback(RTC_HandleTypeDef *hrtc) |
||||
{ |
||||
/* Prevent unused argument(s) compilation warning */ |
||||
UNUSED(hrtc); |
||||
/* NOTE : This function Should not be modified, when the callback is needed,
|
||||
the HAL_RTCEx_RTCEventCallback could be implemented in the user file |
||||
*/ |
||||
} |
||||
|
||||
/**
|
||||
* @brief Second event error callback. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @retval None |
||||
*/ |
||||
__weak void HAL_RTCEx_RTCEventErrorCallback(RTC_HandleTypeDef *hrtc) |
||||
{ |
||||
/* Prevent unused argument(s) compilation warning */ |
||||
UNUSED(hrtc); |
||||
/* NOTE : This function Should not be modified, when the callback is needed,
|
||||
the HAL_RTCEx_RTCEventErrorCallback could be implemented in the user file |
||||
*/ |
||||
} |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/** @defgroup RTCEx_Exported_Functions_Group3 Extended Peripheral Control functions
|
||||
* @brief Extended Peripheral Control functions |
||||
* |
||||
@verbatim |
||||
=============================================================================== |
||||
##### Extension Peripheral Control functions ##### |
||||
=============================================================================== |
||||
[..] |
||||
This subsection provides functions allowing to |
||||
(+) Writes a data in a specified RTC Backup data register |
||||
(+) Read a data in a specified RTC Backup data register |
||||
(+) Sets the Smooth calibration parameters. |
||||
|
||||
@endverbatim |
||||
* @{ |
||||
*/ |
||||
|
||||
/**
|
||||
* @brief Writes a data in a specified RTC Backup data register. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @param BackupRegister: RTC Backup data Register number. |
||||
* This parameter can be: RTC_BKP_DRx where x can be from 1 to 10 (or 42) to |
||||
* specify the register (depending devices). |
||||
* @param Data: Data to be written in the specified RTC Backup data register. |
||||
* @retval None |
||||
*/ |
||||
void HAL_RTCEx_BKUPWrite(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister, uint32_t Data) |
||||
{ |
||||
uint32_t tmp = 0U; |
||||
|
||||
/* Prevent unused argument(s) compilation warning */ |
||||
UNUSED(hrtc); |
||||
|
||||
/* Check the parameters */ |
||||
assert_param(IS_RTC_BKP(BackupRegister)); |
||||
|
||||
tmp = (uint32_t)BKP_BASE; |
||||
tmp += (BackupRegister * 4U); |
||||
|
||||
*(__IO uint32_t *) tmp = (Data & BKP_DR1_D); |
||||
} |
||||
|
||||
/**
|
||||
* @brief Reads data from the specified RTC Backup data Register. |
||||
* @param hrtc: pointer to a RTC_HandleTypeDef structure that contains |
||||
* the configuration information for RTC. |
||||
* @param BackupRegister: RTC Backup data Register number. |
||||
* This parameter can be: RTC_BKP_DRx where x can be from 1 to 10 (or 42) to |
||||
* specify the register (depending devices). |
||||
* @retval Read value |
||||
*/ |
||||
uint32_t HAL_RTCEx_BKUPRead(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister) |
||||
{ |
||||
uint32_t backupregister = 0U; |
||||
uint32_t pvalue = 0U; |
||||
|
||||
/* Prevent unused argument(s) compilation warning */ |
||||
UNUSED(hrtc); |
||||
|
||||
/* Check the parameters */ |
||||
assert_param(IS_RTC_BKP(BackupRegister)); |
||||
|
||||
backupregister = (uint32_t)BKP_BASE; |
||||
backupregister += (BackupRegister * 4U); |
||||
|
||||
pvalue = (*(__IO uint32_t *)(backupregister)) & BKP_DR1_D; |
||||
|
||||
/* Read the specified register */ |
||||
return pvalue; |
||||
} |
||||
|
||||
|
||||
/**
|
||||
* @brief Sets the Smooth calibration parameters. |
||||
* @param hrtc: RTC handle |
||||
* @param SmoothCalibPeriod: Not used (only present for compatibility with another families) |
||||
* @param SmoothCalibPlusPulses: Not used (only present for compatibility with another families) |
||||
* @param SmouthCalibMinusPulsesValue: specifies the RTC Clock Calibration value. |
||||
* This parameter must be a number between 0 and 0x7F. |
||||
* @retval HAL status |
||||
*/ |
||||
HAL_StatusTypeDef HAL_RTCEx_SetSmoothCalib(RTC_HandleTypeDef *hrtc, uint32_t SmoothCalibPeriod, uint32_t SmoothCalibPlusPulses, uint32_t SmouthCalibMinusPulsesValue) |
||||
{ |
||||
/* Check input parameters */ |
||||
if (hrtc == NULL) |
||||
{ |
||||
return HAL_ERROR; |
||||
} |
||||
/* Prevent unused argument(s) compilation warning */ |
||||
UNUSED(SmoothCalibPeriod); |
||||
UNUSED(SmoothCalibPlusPulses); |
||||
|
||||
/* Check the parameters */ |
||||
assert_param(IS_RTC_SMOOTH_CALIB_MINUS(SmouthCalibMinusPulsesValue)); |
||||
|
||||
/* Process Locked */ |
||||
__HAL_LOCK(hrtc); |
||||
|
||||
hrtc->State = HAL_RTC_STATE_BUSY; |
||||
|
||||
/* Sets RTC Clock Calibration value.*/ |
||||
MODIFY_REG(BKP->RTCCR, BKP_RTCCR_CAL, SmouthCalibMinusPulsesValue); |
||||
|
||||
/* Change RTC state */ |
||||
hrtc->State = HAL_RTC_STATE_READY; |
||||
|
||||
/* Process Unlocked */ |
||||
__HAL_UNLOCK(hrtc); |
||||
|
||||
return HAL_OK; |
||||
} |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
#endif /* HAL_RTC_MODULE_ENABLED */ |
||||
|
||||
/**
|
||||
* @} |
||||
*/ |
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ |
||||
|
@ -0,0 +1,25 @@ |
||||
Pinout: |
||||
|
||||
- Knob push: PB8 |
||||
- Knob A/B: PB6, PB7 |
||||
- Buzzer PWM: PA15 |
||||
- Debug SWD: PA13 (IO), PA14 (CK) |
||||
- Debug UART: PA9 (Tx), PA10 (Rx) |
||||
- OLED reset: PB10 |
||||
- OLED DC: PB1 |
||||
- OLED CS: PB0 |
||||
- OLED MOSI: PA7 |
||||
- OLED SCLK: PA5 |
||||
- A0 - Pt100 |
||||
- A1 - Resistive divider top (filtered 3.3V, 1k + Pt100) |
||||
|
||||
|
||||
Peripherals: |
||||
|
||||
- TIM2 - Buzzer -> PA15 |
||||
- TIM3 - Heater PWM -> PA6 |
||||
- TIM4 - Encoder <- PB6, PB7 |
||||
- SPI1 MOSI only - OLED (PA5, PA7) |
||||
- UART1 - debug |
||||
- ADC1 - sensing |
||||
|
Loading…
Reference in new issue