8 Commits

Author SHA1 Message Date
Anton Mukhin
900f6d7d85 v11.2 changes:
- moved 400ms boot delay to a point AFTER peripherals init
- fixed TIM3 and TIM14 periods
- mvoed light updates to separate function and fixed cuty cylce clamp during dimming process
2024-06-21 15:22:50 +03:00
Anton Mukhin
ed9ba49c9c Migrated to a new HAL version 2024-06-21 15:18:57 +03:00
Anton Mukhin
b7782c1e8f v11.1 Reg 0x2011 2024-06-19 10:05:47 +03:00
Anton Mukhin
4239d310ed Merge branch 'V2R1-board' 2024-06-14 18:28:43 +03:00
Anton Mukhin
87f6a0bf3b E-STOP, Light button and pump status functionality fixed/implemented; FW is ready for testing! 2024-06-14 18:27:46 +03:00
Anton Mukhin
651e3b02d1 Smooth LED lights level change 2024-01-18 15:26:13 +03:00
Anton Mukhin
108f165ca2 WIP: Add new features for board version 2 2024-01-17 15:52:55 +03:00
Anton Mukhin
c882ede6bd Description length fixed 2023-11-27 12:11:03 +03:00
29 changed files with 1172 additions and 440 deletions

View File

@@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<projectDescription> <projectDescription>
<name>Relay_RS485</name> <name>Relay_RS485_V2</name>
<comment></comment> <comment></comment>
<projects> <projects>
</projects> </projects>

View File

@@ -6,17 +6,24 @@
#ifndef BOARD_LOGIC_H_ #ifndef BOARD_LOGIC_H_
#define BOARD_LOGIC_H_ #define BOARD_LOGIC_H_
#define MODBUS_FIRMWARE_VERSION ( /*major*/ 10 + /*minor*/ 0 * 0x100) #define MODBUS_FIRMWARE_VERSION ( /*major*/ 11 + /*minor*/ 2 * 0x100)
#define MODBUS_BOARD_TYPE (8) //Relay Module board ID #define MODBUS_BOARD_TYPE (8) //Relay Module board ID
#define REL_MAIN_BIT (1u<<0) #define REL_MAIN_BIT (1u<<0)
#define REL_AUX_BIT (1u<<1) #define REL_AUX_BIT (1u<<1)
#define MOTOR_MIN 0 #define PWM_DUTY_MIN 0
#define MOTOR_MAX 255 #define PWM_DUTY_MAX 255
#define PWM_LIGHTS_STEP 20 // Time step in ms between LED light PWM updates
#define LIGHTS_TIME 600 // Time in ms to spend for smooth lights level change
void estop_reset(void);
void board_init(void);
uint16_t clamp_duty(uint16_t duty);
void set_pwm(uint8_t unit, uint16_t duty);
void set_light(uint16_t duty);
void loop_iterate(); void loop_iterate();
void timer1_ovf_isr(void); void update_service_indication(void);
#endif #endif

View File

@@ -59,6 +59,16 @@ void Error_Handler(void);
/* USER CODE END EFP */ /* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/ /* Private defines -----------------------------------------------------------*/
#define WATER_Pin GPIO_PIN_0
#define WATER_GPIO_Port GPIOA
#define WATER_EXTI_IRQn EXTI0_1_IRQn
#define ESTOP_Pin GPIO_PIN_1
#define ESTOP_GPIO_Port GPIOA
#define ESTOP_EXTI_IRQn EXTI0_1_IRQn
#define LIGHTS_Pin GPIO_PIN_4
#define LIGHTS_GPIO_Port GPIOA
#define RL_EN_Pin GPIO_PIN_5
#define RL_EN_GPIO_Port GPIOA
#define LED_AUX_Pin GPIO_PIN_6 #define LED_AUX_Pin GPIO_PIN_6
#define LED_AUX_GPIO_Port GPIOA #define LED_AUX_GPIO_Port GPIOA
#define LED_MAIN_Pin GPIO_PIN_7 #define LED_MAIN_Pin GPIO_PIN_7
@@ -67,6 +77,9 @@ void Error_Handler(void);
#define LED_ERR_GPIO_Port GPIOB #define LED_ERR_GPIO_Port GPIOB
#define LED_ACT_Pin GPIO_PIN_1 #define LED_ACT_Pin GPIO_PIN_1
#define LED_ACT_GPIO_Port GPIOB #define LED_ACT_GPIO_Port GPIOB
#define LIGHTS_SW_Pin GPIO_PIN_8
#define LIGHTS_SW_GPIO_Port GPIOA
#define LIGHTS_SW_EXTI_IRQn EXTI4_15_IRQn
#define TXEN_Pin GPIO_PIN_11 #define TXEN_Pin GPIO_PIN_11
#define TXEN_GPIO_Port GPIOA #define TXEN_GPIO_Port GPIOA
#define RL_AUX_Pin GPIO_PIN_15 #define RL_AUX_Pin GPIO_PIN_15

View File

@@ -51,6 +51,8 @@ void HardFault_Handler(void);
void SVC_Handler(void); void SVC_Handler(void);
void PendSV_Handler(void); void PendSV_Handler(void);
void SysTick_Handler(void); void SysTick_Handler(void);
void EXTI0_1_IRQHandler(void);
void EXTI4_15_IRQHandler(void);
void DMA1_Channel2_3_IRQHandler(void); void DMA1_Channel2_3_IRQHandler(void);
void TIM1_BRK_UP_TRG_COM_IRQHandler(void); void TIM1_BRK_UP_TRG_COM_IRQHandler(void);
void TIM1_CC_IRQHandler(void); void TIM1_CC_IRQHandler(void);

View File

@@ -5,17 +5,19 @@
#include <stdint.h> #include <stdint.h>
#include <stdio.h> #include <stdio.h>
#include <stdlib.h>
#include "main.h" #include "main.h"
#include "modbus_logic.h" #include "modbus_logic.h"
#include "board_logic.h" #include "board_logic.h"
#define BOARD_DESC_LEN (23) #define BOARD_DESC_LEN (16)
extern TIM_HandleTypeDef htim1;
extern TIM_HandleTypeDef htim3; extern TIM_HandleTypeDef htim3;
static const char board_description[BOARD_DESC_LEN] = "RS485_Relay V1R1"; extern TIM_HandleTypeDef htim14;
static const char board_description[BOARD_DESC_LEN] = "RS485_Relay V2R1";
extern uint16_t tranfer_errors_count; extern uint16_t tranfer_errors_count;
extern uint16_t last_rx_time;
#define REL_MAIN_ON HAL_GPIO_WritePin(RL_MAIN_GPIO_Port, RL_MAIN_Pin, GPIO_PIN_SET) #define REL_MAIN_ON HAL_GPIO_WritePin(RL_MAIN_GPIO_Port, RL_MAIN_Pin, GPIO_PIN_SET)
#define REL_MAIN_OFF HAL_GPIO_WritePin(RL_MAIN_GPIO_Port, RL_MAIN_Pin, GPIO_PIN_RESET) #define REL_MAIN_OFF HAL_GPIO_WritePin(RL_MAIN_GPIO_Port, RL_MAIN_Pin, GPIO_PIN_RESET)
@@ -28,11 +30,99 @@ extern uint16_t last_rx_time;
#define LED_ACT_ON HAL_GPIO_WritePin(LED_ACT_GPIO_Port, LED_ACT_Pin, GPIO_PIN_SET) #define LED_ACT_ON HAL_GPIO_WritePin(LED_ACT_GPIO_Port, LED_ACT_Pin, GPIO_PIN_SET)
#define LED_ACT_OFF HAL_GPIO_WritePin(LED_ACT_GPIO_Port, LED_ACT_Pin, GPIO_PIN_RESET) #define LED_ACT_OFF HAL_GPIO_WritePin(LED_ACT_GPIO_Port, LED_ACT_Pin, GPIO_PIN_RESET)
uint16_t relays=0;
uint16_t motor_pwm=0;
uint16_t led_time_act=0;
void update_service_indication(void); uint16_t relays = 0;
uint16_t status = 0;
uint16_t motor1_pwm = 0;
uint16_t motor2_pwm = 0;
uint16_t lights_pwm = 0;
volatile uint16_t lights_pwm_target = 0;
volatile int16_t lights_pwm_delta = 0;
uint16_t led_time_act = 0;
void estop_reset(void) {
HAL_GPIO_WritePin(RL_EN_GPIO_Port, RL_EN_Pin, GPIO_PIN_RESET);
HAL_Delay(1);
HAL_GPIO_WritePin(RL_EN_GPIO_Port, RL_EN_Pin, GPIO_PIN_SET);
}
void board_init(void) {
// Activate (normalize) E-STOP trigger
estop_reset();
// Check if E-STOP is not shorted
if (HAL_GPIO_ReadPin(ESTOP_GPIO_Port, ESTOP_Pin) == GPIO_PIN_RESET)
status = status | 0b010;
// 1ms timer start
HAL_TIM_Base_Start_IT(&htim1);
}
uint16_t clamp_duty(uint16_t duty) {
if (duty > PWM_DUTY_MAX) return PWM_DUTY_MAX;
if (duty < PWM_DUTY_MIN) return PWM_DUTY_MIN;
return duty;
}
void set_pwm(uint8_t unit, uint16_t duty) {
uint32_t channel;
TIM_HandleTypeDef* tim;
switch (unit) {
case 1: // motor 1
tim = &htim3;
channel = TIM_CHANNEL_1;
break;
case 2: // motor 2
tim = &htim3;
channel = TIM_CHANNEL_2;
break;
case 3: // lights
tim = &htim14;
channel = TIM_CHANNEL_1;
break;
default:
return;
}
duty = clamp_duty(duty);
if (duty == 0)
HAL_TIM_PWM_Stop_IT(tim, channel);
else {
HAL_TIM_PWM_Start_IT(tim, channel);
__HAL_TIM_SetCompare(tim, channel, duty);
//HAL_Delay(1);
}
}
void set_light(uint16_t duty) {
lights_pwm_target = clamp_duty(duty);
if (lights_pwm_target != lights_pwm) {
lights_pwm_delta = (lights_pwm_target - lights_pwm) / (LIGHTS_TIME / PWM_LIGHTS_STEP);
if (lights_pwm_delta == 0) {
if (lights_pwm_target - lights_pwm > 0) lights_pwm_delta = 1;
else lights_pwm_delta = -1;
}
}
}
void update_light(void) {
static uint32_t count_ms = 0;
// Check if we should change lights pwm for smooth transition
if (lights_pwm != lights_pwm_target) {
// Change pwm only every 20ms (PWM_LIGHTS_STEP)
if(++count_ms == PWM_LIGHTS_STEP) {
count_ms = 0;
lights_pwm = clamp_duty(lights_pwm + lights_pwm_delta);
// Set lights pwm to target if the difference is less than the delta
if (abs(lights_pwm_target - lights_pwm) < abs(lights_pwm_delta))
lights_pwm = lights_pwm_target;
set_pwm(3, lights_pwm);
}
}
}
void loop_iterate() void loop_iterate()
{ {
@@ -64,40 +154,15 @@ void loop_iterate()
HAL_Delay(1); HAL_Delay(1);
} }
// Timer1 overflow interrupt service routine
void timer1_ovf_isr(void) //1 ms
{
static uint32_t count_1sec=0;
if(last_rx_time<0xFFFF)last_rx_time++;
update_service_indication();
if(++count_1sec==1000)
{
count_1sec = 0;
//led_time_g += 10;
}
}
void update_service_indication(void) void update_service_indication(void)
{ {
if(led_time_act) if (led_time_act) {
{
LED_ACT_ON; LED_ACT_ON;
led_time_act--; led_time_act--;
} } else
else
LED_ACT_OFF; LED_ACT_OFF;
/*
if(led_time_g)
{
LED_G_ON;
led_time_g--;
}
else
LED_G_OFF;
*/
} }
@@ -125,9 +190,26 @@ uint8_t read_register(uint16_t address, uint16_t* value)
{ {
*value = relays; *value = relays;
} }
else if (address == 0x2002) //Read motor pwm else if (address == 0x2002) //Read motor 1 pwm
{ {
*value = motor_pwm; *value = motor1_pwm;
}
else if (address == 0x2003) //Read motor 2 pwm
{
*value = motor2_pwm;
}
else if (address == 0x2004) //Read Lights pwm
{
*value = lights_pwm;
}
else if (address == 0x2010) //Read status
{
*value = status;
status &= 0b011; // Reset light button press event status
}
else if (address == 0x2011) //Read E-STOP status
{
*value = (status & 0b010)>>1; // Read E-stop status bit and shift it to bit 0 position
} }
else else
return 1; return 1;
@@ -137,24 +219,30 @@ uint8_t read_register(uint16_t address, uint16_t* value)
uint8_t write_register(uint16_t address, uint16_t value) uint8_t write_register(uint16_t address, uint16_t value)
{ {
uint8_t ret; uint8_t ret;
ret=0; ret = 0;
#ifdef UART_DEBUG #ifdef UART_DEBUG
printf("Write A=0x%X D=0x%X\n\r",address,value); printf("Write A=0x%X D=0x%X\n\r",address,value);
#endif #endif
switch (address) { switch (address) {
case 0x2001: case 0x2001:
if (status & 0b010) break; // Check if we are in emergency stop mode
relays = value; relays = value;
break; break;
case 0x2002: case 0x2002:
motor_pwm = value; motor1_pwm = value;
if(motor_pwm>MOTOR_MAX)motor_pwm=MOTOR_MAX; set_pwm(1, motor1_pwm);
if(motor_pwm<MOTOR_MIN)motor_pwm=MOTOR_MIN; break;
if(motor_pwm==0) case 0x2003:
HAL_TIM_PWM_Stop(&htim3, TIM_CHANNEL_1); motor2_pwm = value;
else { set_pwm(2, motor2_pwm);
HAL_TIM_PWM_Start(&htim3, TIM_CHANNEL_1); break;
__HAL_TIM_SetCompare(&htim3, TIM_CHANNEL_1, motor_pwm); case 0x2004:
HAL_Delay(5); set_light(value);
break;
case 0x2020:
if (value == 1) {
estop_reset();
status &= 0b101;
} }
break; break;
default: default:
@@ -163,3 +251,34 @@ uint8_t write_register(uint16_t address, uint16_t value)
return ret; return ret;
} }
// Pin external interrupts handler
void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin)
{
if(GPIO_Pin == ESTOP_Pin) {
status = status | 0b010;
relays = 0;
}
if(GPIO_Pin == LIGHTS_SW_Pin) {
// Set "lights switch pressed" status bit
status |= 0b100;
if (lights_pwm_target > 0) set_light(0);
else set_light(255);
}
if(GPIO_Pin == WATER_Pin) {
// Set or reset "water" status bit
status |= HAL_GPIO_ReadPin(WATER_GPIO_Port, WATER_Pin);
if (HAL_GPIO_ReadPin(WATER_GPIO_Port, WATER_Pin)) status |= 1;
else status &= ~1;
}
}
// Timers overflow interrupt
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
// check if the interrupt comes from TIM1
if(htim->Instance == TIM1) {
update_service_indication();
update_light();
}
}

View File

@@ -45,6 +45,7 @@
/* Private variables ---------------------------------------------------------*/ /* Private variables ---------------------------------------------------------*/
TIM_HandleTypeDef htim1; TIM_HandleTypeDef htim1;
TIM_HandleTypeDef htim3; TIM_HandleTypeDef htim3;
TIM_HandleTypeDef htim14;
UART_HandleTypeDef huart1; UART_HandleTypeDef huart1;
DMA_HandleTypeDef hdma_usart1_rx; DMA_HandleTypeDef hdma_usart1_rx;
@@ -61,6 +62,7 @@ static void MX_DMA_Init(void);
static void MX_TIM3_Init(void); static void MX_TIM3_Init(void);
static void MX_USART1_UART_Init(void); static void MX_USART1_UART_Init(void);
static void MX_TIM1_Init(void); static void MX_TIM1_Init(void);
static void MX_TIM14_Init(void);
/* USER CODE BEGIN PFP */ /* USER CODE BEGIN PFP */
/* USER CODE END PFP */ /* USER CODE END PFP */
@@ -76,6 +78,7 @@ static void MX_TIM1_Init(void);
*/ */
int main(void) int main(void)
{ {
/* USER CODE BEGIN 1 */ /* USER CODE BEGIN 1 */
/* USER CODE END 1 */ /* USER CODE END 1 */
@@ -93,7 +96,7 @@ int main(void)
SystemClock_Config(); SystemClock_Config();
/* USER CODE BEGIN SysInit */ /* USER CODE BEGIN SysInit */
HAL_Delay(400); // HAL_Delay(400);
/* USER CODE END SysInit */ /* USER CODE END SysInit */
/* Initialize all configured peripherals */ /* Initialize all configured peripherals */
@@ -102,8 +105,10 @@ int main(void)
MX_TIM3_Init(); MX_TIM3_Init();
MX_USART1_UART_Init(); MX_USART1_UART_Init();
MX_TIM1_Init(); MX_TIM1_Init();
MX_TIM14_Init();
/* USER CODE BEGIN 2 */ /* USER CODE BEGIN 2 */
HAL_TIM_Base_Start_IT(&htim1); HAL_Delay(400);
board_init();
/* USER CODE END 2 */ /* USER CODE END 2 */
@@ -183,9 +188,9 @@ static void MX_TIM1_Init(void)
/* USER CODE END TIM1_Init 1 */ /* USER CODE END TIM1_Init 1 */
htim1.Instance = TIM1; htim1.Instance = TIM1;
htim1.Init.Prescaler = 479; htim1.Init.Prescaler = 480-1;
htim1.Init.CounterMode = TIM_COUNTERMODE_UP; htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
htim1.Init.Period = 100; htim1.Init.Period = 100-1;
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim1.Init.RepetitionCounter = 0; htim1.Init.RepetitionCounter = 0;
htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
@@ -229,9 +234,9 @@ static void MX_TIM3_Init(void)
/* USER CODE END TIM3_Init 1 */ /* USER CODE END TIM3_Init 1 */
htim3.Instance = TIM3; htim3.Instance = TIM3;
htim3.Init.Prescaler = 239; htim3.Init.Prescaler = 240-1;
htim3.Init.CounterMode = TIM_COUNTERMODE_UP; htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
htim3.Init.Period = 255; htim3.Init.Period = 255-1;
htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_PWM_Init(&htim3) != HAL_OK) if (HAL_TIM_PWM_Init(&htim3) != HAL_OK)
@@ -252,6 +257,10 @@ static void MX_TIM3_Init(void)
{ {
Error_Handler(); Error_Handler();
} }
if (HAL_TIM_PWM_ConfigChannel(&htim3, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM3_Init 2 */ /* USER CODE BEGIN TIM3_Init 2 */
/* USER CODE END TIM3_Init 2 */ /* USER CODE END TIM3_Init 2 */
@@ -259,6 +268,52 @@ static void MX_TIM3_Init(void)
} }
/**
* @brief TIM14 Initialization Function
* @param None
* @retval None
*/
static void MX_TIM14_Init(void)
{
/* USER CODE BEGIN TIM14_Init 0 */
/* USER CODE END TIM14_Init 0 */
TIM_OC_InitTypeDef sConfigOC = {0};
/* USER CODE BEGIN TIM14_Init 1 */
/* USER CODE END TIM14_Init 1 */
htim14.Instance = TIM14;
htim14.Init.Prescaler = 6-1;
htim14.Init.CounterMode = TIM_COUNTERMODE_UP;
htim14.Init.Period = 255-1;
htim14.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
htim14.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
if (HAL_TIM_Base_Init(&htim14) != HAL_OK)
{
Error_Handler();
}
if (HAL_TIM_PWM_Init(&htim14) != HAL_OK)
{
Error_Handler();
}
sConfigOC.OCMode = TIM_OCMODE_PWM1;
sConfigOC.Pulse = 0;
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
if (HAL_TIM_PWM_ConfigChannel(&htim14, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
{
Error_Handler();
}
/* USER CODE BEGIN TIM14_Init 2 */
/* USER CODE END TIM14_Init 2 */
HAL_TIM_MspPostInit(&htim14);
}
/** /**
* @brief USART1 Initialization Function * @brief USART1 Initialization Function
* @param None * @param None
@@ -326,14 +381,31 @@ static void MX_GPIO_Init(void)
__HAL_RCC_GPIOA_CLK_ENABLE(); __HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE(); __HAL_RCC_GPIOB_CLK_ENABLE();
/*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(RL_EN_GPIO_Port, RL_EN_Pin, GPIO_PIN_SET);
/*Configure GPIO pin Output Level */ /*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOA, LED_AUX_Pin|LED_MAIN_Pin|TXEN_Pin|RL_AUX_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(GPIOA, LED_AUX_Pin|LED_MAIN_Pin|TXEN_Pin|RL_AUX_Pin, GPIO_PIN_RESET);
/*Configure GPIO pin Output Level */ /*Configure GPIO pin Output Level */
HAL_GPIO_WritePin(GPIOB, LED_ERR_Pin|LED_ACT_Pin|RL_MAIN_Pin, GPIO_PIN_RESET); HAL_GPIO_WritePin(GPIOB, LED_ERR_Pin|LED_ACT_Pin|RL_MAIN_Pin, GPIO_PIN_RESET);
/*Configure GPIO pins : LED_AUX_Pin LED_MAIN_Pin TXEN_Pin RL_AUX_Pin */ /*Configure GPIO pin : WATER_Pin */
GPIO_InitStruct.Pin = LED_AUX_Pin|LED_MAIN_Pin|TXEN_Pin|RL_AUX_Pin; GPIO_InitStruct.Pin = WATER_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING_FALLING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(WATER_GPIO_Port, &GPIO_InitStruct);
/*Configure GPIO pins : ESTOP_Pin LIGHTS_SW_Pin */
GPIO_InitStruct.Pin = ESTOP_Pin|LIGHTS_SW_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/*Configure GPIO pins : RL_EN_Pin LED_AUX_Pin LED_MAIN_Pin TXEN_Pin
RL_AUX_Pin */
GPIO_InitStruct.Pin = RL_EN_Pin|LED_AUX_Pin|LED_MAIN_Pin|TXEN_Pin
|RL_AUX_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
@@ -346,18 +418,19 @@ static void MX_GPIO_Init(void)
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
/* EXTI interrupt init*/
HAL_NVIC_SetPriority(EXTI0_1_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(EXTI0_1_IRQn);
HAL_NVIC_SetPriority(EXTI4_15_IRQn, 0, 0);
HAL_NVIC_EnableIRQ(EXTI4_15_IRQn);
/* USER CODE BEGIN MX_GPIO_Init_2 */ /* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */ /* USER CODE END MX_GPIO_Init_2 */
} }
/* USER CODE BEGIN 4 */ /* USER CODE BEGIN 4 */
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
{
if(htim->Instance == TIM1) //check if the interrupt comes from TIM1
{
timer1_ovf_isr();
}
}
/* USER CODE END 4 */ /* USER CODE END 4 */
/** /**

View File

@@ -15,7 +15,7 @@ uint8_t recv_buffer[BUFFERS_SIZE];
uint8_t send_buffer[BUFFERS_SIZE]; uint8_t send_buffer[BUFFERS_SIZE];
uint16_t bytes_to_send = 0; uint16_t bytes_to_send = 0;
uint16_t last_rx_time = 0xFFFF; //uint16_t last_rx_time = 0xFFFF;
enum recv_state cmd_receiving = RECV_IDLE; enum recv_state cmd_receiving = RECV_IDLE;
enum send_state cmd_sending = SEND_IDLE; enum send_state cmd_sending = SEND_IDLE;
uint16_t tranfer_errors_count; uint16_t tranfer_errors_count;
@@ -79,14 +79,7 @@ void modbus_loop_iterate()
{ {
if (cmd_receiving == RECV_ERROR) if (cmd_receiving == RECV_ERROR)
{ {
// poor man's way to synchronize packets cmd_receiving = RECV_IDLE;
//if(last_rx_time>=BUS_IDLE_TIME)
//{
cmd_receiving = RECV_IDLE;
//TXEN_485 = 1;
//delay_us(10);
//TXEN_485 = 0;
//}
} }
if (cmd_receiving == RECV_IDLE) if (cmd_receiving == RECV_IDLE)
{ {

View File

@@ -20,7 +20,6 @@
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "main.h" #include "main.h"
/* USER CODE BEGIN Includes */ /* USER CODE BEGIN Includes */
/* USER CODE END Includes */ /* USER CODE END Includes */
@@ -63,11 +62,12 @@ extern DMA_HandleTypeDef hdma_usart1_tx;
/* USER CODE END 0 */ /* USER CODE END 0 */
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
/** /**
* Initializes the Global MSP. * Initializes the Global MSP.
*/ */
void HAL_MspInit(void) void HAL_MspInit(void)
{ {
/* USER CODE BEGIN MspInit 0 */ /* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */ /* USER CODE END MspInit 0 */
@@ -106,6 +106,17 @@ void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* htim_base)
/* USER CODE END TIM1_MspInit 1 */ /* USER CODE END TIM1_MspInit 1 */
} }
else if(htim_base->Instance==TIM14)
{
/* USER CODE BEGIN TIM14_MspInit 0 */
/* USER CODE END TIM14_MspInit 0 */
/* Peripheral clock enable */
__HAL_RCC_TIM14_CLK_ENABLE();
/* USER CODE BEGIN TIM14_MspInit 1 */
/* USER CODE END TIM14_MspInit 1 */
}
} }
@@ -139,12 +150,12 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
/* USER CODE BEGIN TIM3_MspPostInit 0 */ /* USER CODE BEGIN TIM3_MspPostInit 0 */
/* USER CODE END TIM3_MspPostInit 0 */ /* USER CODE END TIM3_MspPostInit 0 */
__HAL_RCC_GPIOB_CLK_ENABLE(); __HAL_RCC_GPIOB_CLK_ENABLE();
/**TIM3 GPIO Configuration /**TIM3 GPIO Configuration
PB4 ------> TIM3_CH1 PB4 ------> TIM3_CH1
PB5 ------> TIM3_CH2
*/ */
GPIO_InitStruct.Pin = GPIO_PIN_4; GPIO_InitStruct.Pin = GPIO_PIN_4|GPIO_PIN_5;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
@@ -155,6 +166,27 @@ void HAL_TIM_MspPostInit(TIM_HandleTypeDef* htim)
/* USER CODE END TIM3_MspPostInit 1 */ /* USER CODE END TIM3_MspPostInit 1 */
} }
else if(htim->Instance==TIM14)
{
/* USER CODE BEGIN TIM14_MspPostInit 0 */
/* USER CODE END TIM14_MspPostInit 0 */
__HAL_RCC_GPIOA_CLK_ENABLE();
/**TIM14 GPIO Configuration
PA4 ------> TIM14_CH1
*/
GPIO_InitStruct.Pin = LIGHTS_Pin;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF4_TIM14;
HAL_GPIO_Init(LIGHTS_GPIO_Port, &GPIO_InitStruct);
/* USER CODE BEGIN TIM14_MspPostInit 1 */
/* USER CODE END TIM14_MspPostInit 1 */
}
} }
/** /**
@@ -180,6 +212,17 @@ void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* htim_base)
/* USER CODE END TIM1_MspDeInit 1 */ /* USER CODE END TIM1_MspDeInit 1 */
} }
else if(htim_base->Instance==TIM14)
{
/* USER CODE BEGIN TIM14_MspDeInit 0 */
/* USER CODE END TIM14_MspDeInit 0 */
/* Peripheral clock disable */
__HAL_RCC_TIM14_CLK_DISABLE();
/* USER CODE BEGIN TIM14_MspDeInit 1 */
/* USER CODE END TIM14_MspDeInit 1 */
}
} }

View File

@@ -143,6 +143,35 @@ void SysTick_Handler(void)
/* please refer to the startup file (startup_stm32f0xx.s). */ /* please refer to the startup file (startup_stm32f0xx.s). */
/******************************************************************************/ /******************************************************************************/
/**
* @brief This function handles EXTI line 0 and 1 interrupts.
*/
void EXTI0_1_IRQHandler(void)
{
/* USER CODE BEGIN EXTI0_1_IRQn 0 */
/* USER CODE END EXTI0_1_IRQn 0 */
HAL_GPIO_EXTI_IRQHandler(WATER_Pin);
HAL_GPIO_EXTI_IRQHandler(ESTOP_Pin);
/* USER CODE BEGIN EXTI0_1_IRQn 1 */
/* USER CODE END EXTI0_1_IRQn 1 */
}
/**
* @brief This function handles EXTI line 4 to 15 interrupts.
*/
void EXTI4_15_IRQHandler(void)
{
/* USER CODE BEGIN EXTI4_15_IRQn 0 */
/* USER CODE END EXTI4_15_IRQn 0 */
HAL_GPIO_EXTI_IRQHandler(LIGHTS_SW_Pin);
/* USER CODE BEGIN EXTI4_15_IRQn 1 */
/* USER CODE END EXTI4_15_IRQn 1 */
}
/** /**
* @brief This function handles DMA1 channel 2 and 3 interrupts. * @brief This function handles DMA1 channel 2 and 3 interrupts.
*/ */

View File

@@ -7,7 +7,7 @@
****************************************************************************** ******************************************************************************
* @attention * @attention
* *
* Copyright (c) 2023 STMicroelectronics. * Copyright (c) 2021 STMicroelectronics.
* All rights reserved. * All rights reserved.
* *
* This software is licensed under terms that can be found in the LICENSE file * This software is licensed under terms that can be found in the LICENSE file
@@ -37,16 +37,12 @@ extern "C" {
#define AES_CLEARFLAG_CCF CRYP_CLEARFLAG_CCF #define AES_CLEARFLAG_CCF CRYP_CLEARFLAG_CCF
#define AES_CLEARFLAG_RDERR CRYP_CLEARFLAG_RDERR #define AES_CLEARFLAG_RDERR CRYP_CLEARFLAG_RDERR
#define AES_CLEARFLAG_WRERR CRYP_CLEARFLAG_WRERR #define AES_CLEARFLAG_WRERR CRYP_CLEARFLAG_WRERR
#if defined(STM32U5) || defined(STM32H7) || defined(STM32MP1) #if defined(STM32H7) || defined(STM32MP1)
#define CRYP_DATATYPE_32B CRYP_NO_SWAP #define CRYP_DATATYPE_32B CRYP_NO_SWAP
#define CRYP_DATATYPE_16B CRYP_HALFWORD_SWAP #define CRYP_DATATYPE_16B CRYP_HALFWORD_SWAP
#define CRYP_DATATYPE_8B CRYP_BYTE_SWAP #define CRYP_DATATYPE_8B CRYP_BYTE_SWAP
#define CRYP_DATATYPE_1B CRYP_BIT_SWAP #define CRYP_DATATYPE_1B CRYP_BIT_SWAP
#if defined(STM32U5) #endif /* STM32H7 || STM32MP1 */
#define CRYP_CCF_CLEAR CRYP_CLEAR_CCF
#define CRYP_ERR_CLEAR CRYP_CLEAR_RWEIF
#endif /* STM32U5 */
#endif /* STM32U5 || STM32H7 || STM32MP1 */
/** /**
* @} * @}
*/ */
@@ -279,7 +275,7 @@ extern "C" {
#define DAC_WAVEGENERATION_NOISE DAC_WAVE_NOISE #define DAC_WAVEGENERATION_NOISE DAC_WAVE_NOISE
#define DAC_WAVEGENERATION_TRIANGLE DAC_WAVE_TRIANGLE #define DAC_WAVEGENERATION_TRIANGLE DAC_WAVE_TRIANGLE
#if defined(STM32G4) || defined(STM32L5) || defined(STM32H7) || defined (STM32U5) #if defined(STM32G4) || defined(STM32H7) || defined (STM32U5)
#define DAC_CHIPCONNECT_DISABLE DAC_CHIPCONNECT_EXTERNAL #define DAC_CHIPCONNECT_DISABLE DAC_CHIPCONNECT_EXTERNAL
#define DAC_CHIPCONNECT_ENABLE DAC_CHIPCONNECT_INTERNAL #define DAC_CHIPCONNECT_ENABLE DAC_CHIPCONNECT_INTERNAL
#endif #endif
@@ -552,6 +548,16 @@ extern "C" {
#define OB_SRAM134_RST_ERASE OB_SRAM_RST_ERASE #define OB_SRAM134_RST_ERASE OB_SRAM_RST_ERASE
#define OB_SRAM134_RST_NOT_ERASE OB_SRAM_RST_NOT_ERASE #define OB_SRAM134_RST_NOT_ERASE OB_SRAM_RST_NOT_ERASE
#endif /* STM32U5 */ #endif /* STM32U5 */
#if defined(STM32U0)
#define OB_USER_nRST_STOP OB_USER_NRST_STOP
#define OB_USER_nRST_STDBY OB_USER_NRST_STDBY
#define OB_USER_nRST_SHDW OB_USER_NRST_SHDW
#define OB_USER_nBOOT_SEL OB_USER_NBOOT_SEL
#define OB_USER_nBOOT0 OB_USER_NBOOT0
#define OB_USER_nBOOT1 OB_USER_NBOOT1
#define OB_nBOOT0_RESET OB_NBOOT0_RESET
#define OB_nBOOT0_SET OB_NBOOT0_SET
#endif /* STM32U0 */
/** /**
* @} * @}
@@ -1243,10 +1249,10 @@ extern "C" {
#define RTC_TAMPERPIN_PA0 RTC_TAMPERPIN_POS1 #define RTC_TAMPERPIN_PA0 RTC_TAMPERPIN_POS1
#define RTC_TAMPERPIN_PI8 RTC_TAMPERPIN_POS1 #define RTC_TAMPERPIN_PI8 RTC_TAMPERPIN_POS1
#if defined(STM32H5) #if defined(STM32H5) || defined(STM32H7RS)
#define TAMP_SECRETDEVICE_ERASE_NONE TAMP_DEVICESECRETS_ERASE_NONE #define TAMP_SECRETDEVICE_ERASE_NONE TAMP_DEVICESECRETS_ERASE_NONE
#define TAMP_SECRETDEVICE_ERASE_BKP_SRAM TAMP_DEVICESECRETS_ERASE_BKPSRAM #define TAMP_SECRETDEVICE_ERASE_BKP_SRAM TAMP_DEVICESECRETS_ERASE_BKPSRAM
#endif /* STM32H5 */ #endif /* STM32H5 || STM32H7RS */
#if defined(STM32WBA) #if defined(STM32WBA)
#define TAMP_SECRETDEVICE_ERASE_NONE TAMP_DEVICESECRETS_ERASE_NONE #define TAMP_SECRETDEVICE_ERASE_NONE TAMP_DEVICESECRETS_ERASE_NONE
@@ -1258,10 +1264,10 @@ extern "C" {
#define TAMP_SECRETDEVICE_ERASE_ALL TAMP_DEVICESECRETS_ERASE_ALL #define TAMP_SECRETDEVICE_ERASE_ALL TAMP_DEVICESECRETS_ERASE_ALL
#endif /* STM32WBA */ #endif /* STM32WBA */
#if defined(STM32H5) || defined(STM32WBA) #if defined(STM32H5) || defined(STM32WBA) || defined(STM32H7RS)
#define TAMP_SECRETDEVICE_ERASE_DISABLE TAMP_DEVICESECRETS_ERASE_NONE #define TAMP_SECRETDEVICE_ERASE_DISABLE TAMP_DEVICESECRETS_ERASE_NONE
#define TAMP_SECRETDEVICE_ERASE_ENABLE TAMP_SECRETDEVICE_ERASE_ALL #define TAMP_SECRETDEVICE_ERASE_ENABLE TAMP_SECRETDEVICE_ERASE_ALL
#endif /* STM32H5 || STM32WBA */ #endif /* STM32H5 || STM32WBA || STM32H7RS */
#if defined(STM32F7) #if defined(STM32F7)
#define RTC_TAMPCR_TAMPXE RTC_TAMPER_ENABLE_BITS_MASK #define RTC_TAMPCR_TAMPXE RTC_TAMPER_ENABLE_BITS_MASK
@@ -1599,6 +1605,8 @@ extern "C" {
#define ETH_MAC_SMALL_FIFO_RW_ACTIVE 0x00000006U /* MAC small FIFO read / write controllers active */ #define ETH_MAC_SMALL_FIFO_RW_ACTIVE 0x00000006U /* MAC small FIFO read / write controllers active */
#define ETH_MAC_MII_RECEIVE_PROTOCOL_ACTIVE 0x00000001U /* MAC MII receive protocol engine active */ #define ETH_MAC_MII_RECEIVE_PROTOCOL_ACTIVE 0x00000001U /* MAC MII receive protocol engine active */
#define ETH_TxPacketConfig ETH_TxPacketConfigTypeDef /* Transmit Packet Configuration structure definition */
/** /**
* @} * @}
*/ */
@@ -1991,12 +1999,12 @@ extern "C" {
/** @defgroup HAL_RTC_Aliased_Functions HAL RTC Aliased Functions maintained for legacy purpose /** @defgroup HAL_RTC_Aliased_Functions HAL RTC Aliased Functions maintained for legacy purpose
* @{ * @{
*/ */
#if defined(STM32H5) || defined(STM32WBA) #if defined(STM32H5) || defined(STM32WBA) || defined(STM32H7RS)
#define HAL_RTCEx_SetBoothardwareKey HAL_RTCEx_LockBootHardwareKey #define HAL_RTCEx_SetBoothardwareKey HAL_RTCEx_LockBootHardwareKey
#define HAL_RTCEx_BKUPBlock_Enable HAL_RTCEx_BKUPBlock #define HAL_RTCEx_BKUPBlock_Enable HAL_RTCEx_BKUPBlock
#define HAL_RTCEx_BKUPBlock_Disable HAL_RTCEx_BKUPUnblock #define HAL_RTCEx_BKUPBlock_Disable HAL_RTCEx_BKUPUnblock
#define HAL_RTCEx_Erase_SecretDev_Conf HAL_RTCEx_ConfigEraseDeviceSecrets #define HAL_RTCEx_Erase_SecretDev_Conf HAL_RTCEx_ConfigEraseDeviceSecrets
#endif /* STM32H5 || STM32WBA */ #endif /* STM32H5 || STM32WBA || STM32H7RS */
/** /**
* @} * @}
@@ -2311,8 +2319,8 @@ extern "C" {
#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ #define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \
((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \
__HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) __HAL_COMP_COMP6_EXTI_CLEAR_FLAG())
# endif #endif
# if defined(STM32F302xE) || defined(STM32F302xC) #if defined(STM32F302xE) || defined(STM32F302xC)
#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ #define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \
((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \
@@ -2345,8 +2353,8 @@ extern "C" {
((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \
((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \
__HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) __HAL_COMP_COMP6_EXTI_CLEAR_FLAG())
# endif #endif
# if defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F303xC) || defined(STM32F358xx) #if defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F303xC) || defined(STM32F358xx)
#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ #define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \
((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_RISING_EDGE() : \ ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_RISING_EDGE() : \
@@ -2403,8 +2411,8 @@ extern "C" {
((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_CLEAR_FLAG() : \ ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_CLEAR_FLAG() : \
((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_CLEAR_FLAG() : \ ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_CLEAR_FLAG() : \
__HAL_COMP_COMP7_EXTI_CLEAR_FLAG()) __HAL_COMP_COMP7_EXTI_CLEAR_FLAG())
# endif #endif
# if defined(STM32F373xC) ||defined(STM32F378xx) #if defined(STM32F373xC) ||defined(STM32F378xx)
#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ #define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
__HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE())
#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ #define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \
@@ -2421,7 +2429,7 @@ extern "C" {
__HAL_COMP_COMP2_EXTI_GET_FLAG()) __HAL_COMP_COMP2_EXTI_GET_FLAG())
#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ #define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \
__HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) __HAL_COMP_COMP2_EXTI_CLEAR_FLAG())
# endif #endif
#else #else
#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ #define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \
__HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE())
@@ -2723,6 +2731,12 @@ extern "C" {
#define __APB1_RELEASE_RESET __HAL_RCC_APB1_RELEASE_RESET #define __APB1_RELEASE_RESET __HAL_RCC_APB1_RELEASE_RESET
#define __APB2_FORCE_RESET __HAL_RCC_APB2_FORCE_RESET #define __APB2_FORCE_RESET __HAL_RCC_APB2_FORCE_RESET
#define __APB2_RELEASE_RESET __HAL_RCC_APB2_RELEASE_RESET #define __APB2_RELEASE_RESET __HAL_RCC_APB2_RELEASE_RESET
#if defined(STM32C0)
#define __HAL_RCC_APB1_FORCE_RESET __HAL_RCC_APB1_GRP1_FORCE_RESET
#define __HAL_RCC_APB1_RELEASE_RESET __HAL_RCC_APB1_GRP1_RELEASE_RESET
#define __HAL_RCC_APB2_FORCE_RESET __HAL_RCC_APB1_GRP2_FORCE_RESET
#define __HAL_RCC_APB2_RELEASE_RESET __HAL_RCC_APB1_GRP2_RELEASE_RESET
#endif /* STM32C0 */
#define __BKP_CLK_DISABLE __HAL_RCC_BKP_CLK_DISABLE #define __BKP_CLK_DISABLE __HAL_RCC_BKP_CLK_DISABLE
#define __BKP_CLK_ENABLE __HAL_RCC_BKP_CLK_ENABLE #define __BKP_CLK_ENABLE __HAL_RCC_BKP_CLK_ENABLE
#define __BKP_FORCE_RESET __HAL_RCC_BKP_FORCE_RESET #define __BKP_FORCE_RESET __HAL_RCC_BKP_FORCE_RESET
@@ -3646,8 +3660,12 @@ extern "C" {
#define RCC_MCOSOURCE_PLLCLK_NODIV RCC_MCO1SOURCE_PLLCLK #define RCC_MCOSOURCE_PLLCLK_NODIV RCC_MCO1SOURCE_PLLCLK
#define RCC_MCOSOURCE_PLLCLK_DIV2 RCC_MCO1SOURCE_PLLCLK_DIV2 #define RCC_MCOSOURCE_PLLCLK_DIV2 RCC_MCO1SOURCE_PLLCLK_DIV2
#if defined(STM32U0)
#define RCC_SYSCLKSOURCE_STATUS_PLLR RCC_SYSCLKSOURCE_STATUS_PLLCLK
#endif
#if defined(STM32L4) || defined(STM32WB) || defined(STM32G0) || defined(STM32G4) || defined(STM32L5) || \ #if defined(STM32L4) || defined(STM32WB) || defined(STM32G0) || defined(STM32G4) || defined(STM32L5) || \
defined(STM32WL) || defined(STM32C0) defined(STM32WL) || defined(STM32C0) || defined(STM32H7RS) || defined(STM32U0)
#define RCC_RTCCLKSOURCE_NO_CLK RCC_RTCCLKSOURCE_NONE #define RCC_RTCCLKSOURCE_NO_CLK RCC_RTCCLKSOURCE_NONE
#else #else
#define RCC_RTCCLKSOURCE_NONE RCC_RTCCLKSOURCE_NO_CLK #define RCC_RTCCLKSOURCE_NONE RCC_RTCCLKSOURCE_NO_CLK
@@ -3749,8 +3767,10 @@ extern "C" {
#define __HAL_RCC_GET_DFSDM_SOURCE __HAL_RCC_GET_DFSDM1_SOURCE #define __HAL_RCC_GET_DFSDM_SOURCE __HAL_RCC_GET_DFSDM1_SOURCE
#define RCC_DFSDM1CLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 #define RCC_DFSDM1CLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2
#define RCC_SWPMI1CLKSOURCE_PCLK RCC_SWPMI1CLKSOURCE_PCLK1 #define RCC_SWPMI1CLKSOURCE_PCLK RCC_SWPMI1CLKSOURCE_PCLK1
#if !defined(STM32U0)
#define RCC_LPTIM1CLKSOURCE_PCLK RCC_LPTIM1CLKSOURCE_PCLK1 #define RCC_LPTIM1CLKSOURCE_PCLK RCC_LPTIM1CLKSOURCE_PCLK1
#define RCC_LPTIM2CLKSOURCE_PCLK RCC_LPTIM2CLKSOURCE_PCLK1 #define RCC_LPTIM2CLKSOURCE_PCLK RCC_LPTIM2CLKSOURCE_PCLK1
#endif
#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM1AUDIOCLKSOURCE_I2S1 #define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM1AUDIOCLKSOURCE_I2S1
#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM1AUDIOCLKSOURCE_I2S2 #define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM1AUDIOCLKSOURCE_I2S2
@@ -3896,7 +3916,8 @@ extern "C" {
*/ */
#if defined (STM32G0) || defined (STM32L5) || defined (STM32L412xx) || defined (STM32L422xx) || \ #if defined (STM32G0) || defined (STM32L5) || defined (STM32L412xx) || defined (STM32L422xx) || \
defined (STM32L4P5xx)|| defined (STM32L4Q5xx) || defined (STM32G4) || defined (STM32WL) || defined (STM32U5) || \ defined (STM32L4P5xx)|| defined (STM32L4Q5xx) || defined (STM32G4) || defined (STM32WL) || defined (STM32U5) || \
defined (STM32WBA) || defined (STM32H5) || defined (STM32C0) defined (STM32WBA) || defined (STM32H5) || \
defined (STM32C0) || defined (STM32H7RS) || defined (STM32U0)
#else #else
#define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG #define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG
#endif #endif
@@ -3931,6 +3952,13 @@ extern "C" {
__HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT())) __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT()))
#endif /* STM32F1 */ #endif /* STM32F1 */
#if defined (STM32F0) || defined (STM32F2) || defined (STM32F3) || defined (STM32F4) || defined (STM32F7) || \
defined (STM32H7) || \
defined (STM32L0) || defined (STM32L1) || \
defined (STM32WB)
#define __HAL_RTC_TAMPER_GET_IT __HAL_RTC_TAMPER_GET_FLAG
#endif
#define IS_ALARM IS_RTC_ALARM #define IS_ALARM IS_RTC_ALARM
#define IS_ALARM_MASK IS_RTC_ALARM_MASK #define IS_ALARM_MASK IS_RTC_ALARM_MASK
#define IS_TAMPER IS_RTC_TAMPER #define IS_TAMPER IS_RTC_TAMPER
@@ -4212,6 +4240,9 @@ extern "C" {
#define __HAL_TIM_GetCompare __HAL_TIM_GET_COMPARE #define __HAL_TIM_GetCompare __HAL_TIM_GET_COMPARE
#define TIM_BREAKINPUTSOURCE_DFSDM TIM_BREAKINPUTSOURCE_DFSDM1 #define TIM_BREAKINPUTSOURCE_DFSDM TIM_BREAKINPUTSOURCE_DFSDM1
#define TIM_OCMODE_ASSYMETRIC_PWM1 TIM_OCMODE_ASYMMETRIC_PWM1
#define TIM_OCMODE_ASSYMETRIC_PWM2 TIM_OCMODE_ASYMMETRIC_PWM2
/** /**
* @} * @}
*/ */

View File

@@ -236,8 +236,8 @@ typedef enum
*/ */
#define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET)) #define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET))
#define IS_GPIO_PIN(__PIN__) (((((uint32_t)__PIN__) & GPIO_PIN_MASK) != 0x00U) &&\ #define IS_GPIO_PIN(__PIN__) (((((uint32_t)(__PIN__)) & GPIO_PIN_MASK) != 0x00U) &&\
((((uint32_t)__PIN__) & ~GPIO_PIN_MASK) == 0x00U)) ((((uint32_t)(__PIN__)) & ~GPIO_PIN_MASK) == 0x00U))
#define IS_GPIO_MODE(__MODE__) (((__MODE__) == GPIO_MODE_INPUT) ||\ #define IS_GPIO_MODE(__MODE__) (((__MODE__) == GPIO_MODE_INPUT) ||\
((__MODE__) == GPIO_MODE_OUTPUT_PP) ||\ ((__MODE__) == GPIO_MODE_OUTPUT_PP) ||\

View File

@@ -118,8 +118,6 @@ typedef enum
HAL_I2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception HAL_I2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception
process is ongoing */ process is ongoing */
HAL_I2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ HAL_I2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */
HAL_I2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */
HAL_I2C_STATE_ERROR = 0xE0U /*!< Error */
} HAL_I2C_StateTypeDef; } HAL_I2C_StateTypeDef;

View File

@@ -385,29 +385,28 @@ typedef struct
*/ */
typedef enum typedef enum
{ {
HAL_TIM_BASE_MSPINIT_CB_ID = 0x00U /*!< TIM Base MspInit Callback ID */ HAL_TIM_BASE_MSPINIT_CB_ID = 0x00U /*!< TIM Base MspInit Callback ID */
, HAL_TIM_BASE_MSPDEINIT_CB_ID = 0x01U /*!< TIM Base MspDeInit Callback ID */ , HAL_TIM_BASE_MSPDEINIT_CB_ID = 0x01U /*!< TIM Base MspDeInit Callback ID */
, HAL_TIM_IC_MSPINIT_CB_ID = 0x02U /*!< TIM IC MspInit Callback ID */ , HAL_TIM_IC_MSPINIT_CB_ID = 0x02U /*!< TIM IC MspInit Callback ID */
, HAL_TIM_IC_MSPDEINIT_CB_ID = 0x03U /*!< TIM IC MspDeInit Callback ID */ , HAL_TIM_IC_MSPDEINIT_CB_ID = 0x03U /*!< TIM IC MspDeInit Callback ID */
, HAL_TIM_OC_MSPINIT_CB_ID = 0x04U /*!< TIM OC MspInit Callback ID */ , HAL_TIM_OC_MSPINIT_CB_ID = 0x04U /*!< TIM OC MspInit Callback ID */
, HAL_TIM_OC_MSPDEINIT_CB_ID = 0x05U /*!< TIM OC MspDeInit Callback ID */ , HAL_TIM_OC_MSPDEINIT_CB_ID = 0x05U /*!< TIM OC MspDeInit Callback ID */
, HAL_TIM_PWM_MSPINIT_CB_ID = 0x06U /*!< TIM PWM MspInit Callback ID */ , HAL_TIM_PWM_MSPINIT_CB_ID = 0x06U /*!< TIM PWM MspInit Callback ID */
, HAL_TIM_PWM_MSPDEINIT_CB_ID = 0x07U /*!< TIM PWM MspDeInit Callback ID */ , HAL_TIM_PWM_MSPDEINIT_CB_ID = 0x07U /*!< TIM PWM MspDeInit Callback ID */
, HAL_TIM_ONE_PULSE_MSPINIT_CB_ID = 0x08U /*!< TIM One Pulse MspInit Callback ID */ , HAL_TIM_ONE_PULSE_MSPINIT_CB_ID = 0x08U /*!< TIM One Pulse MspInit Callback ID */
, HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID = 0x09U /*!< TIM One Pulse MspDeInit Callback ID */ , HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID = 0x09U /*!< TIM One Pulse MspDeInit Callback ID */
, HAL_TIM_ENCODER_MSPINIT_CB_ID = 0x0AU /*!< TIM Encoder MspInit Callback ID */ , HAL_TIM_ENCODER_MSPINIT_CB_ID = 0x0AU /*!< TIM Encoder MspInit Callback ID */
, HAL_TIM_ENCODER_MSPDEINIT_CB_ID = 0x0BU /*!< TIM Encoder MspDeInit Callback ID */ , HAL_TIM_ENCODER_MSPDEINIT_CB_ID = 0x0BU /*!< TIM Encoder MspDeInit Callback ID */
, HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID = 0x0CU /*!< TIM Hall Sensor MspDeInit Callback ID */ , HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID = 0x0CU /*!< TIM Hall Sensor MspDeInit Callback ID */
, HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID = 0x0DU /*!< TIM Hall Sensor MspDeInit Callback ID */ , HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID = 0x0DU /*!< TIM Hall Sensor MspDeInit Callback ID */
, HAL_TIM_PERIOD_ELAPSED_CB_ID = 0x0EU /*!< TIM Period Elapsed Callback ID */ , HAL_TIM_PERIOD_ELAPSED_CB_ID = 0x0EU /*!< TIM Period Elapsed Callback ID */
, HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID = 0x0FU /*!< TIM Period Elapsed half complete Callback ID */ , HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID = 0x0FU /*!< TIM Period Elapsed half complete Callback ID */
, HAL_TIM_TRIGGER_CB_ID = 0x10U /*!< TIM Trigger Callback ID */ , HAL_TIM_TRIGGER_CB_ID = 0x10U /*!< TIM Trigger Callback ID */
, HAL_TIM_TRIGGER_HALF_CB_ID = 0x11U /*!< TIM Trigger half complete Callback ID */ , HAL_TIM_TRIGGER_HALF_CB_ID = 0x11U /*!< TIM Trigger half complete Callback ID */
, HAL_TIM_IC_CAPTURE_CB_ID = 0x12U /*!< TIM Input Capture Callback ID */ , HAL_TIM_IC_CAPTURE_CB_ID = 0x12U /*!< TIM Input Capture Callback ID */
, HAL_TIM_IC_CAPTURE_HALF_CB_ID = 0x13U /*!< TIM Input Capture half complete Callback ID */ , HAL_TIM_IC_CAPTURE_HALF_CB_ID = 0x13U /*!< TIM Input Capture half complete Callback ID */
, HAL_TIM_OC_DELAY_ELAPSED_CB_ID = 0x14U /*!< TIM Output Compare Delay Elapsed Callback ID */ , HAL_TIM_OC_DELAY_ELAPSED_CB_ID = 0x14U /*!< TIM Output Compare Delay Elapsed Callback ID */
, HAL_TIM_PWM_PULSE_FINISHED_CB_ID = 0x15U /*!< TIM PWM Pulse Finished Callback ID */ , HAL_TIM_PWM_PULSE_FINISHED_CB_ID = 0x15U /*!< TIM PWM Pulse Finished Callback ID */
, HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID = 0x16U /*!< TIM PWM Pulse Finished half complete Callback ID */ , HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID = 0x16U /*!< TIM PWM Pulse Finished half complete Callback ID */
, HAL_TIM_ERROR_CB_ID = 0x17U /*!< TIM Error Callback ID */ , HAL_TIM_ERROR_CB_ID = 0x17U /*!< TIM Error Callback ID */
, HAL_TIM_COMMUTATION_CB_ID = 0x18U /*!< TIM Commutation Callback ID */ , HAL_TIM_COMMUTATION_CB_ID = 0x18U /*!< TIM Commutation Callback ID */
@@ -1656,8 +1655,9 @@ typedef void (*pTIM_CallbackTypeDef)(TIM_HandleTypeDef *htim); /*!< pointer to
#define IS_TIM_OPM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ #define IS_TIM_OPM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \
((__CHANNEL__) == TIM_CHANNEL_2)) ((__CHANNEL__) == TIM_CHANNEL_2))
#define IS_TIM_PERIOD(__HANDLE__, __PERIOD__) \ #define IS_TIM_PERIOD(__HANDLE__, __PERIOD__) ((IS_TIM_32B_COUNTER_INSTANCE(((__HANDLE__)->Instance)) == 0U) ? \
((IS_TIM_32B_COUNTER_INSTANCE(((__HANDLE__)->Instance)) == 0U) ? (((__PERIOD__) > 0U) && ((__PERIOD__) <= 0x0000FFFFU)) : ((__PERIOD__) > 0U)) (((__PERIOD__) > 0U) && ((__PERIOD__) <= 0x0000FFFFU)) : \
((__PERIOD__) > 0U))
#define IS_TIM_COMPLEMENTARY_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ #define IS_TIM_COMPLEMENTARY_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \
((__CHANNEL__) == TIM_CHANNEL_2) || \ ((__CHANNEL__) == TIM_CHANNEL_2) || \
@@ -1710,7 +1710,6 @@ typedef void (*pTIM_CallbackTypeDef)(TIM_HandleTypeDef *htim); /*!< pointer to
#define IS_TIM_BREAK_FILTER(__BRKFILTER__) ((__BRKFILTER__) <= 0xFUL) #define IS_TIM_BREAK_FILTER(__BRKFILTER__) ((__BRKFILTER__) <= 0xFUL)
#define IS_TIM_BREAK_STATE(__STATE__) (((__STATE__) == TIM_BREAK_ENABLE) || \ #define IS_TIM_BREAK_STATE(__STATE__) (((__STATE__) == TIM_BREAK_ENABLE) || \
((__STATE__) == TIM_BREAK_DISABLE)) ((__STATE__) == TIM_BREAK_DISABLE))
@@ -2048,7 +2047,8 @@ HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_S
HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, const TIM_SlaveConfigTypeDef *sSlaveConfig); HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, const TIM_SlaveConfigTypeDef *sSlaveConfig);
HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, const TIM_SlaveConfigTypeDef *sSlaveConfig); HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, const TIM_SlaveConfigTypeDef *sSlaveConfig);
HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
uint32_t BurstRequestSrc, const uint32_t *BurstBuffer, uint32_t BurstLength); uint32_t BurstRequestSrc, const uint32_t *BurstBuffer,
uint32_t BurstLength);
HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
uint32_t BurstRequestSrc, const uint32_t *BurstBuffer, uint32_t BurstRequestSrc, const uint32_t *BurstBuffer,
uint32_t BurstLength, uint32_t DataLength); uint32_t BurstLength, uint32_t DataLength);

View File

@@ -145,7 +145,7 @@ HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *p
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size);
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size);
HAL_UART_RxEventTypeTypeDef HAL_UARTEx_GetRxEventType(UART_HandleTypeDef *huart); HAL_UART_RxEventTypeTypeDef HAL_UARTEx_GetRxEventType(const UART_HandleTypeDef *huart);
/** /**

View File

@@ -559,10 +559,10 @@ typedef struct
/** @defgroup TIM_LL_EC_COUNTERMODE Counter Mode /** @defgroup TIM_LL_EC_COUNTERMODE Counter Mode
* @{ * @{
*/ */
#define LL_TIM_COUNTERMODE_UP 0x00000000U /*!<Counter used as upcounter */ #define LL_TIM_COUNTERMODE_UP 0x00000000U /*!< Counter used as upcounter */
#define LL_TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as downcounter */ #define LL_TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as downcounter */
#define LL_TIM_COUNTERMODE_CENTER_DOWN TIM_CR1_CMS_0 /*!< The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting down. */ #define LL_TIM_COUNTERMODE_CENTER_DOWN TIM_CR1_CMS_0 /*!< The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting down. */
#define LL_TIM_COUNTERMODE_CENTER_UP TIM_CR1_CMS_1 /*!<The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting up */ #define LL_TIM_COUNTERMODE_CENTER_UP TIM_CR1_CMS_1 /*!< The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting up */
#define LL_TIM_COUNTERMODE_CENTER_UP_DOWN TIM_CR1_CMS /*!< The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting up or down. */ #define LL_TIM_COUNTERMODE_CENTER_UP_DOWN TIM_CR1_CMS /*!< The counter counts up and down alternatively. Output compare interrupt flags of output channels are set only when the counter is counting up or down. */
/** /**
* @} * @}
@@ -822,11 +822,11 @@ typedef struct
#define LL_TIM_ETR_FILTER_FDIV2_N8 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/2, N=8 */ #define LL_TIM_ETR_FILTER_FDIV2_N8 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/2, N=8 */
#define LL_TIM_ETR_FILTER_FDIV4_N6 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/4, N=6 */ #define LL_TIM_ETR_FILTER_FDIV4_N6 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/4, N=6 */
#define LL_TIM_ETR_FILTER_FDIV4_N8 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/4, N=8 */ #define LL_TIM_ETR_FILTER_FDIV4_N8 (TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/4, N=8 */
#define LL_TIM_ETR_FILTER_FDIV8_N6 TIM_SMCR_ETF_3 /*!< fSAMPLING=fDTS/8, N=8 */ #define LL_TIM_ETR_FILTER_FDIV8_N6 TIM_SMCR_ETF_3 /*!< fSAMPLING=fDTS/8, N=6 */
#define LL_TIM_ETR_FILTER_FDIV8_N8 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/16, N=5 */ #define LL_TIM_ETR_FILTER_FDIV8_N8 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/16, N=8 */
#define LL_TIM_ETR_FILTER_FDIV16_N5 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/16, N=6 */ #define LL_TIM_ETR_FILTER_FDIV16_N5 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/16, N=5 */
#define LL_TIM_ETR_FILTER_FDIV16_N6 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_1 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/16, N=8 */ #define LL_TIM_ETR_FILTER_FDIV16_N6 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_1 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/16, N=6 */
#define LL_TIM_ETR_FILTER_FDIV16_N8 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2) /*!< fSAMPLING=fDTS/16, N=5 */ #define LL_TIM_ETR_FILTER_FDIV16_N8 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2) /*!< fSAMPLING=fDTS/16, N=8 */
#define LL_TIM_ETR_FILTER_FDIV32_N5 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/32, N=5 */ #define LL_TIM_ETR_FILTER_FDIV32_N5 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2 | TIM_SMCR_ETF_0) /*!< fSAMPLING=fDTS/32, N=5 */
#define LL_TIM_ETR_FILTER_FDIV32_N6 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/32, N=6 */ #define LL_TIM_ETR_FILTER_FDIV32_N6 (TIM_SMCR_ETF_3 | TIM_SMCR_ETF_2 | TIM_SMCR_ETF_1) /*!< fSAMPLING=fDTS/32, N=6 */
#define LL_TIM_ETR_FILTER_FDIV32_N8 TIM_SMCR_ETF /*!< fSAMPLING=fDTS/32, N=8 */ #define LL_TIM_ETR_FILTER_FDIV32_N8 TIM_SMCR_ETF /*!< fSAMPLING=fDTS/32, N=8 */
@@ -1473,6 +1473,17 @@ __STATIC_INLINE void LL_TIM_CC_DisablePreload(TIM_TypeDef *TIMx)
CLEAR_BIT(TIMx->CR2, TIM_CR2_CCPC); CLEAR_BIT(TIMx->CR2, TIM_CR2_CCPC);
} }
/**
* @brief Indicates whether the capture/compare control bits (CCxE, CCxNE and OCxM) preload is enabled.
* @rmtoll CR2 CCPC LL_TIM_CC_IsEnabledPreload
* @param TIMx Timer instance
* @retval State of bit (1 or 0).
*/
__STATIC_INLINE uint32_t LL_TIM_CC_IsEnabledPreload(const TIM_TypeDef *TIMx)
{
return ((READ_BIT(TIMx->CR2, TIM_CR2_CCPC) == (TIM_CR2_CCPC)) ? 1UL : 0UL);
}
/** /**
* @brief Set the updated source of the capture/compare control bits (CCxE, CCxNE and OCxM). * @brief Set the updated source of the capture/compare control bits (CCxE, CCxNE and OCxM).
* @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check

View File

@@ -213,7 +213,7 @@ __STATIC_INLINE uint32_t LL_GetFlashSize(void)
* @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro) * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro)
* @note When a RTOS is used, it is recommended to avoid changing the SysTick * @note When a RTOS is used, it is recommended to avoid changing the SysTick
* configuration by calling this function, for a delay use rather osDelay RTOS service. * configuration by calling this function, for a delay use rather osDelay RTOS service.
* @param Ticks Number of ticks * @param Ticks Frequency of Ticks (Hz)
* @retval None * @retval None
*/ */
__STATIC_INLINE void LL_InitTick(uint32_t HCLKFrequency, uint32_t Ticks) __STATIC_INLINE void LL_InitTick(uint32_t HCLKFrequency, uint32_t Ticks)

View File

@@ -56,7 +56,7 @@
*/ */
#define __STM32F0xx_HAL_VERSION_MAIN (0x01U) /*!< [31:24] main version */ #define __STM32F0xx_HAL_VERSION_MAIN (0x01U) /*!< [31:24] main version */
#define __STM32F0xx_HAL_VERSION_SUB1 (0x07U) /*!< [23:16] sub1 version */ #define __STM32F0xx_HAL_VERSION_SUB1 (0x07U) /*!< [23:16] sub1 version */
#define __STM32F0xx_HAL_VERSION_SUB2 (0x07U) /*!< [15:8] sub2 version */ #define __STM32F0xx_HAL_VERSION_SUB2 (0x08U) /*!< [15:8] sub2 version */
#define __STM32F0xx_HAL_VERSION_RC (0x00U) /*!< [7:0] release candidate */ #define __STM32F0xx_HAL_VERSION_RC (0x00U) /*!< [7:0] release candidate */
#define __STM32F0xx_HAL_VERSION ((__STM32F0xx_HAL_VERSION_MAIN << 24U)\ #define __STM32F0xx_HAL_VERSION ((__STM32F0xx_HAL_VERSION_MAIN << 24U)\
|(__STM32F0xx_HAL_VERSION_SUB1 << 16U)\ |(__STM32F0xx_HAL_VERSION_SUB1 << 16U)\

View File

@@ -133,10 +133,13 @@
* @retval None * @retval None
*/ */
void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority) void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority)
{ {
/* Check the parameters */ /* Check the parameters */
assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority)); assert_param(IS_NVIC_PREEMPTION_PRIORITY(PreemptPriority));
NVIC_SetPriority(IRQn,PreemptPriority); NVIC_SetPriority(IRQn,PreemptPriority);
/* Prevent unused argument(s) compilation warning */
UNUSED(SubPriority);
} }
/** /**

View File

@@ -64,7 +64,7 @@
(++) Provide exiting handle as parameter. (++) Provide exiting handle as parameter.
(++) Provide pointer on EXTI_ConfigTypeDef structure as second parameter. (++) Provide pointer on EXTI_ConfigTypeDef structure as second parameter.
(#) Clear Exti configuration of a dedicated line using HAL_EXTI_GetConfigLine(). (#) Clear Exti configuration of a dedicated line using HAL_EXTI_ClearConfigLine().
(++) Provide exiting handle as parameter. (++) Provide exiting handle as parameter.
(#) Register callback to treat Exti interrupts using HAL_EXTI_RegisterCallback(). (#) Register callback to treat Exti interrupts using HAL_EXTI_RegisterCallback().
@@ -75,7 +75,7 @@
(#) Get interrupt pending bit using HAL_EXTI_GetPending(). (#) Get interrupt pending bit using HAL_EXTI_GetPending().
(#) Clear interrupt pending bit using HAL_EXTI_GetPending(). (#) Clear interrupt pending bit using HAL_EXTI_ClearPending().
(#) Generate software interrupt using HAL_EXTI_GenerateSWI(). (#) Generate software interrupt using HAL_EXTI_GenerateSWI().

View File

@@ -456,7 +456,7 @@ void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)
* until the next reset. * until the next reset.
* @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F0 family * @param GPIOx where x can be (A..F) to select the GPIO peripheral for STM32F0 family
* @param GPIO_Pin specifies the port bits to be locked. * @param GPIO_Pin specifies the port bits to be locked.
* This parameter can be any combination of GPIO_Pin_x where x can be (0..15). * This parameter can be any combination of GPIO_PIN_x where x can be (0..15).
* @retval None * @retval None
*/ */
HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin)

View File

@@ -90,7 +90,7 @@
add their own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() add their own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
(+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can
add their own code by customization of function pointer HAL_I2C_ErrorCallback() add their own code by customization of function pointer HAL_I2C_ErrorCallback()
(+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() (+) Abort a master or memory I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
(+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can
add their own code by customization of function pointer HAL_I2C_AbortCpltCallback() add their own code by customization of function pointer HAL_I2C_AbortCpltCallback()
(+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro. (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
@@ -156,7 +156,7 @@
HAL_I2C_Master_Seq_Receive_IT() or using HAL_I2C_Master_Seq_Receive_DMA() HAL_I2C_Master_Seq_Receive_IT() or using HAL_I2C_Master_Seq_Receive_DMA()
(+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and users can (+++) At reception end of current frame transfer, HAL_I2C_MasterRxCpltCallback() is executed and users can
add their own code by customization of function pointer HAL_I2C_MasterRxCpltCallback() add their own code by customization of function pointer HAL_I2C_MasterRxCpltCallback()
(++) Abort a master IT or DMA I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() (++) Abort a master or memory IT or DMA I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
(+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can (+++) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can
add their own code by customization of function pointer HAL_I2C_AbortCpltCallback() add their own code by customization of function pointer HAL_I2C_AbortCpltCallback()
(++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT() (++) Enable/disable the Address listen mode in slave I2C mode using HAL_I2C_EnableListen_IT()
@@ -214,7 +214,7 @@
add their own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback() add their own code by customization of function pointer HAL_I2C_SlaveRxCpltCallback()
(+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can (+) In case of transfer Error, HAL_I2C_ErrorCallback() function is executed and users can
add their own code by customization of function pointer HAL_I2C_ErrorCallback() add their own code by customization of function pointer HAL_I2C_ErrorCallback()
(+) Abort a master I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT() (+) Abort a master or memory I2C process communication with Interrupt using HAL_I2C_Master_Abort_IT()
(+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can (+) End of abort process, HAL_I2C_AbortCpltCallback() is executed and users can
add their own code by customization of function pointer HAL_I2C_AbortCpltCallback() add their own code by customization of function pointer HAL_I2C_AbortCpltCallback()
(+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro. (+) Discard a slave I2C process communication using __HAL_I2C_GENERATE_NACK() macro.
@@ -608,7 +608,12 @@ HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c)
/* Configure I2Cx: Addressing Master mode */ /* Configure I2Cx: Addressing Master mode */
if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT) if (hi2c->Init.AddressingMode == I2C_ADDRESSINGMODE_10BIT)
{ {
hi2c->Instance->CR2 = (I2C_CR2_ADD10); SET_BIT(hi2c->Instance->CR2, I2C_CR2_ADD10);
}
else
{
/* Clear the I2C ADD10 bit */
CLEAR_BIT(hi2c->Instance->CR2, I2C_CR2_ADD10);
} }
/* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */ /* Enable the AUTOEND by default, and enable NACK (should be disable only during Slave process */
hi2c->Instance->CR2 |= (I2C_CR2_AUTOEND | I2C_CR2_NACK); hi2c->Instance->CR2 |= (I2C_CR2_AUTOEND | I2C_CR2_NACK);
@@ -1115,6 +1120,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevA
uint16_t Size, uint32_t Timeout) uint16_t Size, uint32_t Timeout)
{ {
uint32_t tickstart; uint32_t tickstart;
uint32_t xfermode;
if (hi2c->State == HAL_I2C_STATE_READY) if (hi2c->State == HAL_I2C_STATE_READY)
{ {
@@ -1138,18 +1144,39 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevA
hi2c->XferCount = Size; hi2c->XferCount = Size;
hi2c->XferISR = NULL; hi2c->XferISR = NULL;
/* Send Slave Address */
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; hi2c->XferSize = MAX_NBYTE_SIZE;
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE, xfermode = I2C_RELOAD_MODE;
I2C_GENERATE_START_WRITE);
} }
else else
{ {
hi2c->XferSize = hi2c->XferCount; hi2c->XferSize = hi2c->XferCount;
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE, xfermode = I2C_AUTOEND_MODE;
}
if (hi2c->XferSize > 0U)
{
/* Preload TX register */
/* Write data to TXDR */
hi2c->Instance->TXDR = *hi2c->pBuffPtr;
/* Increment Buffer pointer */
hi2c->pBuffPtr++;
hi2c->XferCount--;
hi2c->XferSize--;
/* Send Slave Address */
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)(hi2c->XferSize + 1U), xfermode,
I2C_GENERATE_START_WRITE);
}
else
{
/* Send Slave Address */
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode,
I2C_GENERATE_START_WRITE); I2C_GENERATE_START_WRITE);
} }
@@ -1261,7 +1288,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAd
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; hi2c->XferSize = 1U;
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE, I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
I2C_GENERATE_START_READ); I2C_GENERATE_START_READ);
} }
@@ -1352,6 +1379,8 @@ HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData
uint32_t Timeout) uint32_t Timeout)
{ {
uint32_t tickstart; uint32_t tickstart;
uint16_t tmpXferCount;
HAL_StatusTypeDef error;
if (hi2c->State == HAL_I2C_STATE_READY) if (hi2c->State == HAL_I2C_STATE_READY)
{ {
@@ -1378,14 +1407,6 @@ HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData
/* Enable Address Acknowledge */ /* Enable Address Acknowledge */
hi2c->Instance->CR2 &= ~I2C_CR2_NACK; hi2c->Instance->CR2 &= ~I2C_CR2_NACK;
/* Wait until ADDR flag is set */
if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
{
/* Disable Address Acknowledge */
hi2c->Instance->CR2 |= I2C_CR2_NACK;
return HAL_ERROR;
}
/* Preload TX data if no stretch enable */ /* Preload TX data if no stretch enable */
if (hi2c->Init.NoStretchMode == I2C_NOSTRETCH_ENABLE) if (hi2c->Init.NoStretchMode == I2C_NOSTRETCH_ENABLE)
{ {
@@ -1399,6 +1420,18 @@ HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData
hi2c->XferCount--; hi2c->XferCount--;
} }
/* Wait until ADDR flag is set */
if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_ADDR, RESET, Timeout, tickstart) != HAL_OK)
{
/* Disable Address Acknowledge */
hi2c->Instance->CR2 |= I2C_CR2_NACK;
/* Flush TX register */
I2C_Flush_TXDR(hi2c);
return HAL_ERROR;
}
/* Clear ADDR flag */ /* Clear ADDR flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR); __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_ADDR);
@@ -1410,6 +1443,10 @@ HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData
{ {
/* Disable Address Acknowledge */ /* Disable Address Acknowledge */
hi2c->Instance->CR2 |= I2C_CR2_NACK; hi2c->Instance->CR2 |= I2C_CR2_NACK;
/* Flush TX register */
I2C_Flush_TXDR(hi2c);
return HAL_ERROR; return HAL_ERROR;
} }
@@ -1422,6 +1459,10 @@ HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData
{ {
/* Disable Address Acknowledge */ /* Disable Address Acknowledge */
hi2c->Instance->CR2 |= I2C_CR2_NACK; hi2c->Instance->CR2 |= I2C_CR2_NACK;
/* Flush TX register */
I2C_Flush_TXDR(hi2c);
return HAL_ERROR; return HAL_ERROR;
} }
@@ -1445,31 +1486,48 @@ HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData
} }
/* Wait until AF flag is set */ /* Wait until AF flag is set */
if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_AF, RESET, Timeout, tickstart) != HAL_OK) error = I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_AF, RESET, Timeout, tickstart);
if (error != HAL_OK)
{ {
/* Disable Address Acknowledge */ /* Check that I2C transfer finished */
hi2c->Instance->CR2 |= I2C_CR2_NACK; /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
return HAL_ERROR; /* Mean XferCount == 0 */
tmpXferCount = hi2c->XferCount;
if ((hi2c->ErrorCode == HAL_I2C_ERROR_AF) && (tmpXferCount == 0U))
{
/* Reset ErrorCode to NONE */
hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
}
else
{
/* Disable Address Acknowledge */
hi2c->Instance->CR2 |= I2C_CR2_NACK;
return HAL_ERROR;
}
} }
else
/* Flush TX register */
I2C_Flush_TXDR(hi2c);
/* Clear AF flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
/* Wait until STOP flag is set */
if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
{ {
/* Disable Address Acknowledge */ /* Flush TX register */
hi2c->Instance->CR2 |= I2C_CR2_NACK; I2C_Flush_TXDR(hi2c);
return HAL_ERROR; /* Clear AF flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
/* Wait until STOP flag is set */
if (I2C_WaitOnSTOPFlagUntilTimeout(hi2c, Timeout, tickstart) != HAL_OK)
{
/* Disable Address Acknowledge */
hi2c->Instance->CR2 |= I2C_CR2_NACK;
return HAL_ERROR;
}
/* Clear STOP flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
} }
/* Clear STOP flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
/* Wait until BUSY flag is reset */ /* Wait until BUSY flag is reset */
if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK) if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_BUSY, SET, Timeout, tickstart) != HAL_OK)
{ {
@@ -1672,7 +1730,26 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t D
/* Send Slave Address */ /* Send Slave Address */
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_WRITE); if (hi2c->XferSize > 0U)
{
/* Preload TX register */
/* Write data to TXDR */
hi2c->Instance->TXDR = *hi2c->pBuffPtr;
/* Increment Buffer pointer */
hi2c->pBuffPtr++;
hi2c->XferCount--;
hi2c->XferSize--;
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)(hi2c->XferSize + 1U), xfermode,
I2C_GENERATE_START_WRITE);
}
else
{
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode,
I2C_GENERATE_START_WRITE);
}
/* Process Unlocked */ /* Process Unlocked */
__HAL_UNLOCK(hi2c); __HAL_UNLOCK(hi2c);
@@ -1732,7 +1809,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t De
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; hi2c->XferSize = 1U;
xfermode = I2C_RELOAD_MODE; xfermode = I2C_RELOAD_MODE;
} }
else else
@@ -1895,6 +1972,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t
{ {
uint32_t xfermode; uint32_t xfermode;
HAL_StatusTypeDef dmaxferstatus; HAL_StatusTypeDef dmaxferstatus;
uint32_t sizetoxfer = 0U;
if (hi2c->State == HAL_I2C_STATE_READY) if (hi2c->State == HAL_I2C_STATE_READY)
{ {
@@ -1927,6 +2005,20 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t
xfermode = I2C_AUTOEND_MODE; xfermode = I2C_AUTOEND_MODE;
} }
if (hi2c->XferSize > 0U)
{
/* Preload TX register */
/* Write data to TXDR */
hi2c->Instance->TXDR = *hi2c->pBuffPtr;
/* Increment Buffer pointer */
hi2c->pBuffPtr++;
sizetoxfer = hi2c->XferSize;
hi2c->XferCount--;
hi2c->XferSize--;
}
if (hi2c->XferSize > 0U) if (hi2c->XferSize > 0U)
{ {
if (hi2c->hdmatx != NULL) if (hi2c->hdmatx != NULL)
@@ -1942,8 +2034,8 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t
hi2c->hdmatx->XferAbortCallback = NULL; hi2c->hdmatx->XferAbortCallback = NULL;
/* Enable the DMA channel */ /* Enable the DMA channel */
dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR, dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr,
hi2c->XferSize); (uint32_t)&hi2c->Instance->TXDR, hi2c->XferSize);
} }
else else
{ {
@@ -1964,7 +2056,8 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t
{ {
/* Send Slave Address */ /* Send Slave Address */
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, I2C_GENERATE_START_WRITE); I2C_TransferConfig(hi2c, DevAddress, (uint8_t)(hi2c->XferSize + 1U),
xfermode, I2C_GENERATE_START_WRITE);
/* Update XferCount value */ /* Update XferCount value */
hi2c->XferCount -= hi2c->XferSize; hi2c->XferCount -= hi2c->XferSize;
@@ -2003,7 +2096,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t
/* Send Slave Address */ /* Send Slave Address */
/* Set NBYTES to write and generate START condition */ /* Set NBYTES to write and generate START condition */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE, I2C_TransferConfig(hi2c, DevAddress, (uint8_t)sizetoxfer, I2C_AUTOEND_MODE,
I2C_GENERATE_START_WRITE); I2C_GENERATE_START_WRITE);
/* Process Unlocked */ /* Process Unlocked */
@@ -2065,7 +2158,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t D
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; hi2c->XferSize = 1U;
xfermode = I2C_RELOAD_MODE; xfermode = I2C_RELOAD_MODE;
} }
else else
@@ -2159,11 +2252,11 @@ HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t D
/* Note : The I2C interrupts must be enabled after unlocking current process /* Note : The I2C interrupts must be enabled after unlocking current process
to avoid the risk of I2C interrupt handle execution before current to avoid the risk of I2C interrupt handle execution before current
process unlock */ process unlock */
/* Enable ERR, TC, STOP, NACK, TXI interrupt */ /* Enable ERR, TC, STOP, NACK, RXI interrupt */
/* possible to enable all of these */ /* possible to enable all of these */
/* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT); I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
} }
return HAL_OK; return HAL_OK;
@@ -2612,7 +2705,7 @@ HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress,
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; hi2c->XferSize = 1U;
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE, I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE,
I2C_GENERATE_START_READ); I2C_GENERATE_START_READ);
} }
@@ -2650,7 +2743,7 @@ HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress,
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; hi2c->XferSize = 1U;
I2C_TransferConfig(hi2c, DevAddress, (uint8_t) hi2c->XferSize, I2C_RELOAD_MODE, I2C_TransferConfig(hi2c, DevAddress, (uint8_t) hi2c->XferSize, I2C_RELOAD_MODE,
I2C_NO_STARTSTOP); I2C_NO_STARTSTOP);
} }
@@ -2728,6 +2821,7 @@ HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddr
hi2c->ErrorCode = HAL_I2C_ERROR_NONE; hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
/* Prepare transfer parameters */ /* Prepare transfer parameters */
hi2c->XferSize = 0U;
hi2c->pBuffPtr = pData; hi2c->pBuffPtr = pData;
hi2c->XferCount = Size; hi2c->XferCount = Size;
hi2c->XferOptions = I2C_NO_OPTION_FRAME; hi2c->XferOptions = I2C_NO_OPTION_FRAME;
@@ -2849,11 +2943,11 @@ HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddre
to avoid the risk of I2C interrupt handle execution before current to avoid the risk of I2C interrupt handle execution before current
process unlock */ process unlock */
/* Enable ERR, TC, STOP, NACK, RXI interrupt */ /* Enable ERR, TC, STOP, NACK, TXI interrupt */
/* possible to enable all of these */ /* possible to enable all of these */
/* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
I2C_Enable_IRQ(hi2c, (I2C_XFER_TX_IT | I2C_XFER_RX_IT)); I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT);
return HAL_OK; return HAL_OK;
} }
@@ -3259,22 +3353,6 @@ HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAdd
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF); __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
} }
/* Check if the maximum allowed number of trials has been reached */
if (I2C_Trials == Trials)
{
/* Generate Stop */
hi2c->Instance->CR2 |= I2C_CR2_STOP;
/* Wait until STOPF flag is reset */
if (I2C_WaitOnFlagUntilTimeout(hi2c, I2C_FLAG_STOPF, RESET, Timeout, tickstart) != HAL_OK)
{
return HAL_ERROR;
}
/* Clear STOP Flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
}
/* Increment Trials */ /* Increment Trials */
I2C_Trials++; I2C_Trials++;
} while (I2C_Trials < Trials); } while (I2C_Trials < Trials);
@@ -3313,6 +3391,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16
{ {
uint32_t xfermode; uint32_t xfermode;
uint32_t xferrequest = I2C_GENERATE_START_WRITE; uint32_t xferrequest = I2C_GENERATE_START_WRITE;
uint32_t sizetoxfer = 0U;
/* Check the parameters */ /* Check the parameters */
assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
@@ -3344,6 +3423,21 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16
xfermode = hi2c->XferOptions; xfermode = hi2c->XferOptions;
} }
if ((hi2c->XferSize > 0U) && ((XferOptions == I2C_FIRST_FRAME) || \
(XferOptions == I2C_FIRST_AND_LAST_FRAME)))
{
/* Preload TX register */
/* Write data to TXDR */
hi2c->Instance->TXDR = *hi2c->pBuffPtr;
/* Increment Buffer pointer */
hi2c->pBuffPtr++;
sizetoxfer = hi2c->XferSize;
hi2c->XferCount--;
hi2c->XferSize--;
}
/* If transfer direction not change and there is no request to start another frame, /* If transfer direction not change and there is no request to start another frame,
do not generate Restart Condition */ do not generate Restart Condition */
/* Mean Previous state is same as current state */ /* Mean Previous state is same as current state */
@@ -3365,7 +3459,14 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16
} }
/* Send Slave Address and set NBYTES to write */ /* Send Slave Address and set NBYTES to write */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest); if ((XferOptions == I2C_FIRST_FRAME) || (XferOptions == I2C_FIRST_AND_LAST_FRAME))
{
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)sizetoxfer, xfermode, xferrequest);
}
else
{
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest);
}
/* Process Unlocked */ /* Process Unlocked */
__HAL_UNLOCK(hi2c); __HAL_UNLOCK(hi2c);
@@ -3405,6 +3506,7 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint1
uint32_t xfermode; uint32_t xfermode;
uint32_t xferrequest = I2C_GENERATE_START_WRITE; uint32_t xferrequest = I2C_GENERATE_START_WRITE;
HAL_StatusTypeDef dmaxferstatus; HAL_StatusTypeDef dmaxferstatus;
uint32_t sizetoxfer = 0U;
/* Check the parameters */ /* Check the parameters */
assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions)); assert_param(IS_I2C_TRANSFER_OPTIONS_REQUEST(XferOptions));
@@ -3436,6 +3538,21 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint1
xfermode = hi2c->XferOptions; xfermode = hi2c->XferOptions;
} }
if ((hi2c->XferSize > 0U) && ((XferOptions == I2C_FIRST_FRAME) || \
(XferOptions == I2C_FIRST_AND_LAST_FRAME)))
{
/* Preload TX register */
/* Write data to TXDR */
hi2c->Instance->TXDR = *hi2c->pBuffPtr;
/* Increment Buffer pointer */
hi2c->pBuffPtr++;
sizetoxfer = hi2c->XferSize;
hi2c->XferCount--;
hi2c->XferSize--;
}
/* If transfer direction not change and there is no request to start another frame, /* If transfer direction not change and there is no request to start another frame,
do not generate Restart Condition */ do not generate Restart Condition */
/* Mean Previous state is same as current state */ /* Mean Previous state is same as current state */
@@ -3471,8 +3588,8 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint1
hi2c->hdmatx->XferAbortCallback = NULL; hi2c->hdmatx->XferAbortCallback = NULL;
/* Enable the DMA channel */ /* Enable the DMA channel */
dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)pData, (uint32_t)&hi2c->Instance->TXDR, dmaxferstatus = HAL_DMA_Start_IT(hi2c->hdmatx, (uint32_t)hi2c->pBuffPtr,
hi2c->XferSize); (uint32_t)&hi2c->Instance->TXDR, hi2c->XferSize);
} }
else else
{ {
@@ -3492,7 +3609,14 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint1
if (dmaxferstatus == HAL_OK) if (dmaxferstatus == HAL_OK)
{ {
/* Send Slave Address and set NBYTES to write */ /* Send Slave Address and set NBYTES to write */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest); if ((XferOptions == I2C_FIRST_FRAME) || (XferOptions == I2C_FIRST_AND_LAST_FRAME))
{
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)sizetoxfer, xfermode, xferrequest);
}
else
{
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest);
}
/* Update XferCount value */ /* Update XferCount value */
hi2c->XferCount -= hi2c->XferSize; hi2c->XferCount -= hi2c->XferSize;
@@ -3531,8 +3655,14 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint1
/* Send Slave Address */ /* Send Slave Address */
/* Set NBYTES to write and generate START condition */ /* Set NBYTES to write and generate START condition */
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, I2C_AUTOEND_MODE, if ((XferOptions == I2C_FIRST_FRAME) || (XferOptions == I2C_FIRST_AND_LAST_FRAME))
I2C_GENERATE_START_WRITE); {
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)sizetoxfer, xfermode, xferrequest);
}
else
{
I2C_TransferConfig(hi2c, DevAddress, (uint8_t)hi2c->XferSize, xfermode, xferrequest);
}
/* Process Unlocked */ /* Process Unlocked */
__HAL_UNLOCK(hi2c); __HAL_UNLOCK(hi2c);
@@ -3795,11 +3925,11 @@ HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16
/* Note : The I2C interrupts must be enabled after unlocking current process /* Note : The I2C interrupts must be enabled after unlocking current process
to avoid the risk of I2C interrupt handle execution before current to avoid the risk of I2C interrupt handle execution before current
process unlock */ process unlock */
/* Enable ERR, TC, STOP, NACK, TXI interrupt */ /* Enable ERR, TC, STOP, NACK, RXI interrupt */
/* possible to enable all of these */ /* possible to enable all of these */
/* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | /* I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI |
I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */ I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_TXI */
I2C_Enable_IRQ(hi2c, I2C_XFER_TX_IT); I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
} }
return HAL_OK; return HAL_OK;
@@ -4434,7 +4564,7 @@ HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c)
} }
/** /**
* @brief Abort a master I2C IT or DMA process communication with Interrupt. * @brief Abort a master or memory I2C IT or DMA process communication with Interrupt.
* @param hi2c Pointer to a I2C_HandleTypeDef structure that contains * @param hi2c Pointer to a I2C_HandleTypeDef structure that contains
* the configuration information for the specified I2C. * the configuration information for the specified I2C.
* @param DevAddress Target device address: The device 7 bits address value * @param DevAddress Target device address: The device 7 bits address value
@@ -4443,7 +4573,9 @@ HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c)
*/ */
HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress) HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress)
{ {
if (hi2c->Mode == HAL_I2C_MODE_MASTER) HAL_I2C_ModeTypeDef tmp_mode = hi2c->Mode;
if ((tmp_mode == HAL_I2C_MODE_MASTER) || (tmp_mode == HAL_I2C_MODE_MEM))
{ {
/* Process Locked */ /* Process Locked */
__HAL_LOCK(hi2c); __HAL_LOCK(hi2c);
@@ -4842,17 +4974,22 @@ static HAL_StatusTypeDef I2C_Master_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uin
hi2c->XferSize--; hi2c->XferSize--;
hi2c->XferCount--; hi2c->XferCount--;
} }
else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TXIS) != RESET) && \ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TC) == RESET) && \
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TXI) != RESET)) ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TXIS) != RESET) && \
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TXI) != RESET)))
{ {
/* Write data to TXDR */ /* Write data to TXDR */
hi2c->Instance->TXDR = *hi2c->pBuffPtr; if (hi2c->XferCount != 0U)
{
/* Write data to TXDR */
hi2c->Instance->TXDR = *hi2c->pBuffPtr;
/* Increment Buffer pointer */ /* Increment Buffer pointer */
hi2c->pBuffPtr++; hi2c->pBuffPtr++;
hi2c->XferSize--; hi2c->XferSize--;
hi2c->XferCount--; hi2c->XferCount--;
}
} }
else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TCR) != RESET) && \ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TCR) != RESET) && \
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET)) (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
@@ -4863,7 +5000,15 @@ static HAL_StatusTypeDef I2C_Master_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uin
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; /* Errata workaround 170323 */
if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
{
hi2c->XferSize = 1U;
}
else
{
hi2c->XferSize = MAX_NBYTE_SIZE;
}
I2C_TransferConfig(hi2c, devaddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP); I2C_TransferConfig(hi2c, devaddress, (uint8_t)hi2c->XferSize, I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
} }
else else
@@ -5018,7 +5163,15 @@ static HAL_StatusTypeDef I2C_Mem_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32
{ {
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; /* Errata workaround 170323 */
if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
{
hi2c->XferSize = 1U;
}
else
{
hi2c->XferSize = MAX_NBYTE_SIZE;
}
I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize, I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize,
I2C_RELOAD_MODE, I2C_NO_STARTSTOP); I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
} }
@@ -5039,6 +5192,12 @@ static HAL_StatusTypeDef I2C_Mem_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32
else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TC) != RESET) && \ else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_TC) != RESET) && \
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET)) (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
{ {
/* Disable Interrupt related to address step */
I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
/* Enable ERR, TC, STOP, NACK and RXI interrupts */
I2C_Enable_IRQ(hi2c, I2C_XFER_RX_IT);
if (hi2c->State == HAL_I2C_STATE_BUSY_RX) if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
{ {
direction = I2C_GENERATE_START_READ; direction = I2C_GENERATE_START_READ;
@@ -5046,7 +5205,15 @@ static HAL_StatusTypeDef I2C_Mem_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint32
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; /* Errata workaround 170323 */
if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
{
hi2c->XferSize = 1U;
}
else
{
hi2c->XferSize = MAX_NBYTE_SIZE;
}
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize, I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize,
@@ -5103,9 +5270,8 @@ static HAL_StatusTypeDef I2C_Slave_ISR_IT(struct __I2C_HandleTypeDef *hi2c, uint
/* Call I2C Slave complete process */ /* Call I2C Slave complete process */
I2C_ITSlaveCplt(hi2c, tmpITFlags); I2C_ITSlaveCplt(hi2c, tmpITFlags);
} }
else if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_AF) != RESET) && \
if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_AF) != RESET) && \ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
{ {
/* Check that I2C transfer finished */ /* Check that I2C transfer finished */
/* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */ /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
@@ -5268,7 +5434,15 @@ static HAL_StatusTypeDef I2C_Master_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, ui
/* Prepare the new XferSize to transfer */ /* Prepare the new XferSize to transfer */
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; /* Errata workaround 170323 */
if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
{
hi2c->XferSize = 1U;
}
else
{
hi2c->XferSize = MAX_NBYTE_SIZE;
}
xfermode = I2C_RELOAD_MODE; xfermode = I2C_RELOAD_MODE;
} }
else else
@@ -5405,6 +5579,9 @@ static HAL_StatusTypeDef I2C_Mem_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint3
else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_TCR) != RESET) && \ else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_TCR) != RESET) && \
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET)) (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
{ {
/* Disable Interrupt related to address step */
I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
/* Enable only Error interrupt */ /* Enable only Error interrupt */
I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT); I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
@@ -5413,7 +5590,15 @@ static HAL_StatusTypeDef I2C_Mem_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint3
/* Prepare the new XferSize to transfer */ /* Prepare the new XferSize to transfer */
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; /* Errata workaround 170323 */
if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
{
hi2c->XferSize = 1U;
}
else
{
hi2c->XferSize = MAX_NBYTE_SIZE;
}
I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize, I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize,
I2C_RELOAD_MODE, I2C_NO_STARTSTOP); I2C_RELOAD_MODE, I2C_NO_STARTSTOP);
} }
@@ -5447,6 +5632,12 @@ static HAL_StatusTypeDef I2C_Mem_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint3
else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_TC) != RESET) && \ else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_TC) != RESET) && \
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET)) (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_TCI) != RESET))
{ {
/* Disable Interrupt related to address step */
I2C_Disable_IRQ(hi2c, I2C_XFER_TX_IT);
/* Enable only Error and NACK interrupt for data transfer */
I2C_Enable_IRQ(hi2c, I2C_XFER_ERROR_IT);
if (hi2c->State == HAL_I2C_STATE_BUSY_RX) if (hi2c->State == HAL_I2C_STATE_BUSY_RX)
{ {
direction = I2C_GENERATE_START_READ; direction = I2C_GENERATE_START_READ;
@@ -5454,7 +5645,15 @@ static HAL_StatusTypeDef I2C_Mem_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uint3
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; /* Errata workaround 170323 */
if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
{
hi2c->XferSize = 1U;
}
else
{
hi2c->XferSize = MAX_NBYTE_SIZE;
}
/* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */ /* Set NBYTES to write and reload if hi2c->XferCount > MAX_NBYTE_SIZE and generate RESTART */
I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize, I2C_TransferConfig(hi2c, (uint16_t)hi2c->Devaddress, (uint8_t)hi2c->XferSize,
@@ -5524,9 +5723,8 @@ static HAL_StatusTypeDef I2C_Slave_ISR_DMA(struct __I2C_HandleTypeDef *hi2c, uin
/* Call I2C Slave complete process */ /* Call I2C Slave complete process */
I2C_ITSlaveCplt(hi2c, ITFlags); I2C_ITSlaveCplt(hi2c, ITFlags);
} }
else if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_AF) != RESET) && \
if ((I2C_CHECK_FLAG(ITFlags, I2C_FLAG_AF) != RESET) && \ (I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
(I2C_CHECK_IT_SOURCE(ITSources, I2C_IT_NACKI) != RESET))
{ {
/* Check that I2C transfer finished */ /* Check that I2C transfer finished */
/* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */ /* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
@@ -6125,6 +6323,7 @@ static void I2C_ITSlaveCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
{ {
uint32_t tmpcr1value = READ_REG(hi2c->Instance->CR1); uint32_t tmpcr1value = READ_REG(hi2c->Instance->CR1);
uint32_t tmpITFlags = ITFlags; uint32_t tmpITFlags = ITFlags;
uint32_t tmpoptions = hi2c->XferOptions;
HAL_I2C_StateTypeDef tmpstate = hi2c->State; HAL_I2C_StateTypeDef tmpstate = hi2c->State;
/* Clear STOP Flag */ /* Clear STOP Flag */
@@ -6141,6 +6340,11 @@ static void I2C_ITSlaveCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT); I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_RX_IT);
hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX; hi2c->PreviousState = I2C_STATE_SLAVE_BUSY_RX;
} }
else if (tmpstate == HAL_I2C_STATE_LISTEN)
{
I2C_Disable_IRQ(hi2c, I2C_XFER_LISTEN_IT | I2C_XFER_TX_IT | I2C_XFER_RX_IT);
hi2c->PreviousState = I2C_STATE_NONE;
}
else else
{ {
/* Do nothing */ /* Do nothing */
@@ -6207,6 +6411,57 @@ static void I2C_ITSlaveCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
hi2c->ErrorCode |= HAL_I2C_ERROR_AF; hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
} }
if ((I2C_CHECK_FLAG(tmpITFlags, I2C_FLAG_AF) != RESET) && \
(I2C_CHECK_IT_SOURCE(tmpcr1value, I2C_IT_NACKI) != RESET))
{
/* Check that I2C transfer finished */
/* if yes, normal use case, a NACK is sent by the MASTER when Transfer is finished */
/* Mean XferCount == 0*/
/* So clear Flag NACKF only */
if (hi2c->XferCount == 0U)
{
if ((hi2c->State == HAL_I2C_STATE_LISTEN) && (tmpoptions == I2C_FIRST_AND_LAST_FRAME))
/* Same action must be done for (tmpoptions == I2C_LAST_FRAME) which removed for
Warning[Pa134]: left and right operands are identical */
{
/* Call I2C Listen complete process */
I2C_ITListenCplt(hi2c, tmpITFlags);
}
else if ((hi2c->State == HAL_I2C_STATE_BUSY_TX_LISTEN) && (tmpoptions != I2C_NO_OPTION_FRAME))
{
/* Clear NACK Flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
/* Flush TX register */
I2C_Flush_TXDR(hi2c);
/* Last Byte is Transmitted */
/* Call I2C Slave Sequential complete process */
I2C_ITSlaveSeqCplt(hi2c);
}
else
{
/* Clear NACK Flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
}
}
else
{
/* if no, error use case, a Non-Acknowledge of last Data is generated by the MASTER*/
/* Clear NACK Flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
/* Set ErrorCode corresponding to a Non-Acknowledge */
hi2c->ErrorCode |= HAL_I2C_ERROR_AF;
if ((tmpoptions == I2C_FIRST_FRAME) || (tmpoptions == I2C_NEXT_FRAME))
{
/* Call the corresponding callback to inform upper layer of End of Transfer */
I2C_ITError(hi2c, hi2c->ErrorCode);
}
}
}
hi2c->Mode = HAL_I2C_MODE_NONE; hi2c->Mode = HAL_I2C_MODE_NONE;
hi2c->XferISR = NULL; hi2c->XferISR = NULL;
@@ -6624,7 +6879,15 @@ static void I2C_DMAMasterReceiveCplt(DMA_HandleTypeDef *hdma)
/* Set the XferSize to transfer */ /* Set the XferSize to transfer */
if (hi2c->XferCount > MAX_NBYTE_SIZE) if (hi2c->XferCount > MAX_NBYTE_SIZE)
{ {
hi2c->XferSize = MAX_NBYTE_SIZE; /* Errata workaround 170323 */
if (I2C_GET_DIR(hi2c) == I2C_DIRECTION_RECEIVE)
{
hi2c->XferSize = 1U;
}
else
{
hi2c->XferSize = MAX_NBYTE_SIZE;
}
} }
else else
{ {
@@ -6735,6 +6998,12 @@ static HAL_StatusTypeDef I2C_WaitOnFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uin
{ {
while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status) while (__HAL_I2C_GET_FLAG(hi2c, Flag) == Status)
{ {
/* Check if an error is detected */
if (I2C_IsErrorOccurred(hi2c, Timeout, Tickstart) != HAL_OK)
{
return HAL_ERROR;
}
/* Check for the Timeout */ /* Check for the Timeout */
if (Timeout != HAL_MAX_DELAY) if (Timeout != HAL_MAX_DELAY)
{ {
@@ -6846,16 +7115,18 @@ static HAL_StatusTypeDef I2C_WaitOnSTOPFlagUntilTimeout(I2C_HandleTypeDef *hi2c,
static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout, static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c, uint32_t Timeout,
uint32_t Tickstart) uint32_t Tickstart)
{ {
while (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET) HAL_StatusTypeDef status = HAL_OK;
while ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET) && (status == HAL_OK))
{ {
/* Check if an error is detected */ /* Check if an error is detected */
if (I2C_IsErrorOccurred(hi2c, Timeout, Tickstart) != HAL_OK) if (I2C_IsErrorOccurred(hi2c, Timeout, Tickstart) != HAL_OK)
{ {
return HAL_ERROR; status = HAL_ERROR;
} }
/* Check if a STOPF is detected */ /* Check if a STOPF is detected */
if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET) if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_STOPF) == SET) && (status == HAL_OK))
{ {
/* Check if an RXNE is pending */ /* Check if an RXNE is pending */
/* Store Last receive data if any */ /* Store Last receive data if any */
@@ -6863,19 +7134,14 @@ static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c,
{ {
/* Return HAL_OK */ /* Return HAL_OK */
/* The Reading of data from RXDR will be done in caller function */ /* The Reading of data from RXDR will be done in caller function */
return HAL_OK; status = HAL_OK;
} }
else
/* Check a no-acknowledge have been detected */
if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET)
{ {
if (__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_AF) == SET) __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
{ hi2c->ErrorCode = HAL_I2C_ERROR_AF;
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_AF);
hi2c->ErrorCode = HAL_I2C_ERROR_AF;
}
else
{
hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
}
/* Clear STOP Flag */ /* Clear STOP Flag */
__HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF); __HAL_I2C_CLEAR_FLAG(hi2c, I2C_FLAG_STOPF);
@@ -6889,12 +7155,16 @@ static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c,
/* Process Unlocked */ /* Process Unlocked */
__HAL_UNLOCK(hi2c); __HAL_UNLOCK(hi2c);
return HAL_ERROR; status = HAL_ERROR;
}
else
{
hi2c->ErrorCode = HAL_I2C_ERROR_NONE;
} }
} }
/* Check for the Timeout */ /* Check for the Timeout */
if (((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) if ((((HAL_GetTick() - Tickstart) > Timeout) || (Timeout == 0U)) && (status == HAL_OK))
{ {
if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET)) if ((__HAL_I2C_GET_FLAG(hi2c, I2C_FLAG_RXNE) == RESET))
{ {
@@ -6904,11 +7174,11 @@ static HAL_StatusTypeDef I2C_WaitOnRXNEFlagUntilTimeout(I2C_HandleTypeDef *hi2c,
/* Process Unlocked */ /* Process Unlocked */
__HAL_UNLOCK(hi2c); __HAL_UNLOCK(hi2c);
return HAL_ERROR; status = HAL_ERROR;
} }
} }
} }
return HAL_OK; return status;
} }
/** /**
@@ -7103,13 +7373,13 @@ static void I2C_Enable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest)
if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT) if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT)
{ {
/* Enable ERR, TC, STOP, NACK and RXI interrupts */ /* Enable ERR, TC, STOP, NACK and TXI interrupts */
tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_TXI; tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_TXI;
} }
if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT) if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT)
{ {
/* Enable ERR, TC, STOP, NACK and TXI interrupts */ /* Enable ERR, TC, STOP, NACK and RXI interrupts */
tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_RXI; tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_RXI;
} }
@@ -7136,13 +7406,13 @@ static void I2C_Enable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest)
if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT) if ((InterruptRequest & I2C_XFER_TX_IT) == I2C_XFER_TX_IT)
{ {
/* Enable ERR, TC, STOP, NACK and RXI interrupts */ /* Enable ERR, TC, STOP, NACK and TXI interrupts */
tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_TXI; tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_TXI;
} }
if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT) if ((InterruptRequest & I2C_XFER_RX_IT) == I2C_XFER_RX_IT)
{ {
/* Enable ERR, TC, STOP, NACK and TXI interrupts */ /* Enable ERR, TC, STOP, NACK and RXI interrupts */
tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_RXI; tmpisr |= I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_RXI;
} }
@@ -7158,7 +7428,7 @@ static void I2C_Enable_IRQ(I2C_HandleTypeDef *hi2c, uint16_t InterruptRequest)
tmpisr |= (I2C_IT_STOPI | I2C_IT_TCI); tmpisr |= (I2C_IT_STOPI | I2C_IT_TCI);
} }
if ((hi2c->XferISR != I2C_Mem_ISR_DMA) && (InterruptRequest == I2C_XFER_RELOAD_IT)) if (InterruptRequest == I2C_XFER_RELOAD_IT)
{ {
/* Enable TC interrupts */ /* Enable TC interrupts */
tmpisr |= I2C_IT_TCI; tmpisr |= I2C_IT_TCI;

View File

@@ -1021,7 +1021,10 @@ void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_M
assert_param(IS_RCC_MCO(RCC_MCOx)); assert_param(IS_RCC_MCO(RCC_MCOx));
assert_param(IS_RCC_MCODIV(RCC_MCODiv)); assert_param(IS_RCC_MCODIV(RCC_MCODiv));
assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource)); assert_param(IS_RCC_MCO1SOURCE(RCC_MCOSource));
/* Prevent unused argument(s) compilation warning */
UNUSED(RCC_MCOx);
/* Configure the MCO1 pin in alternate function mode */ /* Configure the MCO1 pin in alternate function mode */
gpio.Mode = GPIO_MODE_AF_PP; gpio.Mode = GPIO_MODE_AF_PP;
gpio.Speed = GPIO_SPEED_FREQ_HIGH; gpio.Speed = GPIO_SPEED_FREQ_HIGH;

View File

@@ -3822,13 +3822,16 @@ HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Cha
*/ */
void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim) void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
{ {
uint32_t itsource = htim->Instance->DIER;
uint32_t itflag = htim->Instance->SR;
/* Capture compare 1 event */ /* Capture compare 1 event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC1) != RESET) if ((itflag & (TIM_FLAG_CC1)) == (TIM_FLAG_CC1))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC1) != RESET) if ((itsource & (TIM_IT_CC1)) == (TIM_IT_CC1))
{ {
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_IT_CC1); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_CC1);
htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1; htim->Channel = HAL_TIM_ACTIVE_CHANNEL_1;
/* Input capture event */ /* Input capture event */
@@ -3856,11 +3859,11 @@ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
} }
} }
/* Capture compare 2 event */ /* Capture compare 2 event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC2) != RESET) if ((itflag & (TIM_FLAG_CC2)) == (TIM_FLAG_CC2))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC2) != RESET) if ((itsource & (TIM_IT_CC2)) == (TIM_IT_CC2))
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_IT_CC2); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_CC2);
htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2; htim->Channel = HAL_TIM_ACTIVE_CHANNEL_2;
/* Input capture event */ /* Input capture event */
if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U) if ((htim->Instance->CCMR1 & TIM_CCMR1_CC2S) != 0x00U)
@@ -3886,11 +3889,11 @@ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
} }
} }
/* Capture compare 3 event */ /* Capture compare 3 event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC3) != RESET) if ((itflag & (TIM_FLAG_CC3)) == (TIM_FLAG_CC3))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC3) != RESET) if ((itsource & (TIM_IT_CC3)) == (TIM_IT_CC3))
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_IT_CC3); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_CC3);
htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3; htim->Channel = HAL_TIM_ACTIVE_CHANNEL_3;
/* Input capture event */ /* Input capture event */
if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U) if ((htim->Instance->CCMR2 & TIM_CCMR2_CC3S) != 0x00U)
@@ -3916,11 +3919,11 @@ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
} }
} }
/* Capture compare 4 event */ /* Capture compare 4 event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_CC4) != RESET) if ((itflag & (TIM_FLAG_CC4)) == (TIM_FLAG_CC4))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_CC4) != RESET) if ((itsource & (TIM_IT_CC4)) == (TIM_IT_CC4))
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_IT_CC4); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_CC4);
htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4; htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
/* Input capture event */ /* Input capture event */
if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U) if ((htim->Instance->CCMR2 & TIM_CCMR2_CC4S) != 0x00U)
@@ -3946,11 +3949,11 @@ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
} }
} }
/* TIM Update event */ /* TIM Update event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_UPDATE) != RESET) if ((itflag & (TIM_FLAG_UPDATE)) == (TIM_FLAG_UPDATE))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_UPDATE) != RESET) if ((itsource & (TIM_IT_UPDATE)) == (TIM_IT_UPDATE))
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_IT_UPDATE); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_UPDATE);
#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
htim->PeriodElapsedCallback(htim); htim->PeriodElapsedCallback(htim);
#else #else
@@ -3959,11 +3962,11 @@ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
} }
} }
/* TIM Break input event */ /* TIM Break input event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_BREAK) != RESET) if ((itflag & (TIM_FLAG_BREAK)) == (TIM_FLAG_BREAK))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_BREAK) != RESET) if ((itsource & (TIM_IT_BREAK)) == (TIM_IT_BREAK))
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_IT_BREAK); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_BREAK);
#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
htim->BreakCallback(htim); htim->BreakCallback(htim);
#else #else
@@ -3972,11 +3975,11 @@ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
} }
} }
/* TIM Trigger detection event */ /* TIM Trigger detection event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_TRIGGER) != RESET) if ((itflag & (TIM_FLAG_TRIGGER)) == (TIM_FLAG_TRIGGER))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_TRIGGER) != RESET) if ((itsource & (TIM_IT_TRIGGER)) == (TIM_IT_TRIGGER))
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_IT_TRIGGER); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_TRIGGER);
#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
htim->TriggerCallback(htim); htim->TriggerCallback(htim);
#else #else
@@ -3985,11 +3988,11 @@ void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim)
} }
} }
/* TIM commutation event */ /* TIM commutation event */
if (__HAL_TIM_GET_FLAG(htim, TIM_FLAG_COM) != RESET) if ((itflag & (TIM_FLAG_COM)) == (TIM_FLAG_COM))
{ {
if (__HAL_TIM_GET_IT_SOURCE(htim, TIM_IT_COM) != RESET) if ((itsource & (TIM_IT_COM)) == (TIM_IT_COM))
{ {
__HAL_TIM_CLEAR_IT(htim, TIM_FLAG_COM); __HAL_TIM_CLEAR_FLAG(htim, TIM_FLAG_COM);
#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) #if (USE_HAL_TIM_REGISTER_CALLBACKS == 1)
htim->CommutationCallback(htim); htim->CommutationCallback(htim);
#else #else
@@ -4476,7 +4479,8 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_O
* @retval HAL status * @retval HAL status
*/ */
HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress,
uint32_t BurstRequestSrc, const uint32_t *BurstBuffer, uint32_t BurstLength) uint32_t BurstRequestSrc, const uint32_t *BurstBuffer,
uint32_t BurstLength)
{ {
HAL_StatusTypeDef status; HAL_StatusTypeDef status;
@@ -6819,6 +6823,13 @@ void TIM_Base_SetConfig(TIM_TypeDef *TIMx, const TIM_Base_InitTypeDef *Structure
/* Generate an update event to reload the Prescaler /* Generate an update event to reload the Prescaler
and the repetition counter (only for advanced timer) value immediately */ and the repetition counter (only for advanced timer) value immediately */
TIMx->EGR = TIM_EGR_UG; TIMx->EGR = TIM_EGR_UG;
/* Check if the update flag is set after the Update Generation, if so clear the UIF flag */
if (HAL_IS_BIT_SET(TIMx->SR, TIM_FLAG_UPDATE))
{
/* Clear the update flag */
CLEAR_BIT(TIMx->SR, TIM_FLAG_UPDATE);
}
} }
/** /**
@@ -6833,11 +6844,12 @@ static void TIM_OC1_SetConfig(TIM_TypeDef *TIMx, const TIM_OC_InitTypeDef *OC_Co
uint32_t tmpccer; uint32_t tmpccer;
uint32_t tmpcr2; uint32_t tmpcr2;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Disable the Channel 1: Reset the CC1E Bit */ /* Disable the Channel 1: Reset the CC1E Bit */
TIMx->CCER &= ~TIM_CCER_CC1E; TIMx->CCER &= ~TIM_CCER_CC1E;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Get the TIMx CR2 register value */ /* Get the TIMx CR2 register value */
tmpcr2 = TIMx->CR2; tmpcr2 = TIMx->CR2;
@@ -6908,11 +6920,12 @@ void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, const TIM_OC_InitTypeDef *OC_Config)
uint32_t tmpccer; uint32_t tmpccer;
uint32_t tmpcr2; uint32_t tmpcr2;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Disable the Channel 2: Reset the CC2E Bit */ /* Disable the Channel 2: Reset the CC2E Bit */
TIMx->CCER &= ~TIM_CCER_CC2E; TIMx->CCER &= ~TIM_CCER_CC2E;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Get the TIMx CR2 register value */ /* Get the TIMx CR2 register value */
tmpcr2 = TIMx->CR2; tmpcr2 = TIMx->CR2;
@@ -6941,7 +6954,6 @@ void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, const TIM_OC_InitTypeDef *OC_Config)
tmpccer |= (OC_Config->OCNPolarity << 4U); tmpccer |= (OC_Config->OCNPolarity << 4U);
/* Reset the Output N State */ /* Reset the Output N State */
tmpccer &= ~TIM_CCER_CC2NE; tmpccer &= ~TIM_CCER_CC2NE;
} }
if (IS_TIM_BREAK_INSTANCE(TIMx)) if (IS_TIM_BREAK_INSTANCE(TIMx))
@@ -6984,11 +6996,12 @@ static void TIM_OC3_SetConfig(TIM_TypeDef *TIMx, const TIM_OC_InitTypeDef *OC_Co
uint32_t tmpccer; uint32_t tmpccer;
uint32_t tmpcr2; uint32_t tmpcr2;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Disable the Channel 3: Reset the CC2E Bit */ /* Disable the Channel 3: Reset the CC2E Bit */
TIMx->CCER &= ~TIM_CCER_CC3E; TIMx->CCER &= ~TIM_CCER_CC3E;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Get the TIMx CR2 register value */ /* Get the TIMx CR2 register value */
tmpcr2 = TIMx->CR2; tmpcr2 = TIMx->CR2;
@@ -7058,11 +7071,12 @@ static void TIM_OC4_SetConfig(TIM_TypeDef *TIMx, const TIM_OC_InitTypeDef *OC_Co
uint32_t tmpccer; uint32_t tmpccer;
uint32_t tmpcr2; uint32_t tmpcr2;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Disable the Channel 4: Reset the CC4E Bit */ /* Disable the Channel 4: Reset the CC4E Bit */
TIMx->CCER &= ~TIM_CCER_CC4E; TIMx->CCER &= ~TIM_CCER_CC4E;
/* Get the TIMx CCER register value */
tmpccer = TIMx->CCER;
/* Get the TIMx CR2 register value */ /* Get the TIMx CR2 register value */
tmpcr2 = TIMx->CR2; tmpcr2 = TIMx->CR2;
@@ -7253,9 +7267,9 @@ void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_
uint32_t tmpccer; uint32_t tmpccer;
/* Disable the Channel 1: Reset the CC1E Bit */ /* Disable the Channel 1: Reset the CC1E Bit */
tmpccer = TIMx->CCER;
TIMx->CCER &= ~TIM_CCER_CC1E; TIMx->CCER &= ~TIM_CCER_CC1E;
tmpccmr1 = TIMx->CCMR1; tmpccmr1 = TIMx->CCMR1;
tmpccer = TIMx->CCER;
/* Select the Input */ /* Select the Input */
if (IS_TIM_CC2_INSTANCE(TIMx) != RESET) if (IS_TIM_CC2_INSTANCE(TIMx) != RESET)
@@ -7343,9 +7357,9 @@ static void TIM_TI2_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32
uint32_t tmpccer; uint32_t tmpccer;
/* Disable the Channel 2: Reset the CC2E Bit */ /* Disable the Channel 2: Reset the CC2E Bit */
tmpccer = TIMx->CCER;
TIMx->CCER &= ~TIM_CCER_CC2E; TIMx->CCER &= ~TIM_CCER_CC2E;
tmpccmr1 = TIMx->CCMR1; tmpccmr1 = TIMx->CCMR1;
tmpccer = TIMx->CCER;
/* Select the Input */ /* Select the Input */
tmpccmr1 &= ~TIM_CCMR1_CC2S; tmpccmr1 &= ~TIM_CCMR1_CC2S;
@@ -7382,9 +7396,9 @@ static void TIM_TI2_ConfigInputStage(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity,
uint32_t tmpccer; uint32_t tmpccer;
/* Disable the Channel 2: Reset the CC2E Bit */ /* Disable the Channel 2: Reset the CC2E Bit */
tmpccer = TIMx->CCER;
TIMx->CCER &= ~TIM_CCER_CC2E; TIMx->CCER &= ~TIM_CCER_CC2E;
tmpccmr1 = TIMx->CCMR1; tmpccmr1 = TIMx->CCMR1;
tmpccer = TIMx->CCER;
/* Set the filter */ /* Set the filter */
tmpccmr1 &= ~TIM_CCMR1_IC2F; tmpccmr1 &= ~TIM_CCMR1_IC2F;
@@ -7426,9 +7440,9 @@ static void TIM_TI3_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32
uint32_t tmpccer; uint32_t tmpccer;
/* Disable the Channel 3: Reset the CC3E Bit */ /* Disable the Channel 3: Reset the CC3E Bit */
tmpccer = TIMx->CCER;
TIMx->CCER &= ~TIM_CCER_CC3E; TIMx->CCER &= ~TIM_CCER_CC3E;
tmpccmr2 = TIMx->CCMR2; tmpccmr2 = TIMx->CCMR2;
tmpccer = TIMx->CCER;
/* Select the Input */ /* Select the Input */
tmpccmr2 &= ~TIM_CCMR2_CC3S; tmpccmr2 &= ~TIM_CCMR2_CC3S;
@@ -7474,9 +7488,9 @@ static void TIM_TI4_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32
uint32_t tmpccer; uint32_t tmpccer;
/* Disable the Channel 4: Reset the CC4E Bit */ /* Disable the Channel 4: Reset the CC4E Bit */
tmpccer = TIMx->CCER;
TIMx->CCER &= ~TIM_CCER_CC4E; TIMx->CCER &= ~TIM_CCER_CC4E;
tmpccmr2 = TIMx->CCMR2; tmpccmr2 = TIMx->CCMR2;
tmpccer = TIMx->CCER;
/* Select the Input */ /* Select the Input */
tmpccmr2 &= ~TIM_CCMR2_CC4S; tmpccmr2 &= ~TIM_CCMR2_CC4S;

View File

@@ -836,7 +836,7 @@ HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channe
/* Disable the TIM Break interrupt (only if no more channel is active) */ /* Disable the TIM Break interrupt (only if no more channel is active) */
tmpccer = htim->Instance->CCER; tmpccer = htim->Instance->CCER;
if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) if ((tmpccer & TIM_CCER_CCxNE_MASK) == (uint32_t)RESET)
{ {
__HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK);
} }
@@ -1082,17 +1082,6 @@ HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Chann
(+) Stop the Complementary PWM and disable interrupts. (+) Stop the Complementary PWM and disable interrupts.
(+) Start the Complementary PWM and enable DMA transfers. (+) Start the Complementary PWM and enable DMA transfers.
(+) Stop the Complementary PWM and disable DMA transfers. (+) Stop the Complementary PWM and disable DMA transfers.
(+) Start the Complementary Input Capture measurement.
(+) Stop the Complementary Input Capture.
(+) Start the Complementary Input Capture and enable interrupts.
(+) Stop the Complementary Input Capture and disable interrupts.
(+) Start the Complementary Input Capture and enable DMA transfers.
(+) Stop the Complementary Input Capture and disable DMA transfers.
(+) Start the Complementary One Pulse generation.
(+) Stop the Complementary One Pulse.
(+) Start the Complementary One Pulse and enable interrupts.
(+) Stop the Complementary One Pulse and disable interrupts.
@endverbatim @endverbatim
* @{ * @{
*/ */
@@ -1318,7 +1307,7 @@ HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Chann
/* Disable the TIM Break interrupt (only if no more channel is active) */ /* Disable the TIM Break interrupt (only if no more channel is active) */
tmpccer = htim->Instance->CCER; tmpccer = htim->Instance->CCER;
if ((tmpccer & (TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) == (uint32_t)RESET) if ((tmpccer & TIM_CCER_CCxNE_MASK) == (uint32_t)RESET)
{ {
__HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK); __HAL_TIM_DISABLE_IT(htim, TIM_IT_BREAK);
} }
@@ -2113,7 +2102,7 @@ HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap)
*/ */
/** /**
* @brief Hall commutation changed callback in non-blocking mode * @brief Commutation callback in non-blocking mode
* @param htim TIM handle * @param htim TIM handle
* @retval None * @retval None
*/ */
@@ -2127,7 +2116,7 @@ __weak void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim)
*/ */
} }
/** /**
* @brief Hall commutation changed half complete callback in non-blocking mode * @brief Commutation half complete callback in non-blocking mode
* @param htim TIM handle * @param htim TIM handle
* @retval None * @retval None
*/ */
@@ -2142,7 +2131,7 @@ __weak void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim)
} }
/** /**
* @brief Hall Break detection callback in non-blocking mode * @brief Break detection callback in non-blocking mode
* @param htim TIM handle * @param htim TIM handle
* @retval None * @retval None
*/ */
@@ -2293,15 +2282,6 @@ static void TIM_DMADelayPulseNCplt(DMA_HandleTypeDef *hdma)
TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY); TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_3, HAL_TIM_CHANNEL_STATE_READY);
} }
} }
else if (hdma == htim->hdma[TIM_DMA_ID_CC4])
{
htim->Channel = HAL_TIM_ACTIVE_CHANNEL_4;
if (hdma->Init.Mode == DMA_NORMAL)
{
TIM_CHANNEL_N_STATE_SET(htim, TIM_CHANNEL_4, HAL_TIM_CHANNEL_STATE_READY);
}
}
else else
{ {
/* nothing to do */ /* nothing to do */
@@ -2370,13 +2350,13 @@ static void TIM_CCxNChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Cha
{ {
uint32_t tmp; uint32_t tmp;
tmp = TIM_CCER_CC1NE << (Channel & 0x1FU); /* 0x1FU = 31 bits max shift */ tmp = TIM_CCER_CC1NE << (Channel & 0xFU); /* 0xFU = 15 bits max shift */
/* Reset the CCxNE Bit */ /* Reset the CCxNE Bit */
TIMx->CCER &= ~tmp; TIMx->CCER &= ~tmp;
/* Set or reset the CCxNE Bit */ /* Set or reset the CCxNE Bit */
TIMx->CCER |= (uint32_t)(ChannelNState << (Channel & 0x1FU)); /* 0x1FU = 31 bits max shift */ TIMx->CCER |= (uint32_t)(ChannelNState << (Channel & 0xFU)); /* 0xFU = 15 bits max shift */
} }
/** /**
* @} * @}

View File

@@ -105,7 +105,7 @@
[..] [..]
Use function HAL_UART_UnRegisterCallback() to reset a callback to the default Use function HAL_UART_UnRegisterCallback() to reset a callback to the default
weak (surcharged) function. weak function.
HAL_UART_UnRegisterCallback() takes as parameters the HAL peripheral handle, HAL_UART_UnRegisterCallback() takes as parameters the HAL peripheral handle,
and the Callback ID. and the Callback ID.
This function allows to reset following callbacks: This function allows to reset following callbacks:
@@ -127,10 +127,10 @@
[..] [..]
By default, after the HAL_UART_Init() and when the state is HAL_UART_STATE_RESET By default, after the HAL_UART_Init() and when the state is HAL_UART_STATE_RESET
all callbacks are set to the corresponding weak (surcharged) functions: all callbacks are set to the corresponding weak functions:
examples HAL_UART_TxCpltCallback(), HAL_UART_RxHalfCpltCallback(). examples HAL_UART_TxCpltCallback(), HAL_UART_RxHalfCpltCallback().
Exception done for MspInit and MspDeInit functions that are respectively Exception done for MspInit and MspDeInit functions that are respectively
reset to the legacy weak (surcharged) functions in the HAL_UART_Init() reset to the legacy weak functions in the HAL_UART_Init()
and HAL_UART_DeInit() only when these callbacks are null (not registered beforehand). and HAL_UART_DeInit() only when these callbacks are null (not registered beforehand).
If not, MspInit or MspDeInit are not null, the HAL_UART_Init() and HAL_UART_DeInit() If not, MspInit or MspDeInit are not null, the HAL_UART_Init() and HAL_UART_DeInit()
keep and use the user MspInit/MspDeInit callbacks (registered beforehand). keep and use the user MspInit/MspDeInit callbacks (registered beforehand).
@@ -147,7 +147,7 @@
[..] [..]
When The compilation define USE_HAL_UART_REGISTER_CALLBACKS is set to 0 or When The compilation define USE_HAL_UART_REGISTER_CALLBACKS is set to 0 or
not defined, the callback registration feature is not available not defined, the callback registration feature is not available
and weak (surcharged) callbacks are used. and weak callbacks are used.
@endverbatim @endverbatim
@@ -191,8 +191,8 @@
/** @addtogroup UART_Private_Functions /** @addtogroup UART_Private_Functions
* @{ * @{
*/ */
static void UART_EndTxTransfer(UART_HandleTypeDef *huart);
static void UART_EndRxTransfer(UART_HandleTypeDef *huart); static void UART_EndRxTransfer(UART_HandleTypeDef *huart);
static void UART_EndTxTransfer(UART_HandleTypeDef *huart);
static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma); static void UART_DMATransmitCplt(DMA_HandleTypeDef *hdma);
static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma); static void UART_DMAReceiveCplt(DMA_HandleTypeDef *hdma);
static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma); static void UART_DMARxHalfCplt(DMA_HandleTypeDef *hdma);
@@ -330,17 +330,19 @@ HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart)
__HAL_UART_DISABLE(huart); __HAL_UART_DISABLE(huart);
/* Perform advanced settings configuration */
/* For some items, configuration requires to be done prior TE and RE bits are set */
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Set the UART Communication parameters */ /* Set the UART Communication parameters */
if (UART_SetConfig(huart) == HAL_ERROR) if (UART_SetConfig(huart) == HAL_ERROR)
{ {
return HAL_ERROR; return HAL_ERROR;
} }
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* In asynchronous mode, the following bits must be kept cleared: /* In asynchronous mode, the following bits must be kept cleared:
- LINEN (if LIN is supported) and CLKEN bits in the USART_CR2 register, - LINEN (if LIN is supported) and CLKEN bits in the USART_CR2 register,
- SCEN (if Smartcard is supported), HDSEL and IREN (if IrDA is supported) bits in the USART_CR3 register.*/ - SCEN (if Smartcard is supported), HDSEL and IREN (if IrDA is supported) bits in the USART_CR3 register.*/
@@ -411,17 +413,19 @@ HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart)
__HAL_UART_DISABLE(huart); __HAL_UART_DISABLE(huart);
/* Perform advanced settings configuration */
/* For some items, configuration requires to be done prior TE and RE bits are set */
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Set the UART Communication parameters */ /* Set the UART Communication parameters */
if (UART_SetConfig(huart) == HAL_ERROR) if (UART_SetConfig(huart) == HAL_ERROR)
{ {
return HAL_ERROR; return HAL_ERROR;
} }
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* In half-duplex mode, the following bits must be kept cleared: /* In half-duplex mode, the following bits must be kept cleared:
- LINEN (if LIN is supported) and CLKEN bits in the USART_CR2 register, - LINEN (if LIN is supported) and CLKEN bits in the USART_CR2 register,
- SCEN (if Smartcard is supported) and IREN (if IrDA is supported) bits in the USART_CR3 register.*/ - SCEN (if Smartcard is supported) and IREN (if IrDA is supported) bits in the USART_CR3 register.*/
@@ -512,17 +516,19 @@ HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLe
__HAL_UART_DISABLE(huart); __HAL_UART_DISABLE(huart);
/* Perform advanced settings configuration */
/* For some items, configuration requires to be done prior TE and RE bits are set */
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Set the UART Communication parameters */ /* Set the UART Communication parameters */
if (UART_SetConfig(huart) == HAL_ERROR) if (UART_SetConfig(huart) == HAL_ERROR)
{ {
return HAL_ERROR; return HAL_ERROR;
} }
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* In LIN mode, the following bits must be kept cleared: /* In LIN mode, the following bits must be kept cleared:
- LINEN and CLKEN bits in the USART_CR2 register, - LINEN and CLKEN bits in the USART_CR2 register,
- SCEN(if Smartcard is supported) and IREN(if IrDA is supported) bits in the USART_CR3 register.*/ - SCEN(if Smartcard is supported) and IREN(if IrDA is supported) bits in the USART_CR3 register.*/
@@ -609,17 +615,19 @@ HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Add
__HAL_UART_DISABLE(huart); __HAL_UART_DISABLE(huart);
/* Perform advanced settings configuration */
/* For some items, configuration requires to be done prior TE and RE bits are set */
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Set the UART Communication parameters */ /* Set the UART Communication parameters */
if (UART_SetConfig(huart) == HAL_ERROR) if (UART_SetConfig(huart) == HAL_ERROR)
{ {
return HAL_ERROR; return HAL_ERROR;
} }
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* In multiprocessor mode, the following bits must be kept cleared: /* In multiprocessor mode, the following bits must be kept cleared:
- LINEN (if LIN is supported) and CLKEN bits in the USART_CR2 register, - LINEN (if LIN is supported) and CLKEN bits in the USART_CR2 register,
- SCEN (if Smartcard is supported), HDSEL and IREN (if IrDA is supported) bits in the USART_CR3 register. */ - SCEN (if Smartcard is supported), HDSEL and IREN (if IrDA is supported) bits in the USART_CR3 register. */
@@ -738,7 +746,7 @@ __weak void HAL_UART_MspDeInit(UART_HandleTypeDef *huart)
#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) #if (USE_HAL_UART_REGISTER_CALLBACKS == 1)
/** /**
* @brief Register a User UART Callback * @brief Register a User UART Callback
* To be used instead of the weak predefined callback * To be used to override the weak predefined callback
* @note The HAL_UART_RegisterCallback() may be called before HAL_UART_Init(), HAL_HalfDuplex_Init(), * @note The HAL_UART_RegisterCallback() may be called before HAL_UART_Init(), HAL_HalfDuplex_Init(),
* HAL_LIN_Init(), HAL_MultiProcessor_Init() or HAL_RS485Ex_Init() in HAL_UART_STATE_RESET to register * HAL_LIN_Init(), HAL_MultiProcessor_Init() or HAL_RS485Ex_Init() in HAL_UART_STATE_RESET to register
* callbacks for HAL_UART_MSPINIT_CB_ID and HAL_UART_MSPDEINIT_CB_ID * callbacks for HAL_UART_MSPINIT_CB_ID and HAL_UART_MSPDEINIT_CB_ID
@@ -994,10 +1002,7 @@ HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pU
return HAL_ERROR; return HAL_ERROR;
} }
/* Process locked */ if (huart->RxState == HAL_UART_STATE_READY)
__HAL_LOCK(huart);
if (huart->gState == HAL_UART_STATE_READY)
{ {
huart->RxEventCallback = pCallback; huart->RxEventCallback = pCallback;
} }
@@ -1008,9 +1013,6 @@ HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pU
status = HAL_ERROR; status = HAL_ERROR;
} }
/* Release Lock */
__HAL_UNLOCK(huart);
return status; return status;
} }
@@ -1024,10 +1026,7 @@ HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart)
{ {
HAL_StatusTypeDef status = HAL_OK; HAL_StatusTypeDef status = HAL_OK;
/* Process locked */ if (huart->RxState == HAL_UART_STATE_READY)
__HAL_LOCK(huart);
if (huart->gState == HAL_UART_STATE_READY)
{ {
huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak UART Rx Event Callback */ huart->RxEventCallback = HAL_UARTEx_RxEventCallback; /* Legacy weak UART Rx Event Callback */
} }
@@ -1038,8 +1037,6 @@ HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart)
status = HAL_ERROR; status = HAL_ERROR;
} }
/* Release Lock */
__HAL_UNLOCK(huart);
return status; return status;
} }
@@ -3180,6 +3177,13 @@ void UART_AdvFeatureConfig(UART_HandleTypeDef *huart)
/* Check whether the set of advanced features to configure is properly set */ /* Check whether the set of advanced features to configure is properly set */
assert_param(IS_UART_ADVFEATURE_INIT(huart->AdvancedInit.AdvFeatureInit)); assert_param(IS_UART_ADVFEATURE_INIT(huart->AdvancedInit.AdvFeatureInit));
/* if required, configure RX/TX pins swap */
if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_SWAP_INIT))
{
assert_param(IS_UART_ADVFEATURE_SWAP(huart->AdvancedInit.Swap));
MODIFY_REG(huart->Instance->CR2, USART_CR2_SWAP, huart->AdvancedInit.Swap);
}
/* if required, configure TX pin active level inversion */ /* if required, configure TX pin active level inversion */
if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_TXINVERT_INIT)) if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_TXINVERT_INIT))
{ {
@@ -3201,13 +3205,6 @@ void UART_AdvFeatureConfig(UART_HandleTypeDef *huart)
MODIFY_REG(huart->Instance->CR2, USART_CR2_DATAINV, huart->AdvancedInit.DataInvert); MODIFY_REG(huart->Instance->CR2, USART_CR2_DATAINV, huart->AdvancedInit.DataInvert);
} }
/* if required, configure RX/TX pins swap */
if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_SWAP_INIT))
{
assert_param(IS_UART_ADVFEATURE_SWAP(huart->AdvancedInit.Swap));
MODIFY_REG(huart->Instance->CR2, USART_CR2_SWAP, huart->AdvancedInit.Swap);
}
/* if required, configure RX overrun detection disabling */ /* if required, configure RX overrun detection disabling */
if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_RXOVERRUNDISABLE_INIT)) if (HAL_IS_BIT_SET(huart->AdvancedInit.AdvFeatureInit, UART_ADVFEATURE_RXOVERRUNDISABLE_INIT))
{ {
@@ -3333,24 +3330,24 @@ HAL_StatusTypeDef UART_WaitOnFlagUntilTimeout(UART_HandleTypeDef *huart, uint32_
return HAL_TIMEOUT; return HAL_TIMEOUT;
} }
if (READ_BIT(huart->Instance->CR1, USART_CR1_RE) != 0U) if ((READ_BIT(huart->Instance->CR1, USART_CR1_RE) != 0U) && (Flag != UART_FLAG_TXE) && (Flag != UART_FLAG_TC))
{ {
if (__HAL_UART_GET_FLAG(huart, UART_FLAG_ORE) == SET) if (__HAL_UART_GET_FLAG(huart, UART_FLAG_ORE) == SET)
{ {
/* Clear Overrun Error flag*/ /* Clear Overrun Error flag*/
__HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_OREF); __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_OREF);
/* Blocking error : transfer is aborted /* Blocking error : transfer is aborted
Set the UART state ready to be able to start again the process, Set the UART state ready to be able to start again the process,
Disable Rx Interrupts if ongoing */ Disable Rx Interrupts if ongoing */
UART_EndRxTransfer(huart); UART_EndRxTransfer(huart);
huart->ErrorCode = HAL_UART_ERROR_ORE; huart->ErrorCode = HAL_UART_ERROR_ORE;
/* Process Unlocked */ /* Process Unlocked */
__HAL_UNLOCK(huart); __HAL_UNLOCK(huart);
return HAL_ERROR; return HAL_ERROR;
} }
if (__HAL_UART_GET_FLAG(huart, UART_FLAG_RTOF) == SET) if (__HAL_UART_GET_FLAG(huart, UART_FLAG_RTOF) == SET)
{ {

View File

@@ -195,17 +195,19 @@ HAL_StatusTypeDef HAL_RS485Ex_Init(UART_HandleTypeDef *huart, uint32_t Polarity,
/* Disable the Peripheral */ /* Disable the Peripheral */
__HAL_UART_DISABLE(huart); __HAL_UART_DISABLE(huart);
/* Perform advanced settings configuration */
/* For some items, configuration requires to be done prior TE and RE bits are set */
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Set the UART Communication parameters */ /* Set the UART Communication parameters */
if (UART_SetConfig(huart) == HAL_ERROR) if (UART_SetConfig(huart) == HAL_ERROR)
{ {
return HAL_ERROR; return HAL_ERROR;
} }
if (huart->AdvancedInit.AdvFeatureInit != UART_ADVFEATURE_NO_INIT)
{
UART_AdvFeatureConfig(huart);
}
/* Enable the Driver Enable mode by setting the DEM bit in the CR3 register */ /* Enable the Driver Enable mode by setting the DEM bit in the CR3 register */
SET_BIT(huart->Instance->CR3, USART_CR3_DEM); SET_BIT(huart->Instance->CR3, USART_CR3_DEM);
@@ -634,7 +636,7 @@ HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *p
*/ */
HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size) HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size)
{ {
HAL_StatusTypeDef status; HAL_StatusTypeDef status = HAL_OK;
/* Check that a Rx process is not already ongoing */ /* Check that a Rx process is not already ongoing */
if (huart->RxState == HAL_UART_STATE_READY) if (huart->RxState == HAL_UART_STATE_READY)
@@ -659,24 +661,20 @@ HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t
huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE; huart->ReceptionType = HAL_UART_RECEPTION_TOIDLE;
huart->RxEventType = HAL_UART_RXEVENT_TC; huart->RxEventType = HAL_UART_RXEVENT_TC;
status = UART_Start_Receive_IT(huart, pData, Size); (void)UART_Start_Receive_IT(huart, pData, Size);
/* Check Rx process has been successfully started */ if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE)
if (status == HAL_OK)
{ {
if (huart->ReceptionType == HAL_UART_RECEPTION_TOIDLE) __HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_IDLEF);
{ ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE);
__HAL_UART_CLEAR_FLAG(huart, UART_CLEAR_IDLEF); }
ATOMIC_SET_BIT(huart->Instance->CR1, USART_CR1_IDLEIE); else
} {
else /* In case of errors already pending when reception is started,
{ Interrupts may have already been raised and lead to reception abortion.
/* In case of errors already pending when reception is started, (Overrun error for instance).
Interrupts may have already been raised and lead to reception abortion. In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */
(Overrun error for instance). status = HAL_ERROR;
In such case Reception Type has been reset to HAL_UART_RECEPTION_STANDARD. */
status = HAL_ERROR;
}
} }
return status; return status;
@@ -788,7 +786,7 @@ HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_
* @param huart UART handle. * @param huart UART handle.
* @retval Rx Event Type (return vale will be a value of @ref UART_RxEvent_Type_Values) * @retval Rx Event Type (return vale will be a value of @ref UART_RxEvent_Type_Values)
*/ */
HAL_UART_RxEventTypeTypeDef HAL_UARTEx_GetRxEventType(UART_HandleTypeDef *huart) HAL_UART_RxEventTypeTypeDef HAL_UARTEx_GetRxEventType(const UART_HandleTypeDef *huart)
{ {
/* Return Rx Event type value, as stored in UART handle */ /* Return Rx Event type value, as stored in UART handle */
return (huart->RxEventType); return (huart->RxEventType);

View File

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

View File

@@ -24,7 +24,7 @@ Dma.USART1_TX.1.PeriphInc=DMA_PINC_DISABLE
Dma.USART1_TX.1.Priority=DMA_PRIORITY_LOW Dma.USART1_TX.1.Priority=DMA_PRIORITY_LOW
Dma.USART1_TX.1.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority Dma.USART1_TX.1.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority
File.Version=6 File.Version=6
GPIO.groupedBy= GPIO.groupedBy=Group By Peripherals
KeepUserPlacement=false KeepUserPlacement=false
Mcu.CPN=STM32F030K6T6 Mcu.CPN=STM32F030K6T6
Mcu.Family=STM32F0 Mcu.Family=STM32F0
@@ -34,33 +34,43 @@ Mcu.IP2=RCC
Mcu.IP3=SYS Mcu.IP3=SYS
Mcu.IP4=TIM1 Mcu.IP4=TIM1
Mcu.IP5=TIM3 Mcu.IP5=TIM3
Mcu.IP6=USART1 Mcu.IP6=TIM14
Mcu.IPNb=7 Mcu.IP7=USART1
Mcu.IPNb=8
Mcu.Name=STM32F030K6Tx Mcu.Name=STM32F030K6Tx
Mcu.Package=LQFP32 Mcu.Package=LQFP32
Mcu.Pin0=PF0-OSC_IN Mcu.Pin0=PF0-OSC_IN
Mcu.Pin1=PF1-OSC_OUT Mcu.Pin1=PF1-OSC_OUT
Mcu.Pin10=PA14 Mcu.Pin10=PA8
Mcu.Pin11=PA15 Mcu.Pin11=PA9
Mcu.Pin12=PB3 Mcu.Pin12=PA10
Mcu.Pin13=PB4 Mcu.Pin13=PA11
Mcu.Pin14=VP_SYS_VS_Systick Mcu.Pin14=PA13
Mcu.Pin15=VP_TIM1_VS_ClockSourceINT Mcu.Pin15=PA14
Mcu.Pin2=PA6 Mcu.Pin16=PA15
Mcu.Pin3=PA7 Mcu.Pin17=PB3
Mcu.Pin4=PB0 Mcu.Pin18=PB4
Mcu.Pin5=PB1 Mcu.Pin19=PB5
Mcu.Pin6=PA9 Mcu.Pin2=PA0
Mcu.Pin7=PA10 Mcu.Pin20=VP_SYS_VS_Systick
Mcu.Pin8=PA11 Mcu.Pin21=VP_TIM1_VS_ClockSourceINT
Mcu.Pin9=PA13 Mcu.Pin22=VP_TIM14_VS_ClockSourceINT
Mcu.PinsNb=16 Mcu.Pin3=PA1
Mcu.Pin4=PA4
Mcu.Pin5=PA5
Mcu.Pin6=PA6
Mcu.Pin7=PA7
Mcu.Pin8=PB0
Mcu.Pin9=PB1
Mcu.PinsNb=23
Mcu.ThirdPartyNb=0 Mcu.ThirdPartyNb=0
Mcu.UserConstants= Mcu.UserConstants=
Mcu.UserName=STM32F030K6Tx Mcu.UserName=STM32F030K6Tx
MxCube.Version=6.9.2 MxCube.Version=6.11.1
MxDb.Version=DB.6.0.92 MxDb.Version=DB.6.0.111
NVIC.DMA1_Channel2_3_IRQn=true\:2\:0\:true\:false\:true\:false\:true\:true NVIC.DMA1_Channel2_3_IRQn=true\:2\:0\:true\:false\:true\:false\:true\:true
NVIC.EXTI0_1_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.EXTI4_15_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.ForceEnableDMAVector=true NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
@@ -70,6 +80,16 @@ NVIC.SysTick_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:false
NVIC.TIM1_BRK_UP_TRG_COM_IRQn=true\:3\:0\:true\:false\:true\:true\:true\:true NVIC.TIM1_BRK_UP_TRG_COM_IRQn=true\:3\:0\:true\:false\:true\:true\:true\:true
NVIC.TIM1_CC_IRQn=true\:3\:0\:true\:false\:true\:true\:true\:true NVIC.TIM1_CC_IRQn=true\:3\:0\:true\:false\:true\:true\:true\:true
NVIC.USART1_IRQn=true\:1\:0\:true\:false\:true\:true\:true\:true NVIC.USART1_IRQn=true\:1\:0\:true\:false\:true\:true\:true\:true
PA0.GPIOParameters=GPIO_Label,GPIO_ModeDefaultEXTI
PA0.GPIO_Label=WATER
PA0.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_RISING_FALLING
PA0.Locked=true
PA0.Signal=GPXTI0
PA1.GPIOParameters=GPIO_Label,GPIO_ModeDefaultEXTI
PA1.GPIO_Label=ESTOP
PA1.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_FALLING
PA1.Locked=true
PA1.Signal=GPXTI1
PA10.Locked=true PA10.Locked=true
PA10.Mode=Asynchronous PA10.Mode=Asynchronous
PA10.Signal=USART1_RX PA10.Signal=USART1_RX
@@ -85,6 +105,14 @@ PA15.GPIOParameters=GPIO_Label
PA15.GPIO_Label=RL_AUX PA15.GPIO_Label=RL_AUX
PA15.Locked=true PA15.Locked=true
PA15.Signal=GPIO_Output PA15.Signal=GPIO_Output
PA4.GPIOParameters=GPIO_Label
PA4.GPIO_Label=LIGHTS
PA4.Signal=S_TIM14_CH1
PA5.GPIOParameters=PinState,GPIO_Label
PA5.GPIO_Label=RL_EN
PA5.Locked=true
PA5.PinState=GPIO_PIN_SET
PA5.Signal=GPIO_Output
PA6.GPIOParameters=GPIO_Label PA6.GPIOParameters=GPIO_Label
PA6.GPIO_Label=LED_AUX PA6.GPIO_Label=LED_AUX
PA6.Locked=true PA6.Locked=true
@@ -93,6 +121,11 @@ PA7.GPIOParameters=GPIO_Label
PA7.GPIO_Label=LED_MAIN PA7.GPIO_Label=LED_MAIN
PA7.Locked=true PA7.Locked=true
PA7.Signal=GPIO_Output PA7.Signal=GPIO_Output
PA8.GPIOParameters=GPIO_Label,GPIO_ModeDefaultEXTI
PA8.GPIO_Label=LIGHTS_SW
PA8.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_FALLING
PA8.Locked=true
PA8.Signal=GPXTI8
PA9.Locked=true PA9.Locked=true
PA9.Mode=Asynchronous PA9.Mode=Asynchronous
PA9.Signal=USART1_TX PA9.Signal=USART1_TX
@@ -104,12 +137,14 @@ PB1.GPIOParameters=GPIO_Label
PB1.GPIO_Label=LED_ACT PB1.GPIO_Label=LED_ACT
PB1.Locked=true PB1.Locked=true
PB1.Signal=GPIO_Output PB1.Signal=GPIO_Output
PB3.GPIOParameters=GPIO_Label PB3.GPIOParameters=GPIO_PuPd,GPIO_Label
PB3.GPIO_Label=RL_MAIN PB3.GPIO_Label=RL_MAIN
PB3.GPIO_PuPd=GPIO_NOPULL
PB3.Locked=true PB3.Locked=true
PB3.Signal=GPIO_Output PB3.Signal=GPIO_Output
PB4.Locked=true PB4.Locked=true
PB4.Signal=S_TIM3_CH1 PB4.Signal=S_TIM3_CH1
PB5.Signal=S_TIM3_CH2
PF0-OSC_IN.Mode=HSE-External-Oscillator PF0-OSC_IN.Mode=HSE-External-Oscillator
PF0-OSC_IN.Signal=RCC_OSC_IN PF0-OSC_IN.Signal=RCC_OSC_IN
PF1-OSC_OUT.Mode=HSE-External-Oscillator PF1-OSC_OUT.Mode=HSE-External-Oscillator
@@ -124,7 +159,7 @@ ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F030K6Tx ProjectManager.DeviceId=STM32F030K6Tx
ProjectManager.FirmwarePackage=STM32Cube FW_F0 V1.11.4 ProjectManager.FirmwarePackage=STM32Cube FW_F0 V1.11.5
ProjectManager.FreePins=false ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200 ProjectManager.HeapSize=0x200
@@ -135,8 +170,8 @@ ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=STM32CubeIDE ProjectManager.PreviousToolchain=STM32CubeIDE
ProjectManager.ProjectBuild=false ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=Relay_RS485.ioc ProjectManager.ProjectFileName=Relay_RS485_V2.ioc
ProjectManager.ProjectName=Relay_RS485 ProjectManager.ProjectName=Relay_RS485_V2
ProjectManager.ProjectStructure= ProjectManager.ProjectStructure=
ProjectManager.RegisterCallBack= ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400 ProjectManager.StackSize=0x400
@@ -145,7 +180,7 @@ ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath= ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath= ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=true ProjectManager.UnderRoot=true
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_TIM3_Init-TIM3-false-HAL-true,5-MX_USART1_UART_Init-USART1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_TIM3_Init-TIM3-false-HAL-true,5-MX_USART1_UART_Init-USART1-false-HAL-true,6-MX_TIM1_Init-TIM1-false-HAL-true,7-MX_TIM14_Init-TIM14-false-HAL-true
RCC.AHBFreq_Value=48000000 RCC.AHBFreq_Value=48000000
RCC.APB1Freq_Value=48000000 RCC.APB1Freq_Value=48000000
RCC.APB1TimFreq_Value=48000000 RCC.APB1TimFreq_Value=48000000
@@ -163,20 +198,38 @@ RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.TimSysFreq_Value=48000000 RCC.TimSysFreq_Value=48000000
RCC.USART1Freq_Value=48000000 RCC.USART1Freq_Value=48000000
RCC.VCOOutput2Freq_Value=8000000 RCC.VCOOutput2Freq_Value=8000000
SH.GPXTI0.0=GPIO_EXTI0
SH.GPXTI0.ConfNb=1
SH.GPXTI1.0=GPIO_EXTI1
SH.GPXTI1.ConfNb=1
SH.GPXTI8.0=GPIO_EXTI8
SH.GPXTI8.ConfNb=1
SH.S_TIM14_CH1.0=TIM14_CH1,PWM Generation1 CH1
SH.S_TIM14_CH1.ConfNb=1
SH.S_TIM3_CH1.0=TIM3_CH1,PWM Generation1 CH1 SH.S_TIM3_CH1.0=TIM3_CH1,PWM Generation1 CH1
SH.S_TIM3_CH1.ConfNb=1 SH.S_TIM3_CH1.ConfNb=1
SH.S_TIM3_CH2.0=TIM3_CH2,PWM Generation2 CH2
SH.S_TIM3_CH2.ConfNb=1
TIM1.IPParameters=Prescaler,Period TIM1.IPParameters=Prescaler,Period
TIM1.Period=100 TIM1.Period=100-1
TIM1.Prescaler=479 TIM1.Prescaler=480-1
TIM14.Channel=TIM_CHANNEL_1
TIM14.IPParameters=Channel,Prescaler,Period,OCMode_PWM
TIM14.OCMode_PWM=TIM_OCMODE_PWM1
TIM14.Period=255-1
TIM14.Prescaler=6-1
TIM3.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1 TIM3.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM3.IPParameters=Channel-PWM Generation1 CH1,Prescaler,Period TIM3.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM3.Period=255 TIM3.IPParameters=Channel-PWM Generation1 CH1,Prescaler,Period,Channel-PWM Generation2 CH2
TIM3.Prescaler=239 TIM3.Period=255-1
TIM3.Prescaler=240-1
USART1.BaudRate=9600 USART1.BaudRate=9600
USART1.IPParameters=VirtualMode-Asynchronous,BaudRate USART1.IPParameters=VirtualMode-Asynchronous,BaudRate
USART1.VirtualMode-Asynchronous=VM_ASYNC USART1.VirtualMode-Asynchronous=VM_ASYNC
VP_SYS_VS_Systick.Mode=SysTick VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick VP_SYS_VS_Systick.Signal=SYS_VS_Systick
VP_TIM14_VS_ClockSourceINT.Mode=Enable_Timer
VP_TIM14_VS_ClockSourceINT.Signal=TIM14_VS_ClockSourceINT
VP_TIM1_VS_ClockSourceINT.Mode=Internal VP_TIM1_VS_ClockSourceINT.Mode=Internal
VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT
board=custom board=custom

12
V1-V2_HW_changes.txt Normal file
View File

@@ -0,0 +1,12 @@
New in Relay_V2 MCU:
PA0 - INPUT - Water level (HIGH - we have water)
PA1 - INPUT - E-STOP button (HIGH - normal state. should be interrupt-driven on falling edge detection)
PA2 \
PA3 ---------- Test points TP4, TP5 (ADC / USART1 / GPIO)
PA4 - OUTPUT - LED Lights TIM14 CH1 PWM output
PA5 - OUTPUT - RL_EN. Sets E-STOP trigger to controllable state (resets to normal state). LOW to activate. Should be HIGH by default.
PA8 - INPUT - LED Lights switch
PB5 - OUTPUT - Second DC motor channel. TIM3 CH2 PWM
PB6 \
PB7 ---------- Test points TP1, TP2 (USART1, I2C1, GPIO)